diff --git a/.docker/noetic/vnc_startup.sh b/.docker/noetic/vnc_startup.sh
old mode 100755
new mode 100644
diff --git a/assets/behavior_metrics_paper_behavior_metrics_full_architecture.png b/assets/behavior_metrics_paper_behavior_metrics_full_architecture.png
deleted file mode 100644
index 951b4aed..00000000
Binary files a/assets/behavior_metrics_paper_behavior_metrics_full_architecture.png and /dev/null differ
diff --git a/assets/behavior_metrics_paper_behavior_metrics_gui.png b/assets/behavior_metrics_paper_behavior_metrics_gui.png
deleted file mode 100644
index b520e85a..00000000
Binary files a/assets/behavior_metrics_paper_behavior_metrics_gui.png and /dev/null differ
diff --git a/assets/behavior_metrics_paper_headless.png b/assets/behavior_metrics_paper_headless.png
deleted file mode 100644
index 71ec6838..00000000
Binary files a/assets/behavior_metrics_paper_headless.png and /dev/null differ
diff --git a/assets/behavior_metrics_paper_robot_controller.png b/assets/behavior_metrics_paper_robot_controller.png
deleted file mode 100644
index 03e4ccdb..00000000
Binary files a/assets/behavior_metrics_paper_robot_controller.png and /dev/null differ
diff --git a/assets/behavior_metrics_publish_subscribe.png b/assets/behavior_metrics_publish_subscribe.png
deleted file mode 100644
index f0f2133c..00000000
Binary files a/assets/behavior_metrics_publish_subscribe.png and /dev/null differ
diff --git a/assets/images/behavior_metrics_full_architecture.png b/assets/images/behavior_metrics_full_architecture.png
deleted file mode 100644
index d69552c0..00000000
Binary files a/assets/images/behavior_metrics_full_architecture.png and /dev/null differ
diff --git a/behavior_metrics/Crypto b/behavior_metrics/Crypto
deleted file mode 120000
index 70cfa75a..00000000
--- a/behavior_metrics/Crypto
+++ /dev/null
@@ -1 +0,0 @@
-Cryptodome
\ No newline at end of file
diff --git a/behavior_metrics/Crypto b/behavior_metrics/Crypto
new file mode 100644
index 00000000..70cfa75a
--- /dev/null
+++ b/behavior_metrics/Crypto
@@ -0,0 +1 @@
+Cryptodome
\ No newline at end of file
diff --git a/behavior_metrics/README.md b/behavior_metrics/README.md
index 38aa788a..ff3cb094 100644
--- a/behavior_metrics/README.md
+++ b/behavior_metrics/README.md
@@ -1,219 +1,219 @@
-
-
-# [DEPRECATED] Behavior Metrics Library
-
-## **Please don't use this README since it's outdated. Checkout current [website](https://jderobot.github.io/BehaviorMetrics/)**
-
-
-- [Usage](#usage)
-- [Dataset](#datasets)
-- [Models](#models)
-- [Solutions](#solutions)
- - [Manual Solution](#manual-solution)
- - [Classification Network](#classification-network)
- - [Regression Network](#regression-network)
-- [FAQ](#faq)
-
-The objective of this project is to **take images** from the camera on a circuit where the mission is to follow a red line to complete a lap of the circuit **using classification and regression neural networks**.
-
-## Info
-
-- More detailed info at my [Github-pages](https://roboticslaburjc.github.io/2017-tfm-vanessa-fernandez/).
-
-
-## Datasets
-
-There are currently **two sets** of data to train the neural network that resolves the circuit. One contains **images of all types** such as straights and curves and the other contains **only the curves** of the circuit. The second one is smaller and the results are good enough to solve a lap of the circuit.
-
-- [Complete dataset](http://wiki.jderobot.org/store/jmplaza/uploads/deeplearning-datasets/vision-based-end2end-learning/complete_dataset.zip).
-- [Curve dataset](http://wiki.jderobot.org/store/jmplaza/uploads/deeplearning-datasets/vision-based-end2end-learning/curves_only.zip).
-
-## Models
-
-The models used in this repository are the following:
-
-| Model | Links | Image |
-| ------------------------- | ------------------------------------------------------------ | ----------------------------------------------------------- |
-| PilotNet | [Paper](https://arxiv.org/pdf/1704.07911.pdf). [Nvidia source.](https://devblogs.nvidia.com/explaining-deep-learning-self-driving-car/) | [Structure](./docs/imgs/model_pilotnet.png) |
-| TinyPilotNet | [Javier del Egido Sierra](https://ebuah.uah.es/dspace/bitstream/handle/10017/33946/TFG_Egido_Sierra_2018.pdf?sequence=1&isAllowed=y) TFG's. | - |
-| LSTM | [Info](https://colah.github.io/posts/2015-08-Understanding-LSTMs/) | - |
-| LSTM TinyPilotNet | - | [Structure](./docs/imgs/model_lstm_tinypilotnet.png) |
-| Deepest LSTM TinyPilotNet | [Javier del Egido Sierra](https://ebuah.uah.es/dspace/bitstream/handle/10017/33946/TFG_Egido_Sierra_2018.pdf?sequence=1&isAllowed=y) TFG's. | [Structure](./docs/imgs/model_deepestlstm_tinypilotnet.png) |
-| ControlNet | - | [Structure](./docs/imgs/model_controlnet.png) |
-| Stacked | - | [Structure](./docs/imgs/model_stacked.png) |
-| Stacked Dif or Temporal | - | - |
-
-The models are available in the [following repository](http://wiki.jderobot.org/store/jmplaza/uploads/deeplearning-models/models.zip).
-
-
-## Installation
-
-- First of all, we need to **install the JdeRobot environment** packages. We need two packages: [JdeRobot-base](https://github.com/JdeRobot/base) and [JdeRobot-assets](https://github.com/JdeRobot/assets). You can follow [this tutorial](https://github.com/JdeRobot/base#getting-environment-ready) for the complete installation.
-
-- Install ROS plugins typing:
-
- ```bash
- sudo apt install ros-melodic-gazebo-plugins
- ```
-
-- Clone the repository :
-
- ```bash
- git clone https://github.com/RoboticsLabURJC/2017-tfm-vanessa-fernandez.git
- ```
-
-- Create and activate a virtual environment:
-
- ```bash
- virtualenv -p python2.7 --system-site-packages neural_behavior_env
- ```
-
-- Install `requirements`:
-
- ```bash
- pip install -r requirements.txt
- ```
-
-- Launch Gazebo with the F1 world through the command:
-
- ```bash
- roslaunch /opt/jderobot/share/jderobot/gazebo/launch/f1_1_simplecircuit.launch
- ```
-
-- Then you have to execute the application, which will incorporate your code:
-
- ```bash
- python2 driver.py driver.yml
- ```
-
-
-## Usage
-
-### 1. Manual Solution
-
-For this solution, the **code developed in the robotics course of the Official Master's Degree** in **Computer Vision** has been used. The structure of the project allows to combine between the different solutions. As a first approach, the one developed manually by a student or user is used.
-
-An excerpt of the solution can be seen in the following gif:
-
-
-
-
-
-### 2. Classification Network
-
-The solution using **classification networks** leaves a somewhat slower solution than the manual solution but equally useful. A piece of the solution can be seen in the following gif.
-
-
-
-Depending on the type of network you want to run (normal or cropped) you have to change the size of the images entering the network in the `ckassification_network.py` file.
-
-For **cropped images**, the values are:
-
-```python
-. . .
-self.img_height = 60
-self.img_width = 160
-. . .
-```
-
-You also need to change the predict method to configure it to the image type:
-
-```python
-def predict(self):
- input_image = self.camera.getImage()
- # Preprocessing
- img = cv2.cvtColor(input_image.data[240:480, 0:640], cv2.COLOR_RGB2BGR)
- . . .
-```
-
-For **normal images**, the default value is:
-
-```python
-. . .
-self.img_height = 120
-. . .
-```
-
-The `predict` method is the same but without cropping the image:
-
-```python
-def predict(self):
- input_image = self.camera.getImage()
- # Preprocessing
- img = cv2.cvtColor(input_image.data, cv2.COLOR_RGB2BGR)
- . . .
-```
-
-In the same file you can specify the number of output classes, which refers to the number of possible rotation angles.
-
-```python
-self.num_classes_w = 7
-```
-
-#### Train Classification Network
-
-To train the classification network to run the file:
-
-```bash
-cd 2017-tfm-vanessa-fernandez/Follow Line/dl-driver/Net/Keras/
-python classification_train.py
-```
-
-When the program is running it will ask for data to know the characteristics of the network to be trained:
-
-1. **Choose one of the options for the number of classes:** *Choose the number of classes you want, typically 4-5 for `v` parameter and 2, 7 or 9 for `w` parameter. Depending on the dataset created, there are different classifications in the json depending on the number of classes for each screen.*
-
-2. **Choose the variable you want to train:** `v` or `w`: *here you put `v` or `w` depending on the type of speed you want to train (traction or turn).*
-
-3. **Choose the type of image you want:** `normal` or `cropped`: *you can choose `normal` or `cropped`. If you want to train with the full image you have to choose `normal` and if you want to train with the cropped image choose `cropped`.*
-
-4. **Choose the type of network you want: normal, biased or balanced:** *this option refers to the type of dataset or training you want.*
-
- *The documentation talks about having on the one hand a training with the whole dataset without any type of treatment of the number of images for each class (there were many more straight lines than curves) or using a balanced dataset that we created keeping the same number of images for each class (v and w),*
-
- *To train with that configuration, set the `normal` option. To train with balanced dataset, set the option: `balanced`.*
-
- *And finally, `biased` refers to you training with the full dataset (unbalanced) but in training you put weights to each class with `class_weigth` type.*
-
- ```python
- class_weight = {0: 4., 1: 2., 2: 2., 3: 1., 4:2., 5: 2., 6: 3.}
- ```
-
- *then with this option you can give more weight to the kinds of curves than straight lines. In that example the class 0 is the class `radically_left` and the 6 would be `radically_right`. The option that worked best was that of 'biased'.*
-
-5. **Choose the model you want to use:** `lenet`, `smaller_vgg` or `other`: *Here you have to choose the model you want to train. The option that offers the best results is `smaller_vgg`. The `lenet` model gave very bad results because it was very basic. The `other` model loaded another model that gives worse results. The files containing the network models as such are in the folder `models/`. For classification you have them in `classification_model.py` for regression in `model_nvidia.py`.*
-
-### 3. Regression Network
-
-If you want to train the regression network you have to run the `regression_train.py` file which is in the `/net/keras/` path. To run it, type `python train.py`. When you run it, it will ask you for the parameters for the training.
-
-1. **Choose the type of image you want:** `normal` or `cropped`: *you can choose `normal` or `cropped`. If you want to train with the full image you have to choose `normal` and if you want to train with the cropped image choose `cropped`.*
-
-2. **Choose the type of network you want**: The available options are:
-
- - `pilotnet`.
- - `tinypilotnet`.
- - `lstm_tinypilotnet`.
- - `lstm`
- - `deepestlstm_tinypilotnet`.
- - `controlnet`
- - `stacked`
- - `stacked_dif` or `temporal`.
-
-
-
-## FAQ
-
-### Install Graphviz:
-
-- Problem
-
- ```
- E: Unmet dependencies. Try 'apt-get -f install' with no packages (or specify a solution).
- ```
-
-- Solution
-
- ```
- sudo apt autoclean && apt-get -f install && sudo dpkg --configure -a && sudo apt-get -f install
+
+
+# [DEPRECATED] Behavior Metrics Library
+
+## **Please don't use this README since it's outdated. Checkout current [website](https://jderobot.github.io/BehaviorMetrics/)**
+
+
+- [Usage](#usage)
+- [Dataset](#datasets)
+- [Models](#models)
+- [Solutions](#solutions)
+ - [Manual Solution](#manual-solution)
+ - [Classification Network](#classification-network)
+ - [Regression Network](#regression-network)
+- [FAQ](#faq)
+
+The objective of this project is to **take images** from the camera on a circuit where the mission is to follow a red line to complete a lap of the circuit **using classification and regression neural networks**.
+
+## Info
+
+- More detailed info at my [Github-pages](https://roboticslaburjc.github.io/2017-tfm-vanessa-fernandez/).
+
+
+## Datasets
+
+There are currently **two sets** of data to train the neural network that resolves the circuit. One contains **images of all types** such as straights and curves and the other contains **only the curves** of the circuit. The second one is smaller and the results are good enough to solve a lap of the circuit.
+
+- [Complete dataset](http://wiki.jderobot.org/store/jmplaza/uploads/deeplearning-datasets/vision-based-end2end-learning/complete_dataset.zip).
+- [Curve dataset](http://wiki.jderobot.org/store/jmplaza/uploads/deeplearning-datasets/vision-based-end2end-learning/curves_only.zip).
+
+## Models
+
+The models used in this repository are the following:
+
+| Model | Links | Image |
+| ------------------------- | ------------------------------------------------------------ | ----------------------------------------------------------- |
+| PilotNet | [Paper](https://arxiv.org/pdf/1704.07911.pdf). [Nvidia source.](https://devblogs.nvidia.com/explaining-deep-learning-self-driving-car/) | [Structure](./docs/imgs/model_pilotnet.png) |
+| TinyPilotNet | [Javier del Egido Sierra](https://ebuah.uah.es/dspace/bitstream/handle/10017/33946/TFG_Egido_Sierra_2018.pdf?sequence=1&isAllowed=y) TFG's. | - |
+| LSTM | [Info](https://colah.github.io/posts/2015-08-Understanding-LSTMs/) | - |
+| LSTM TinyPilotNet | - | [Structure](./docs/imgs/model_lstm_tinypilotnet.png) |
+| Deepest LSTM TinyPilotNet | [Javier del Egido Sierra](https://ebuah.uah.es/dspace/bitstream/handle/10017/33946/TFG_Egido_Sierra_2018.pdf?sequence=1&isAllowed=y) TFG's. | [Structure](./docs/imgs/model_deepestlstm_tinypilotnet.png) |
+| ControlNet | - | [Structure](./docs/imgs/model_controlnet.png) |
+| Stacked | - | [Structure](./docs/imgs/model_stacked.png) |
+| Stacked Dif or Temporal | - | - |
+
+The models are available in the [following repository](http://wiki.jderobot.org/store/jmplaza/uploads/deeplearning-models/models.zip).
+
+
+## Installation
+
+- First of all, we need to **install the JdeRobot environment** packages. We need two packages: [JdeRobot-base](https://github.com/JdeRobot/base) and [JdeRobot-assets](https://github.com/JdeRobot/assets). You can follow [this tutorial](https://github.com/JdeRobot/base#getting-environment-ready) for the complete installation.
+
+- Install ROS plugins typing:
+
+ ```bash
+ sudo apt install ros-melodic-gazebo-plugins
+ ```
+
+- Clone the repository :
+
+ ```bash
+ git clone https://github.com/RoboticsLabURJC/2017-tfm-vanessa-fernandez.git
+ ```
+
+- Create and activate a virtual environment:
+
+ ```bash
+ virtualenv -p python2.7 --system-site-packages neural_behavior_env
+ ```
+
+- Install `requirements`:
+
+ ```bash
+ pip install -r requirements.txt
+ ```
+
+- Launch Gazebo with the F1 world through the command:
+
+ ```bash
+ roslaunch /opt/jderobot/share/jderobot/gazebo/launch/f1_1_simplecircuit.launch
+ ```
+
+- Then you have to execute the application, which will incorporate your code:
+
+ ```bash
+ python2 driver.py driver.yml
+ ```
+
+
+## Usage
+
+### 1. Manual Solution
+
+For this solution, the **code developed in the robotics course of the Official Master's Degree** in **Computer Vision** has been used. The structure of the project allows to combine between the different solutions. As a first approach, the one developed manually by a student or user is used.
+
+An excerpt of the solution can be seen in the following gif:
+
+
+
+
+
+### 2. Classification Network
+
+The solution using **classification networks** leaves a somewhat slower solution than the manual solution but equally useful. A piece of the solution can be seen in the following gif.
+
+
+
+Depending on the type of network you want to run (normal or cropped) you have to change the size of the images entering the network in the `ckassification_network.py` file.
+
+For **cropped images**, the values are:
+
+```python
+. . .
+self.img_height = 60
+self.img_width = 160
+. . .
+```
+
+You also need to change the predict method to configure it to the image type:
+
+```python
+def predict(self):
+ input_image = self.camera.getImage()
+ # Preprocessing
+ img = cv2.cvtColor(input_image.data[240:480, 0:640], cv2.COLOR_RGB2BGR)
+ . . .
+```
+
+For **normal images**, the default value is:
+
+```python
+. . .
+self.img_height = 120
+. . .
+```
+
+The `predict` method is the same but without cropping the image:
+
+```python
+def predict(self):
+ input_image = self.camera.getImage()
+ # Preprocessing
+ img = cv2.cvtColor(input_image.data, cv2.COLOR_RGB2BGR)
+ . . .
+```
+
+In the same file you can specify the number of output classes, which refers to the number of possible rotation angles.
+
+```python
+self.num_classes_w = 7
+```
+
+#### Train Classification Network
+
+To train the classification network to run the file:
+
+```bash
+cd 2017-tfm-vanessa-fernandez/Follow Line/dl-driver/Net/Keras/
+python classification_train.py
+```
+
+When the program is running it will ask for data to know the characteristics of the network to be trained:
+
+1. **Choose one of the options for the number of classes:** *Choose the number of classes you want, typically 4-5 for `v` parameter and 2, 7 or 9 for `w` parameter. Depending on the dataset created, there are different classifications in the json depending on the number of classes for each screen.*
+
+2. **Choose the variable you want to train:** `v` or `w`: *here you put `v` or `w` depending on the type of speed you want to train (traction or turn).*
+
+3. **Choose the type of image you want:** `normal` or `cropped`: *you can choose `normal` or `cropped`. If you want to train with the full image you have to choose `normal` and if you want to train with the cropped image choose `cropped`.*
+
+4. **Choose the type of network you want: normal, biased or balanced:** *this option refers to the type of dataset or training you want.*
+
+ *The documentation talks about having on the one hand a training with the whole dataset without any type of treatment of the number of images for each class (there were many more straight lines than curves) or using a balanced dataset that we created keeping the same number of images for each class (v and w),*
+
+ *To train with that configuration, set the `normal` option. To train with balanced dataset, set the option: `balanced`.*
+
+ *And finally, `biased` refers to you training with the full dataset (unbalanced) but in training you put weights to each class with `class_weigth` type.*
+
+ ```python
+ class_weight = {0: 4., 1: 2., 2: 2., 3: 1., 4:2., 5: 2., 6: 3.}
+ ```
+
+ *then with this option you can give more weight to the kinds of curves than straight lines. In that example the class 0 is the class `radically_left` and the 6 would be `radically_right`. The option that worked best was that of 'biased'.*
+
+5. **Choose the model you want to use:** `lenet`, `smaller_vgg` or `other`: *Here you have to choose the model you want to train. The option that offers the best results is `smaller_vgg`. The `lenet` model gave very bad results because it was very basic. The `other` model loaded another model that gives worse results. The files containing the network models as such are in the folder `models/`. For classification you have them in `classification_model.py` for regression in `model_nvidia.py`.*
+
+### 3. Regression Network
+
+If you want to train the regression network you have to run the `regression_train.py` file which is in the `/net/keras/` path. To run it, type `python train.py`. When you run it, it will ask you for the parameters for the training.
+
+1. **Choose the type of image you want:** `normal` or `cropped`: *you can choose `normal` or `cropped`. If you want to train with the full image you have to choose `normal` and if you want to train with the cropped image choose `cropped`.*
+
+2. **Choose the type of network you want**: The available options are:
+
+ - `pilotnet`.
+ - `tinypilotnet`.
+ - `lstm_tinypilotnet`.
+ - `lstm`
+ - `deepestlstm_tinypilotnet`.
+ - `controlnet`
+ - `stacked`
+ - `stacked_dif` or `temporal`.
+
+
+
+## FAQ
+
+### Install Graphviz:
+
+- Problem
+
+ ```
+ E: Unmet dependencies. Try 'apt-get -f install' with no packages (or specify a solution).
+ ```
+
+- Solution
+
+ ```
+ sudo apt autoclean && apt-get -f install && sudo dpkg --configure -a && sudo apt-get -f install
```
\ No newline at end of file
diff --git a/behavior_metrics/behaviorlib/keraslib/__init__.py b/behavior_metrics/behaviorlib/keraslib/__init__.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/behaviorlib/keraslib/keras_predict.py b/behavior_metrics/behaviorlib/keraslib/keras_predict.py
old mode 100755
new mode 100644
index 496c0deb..1c127546
--- a/behavior_metrics/behaviorlib/keraslib/keras_predict.py
+++ b/behavior_metrics/behaviorlib/keraslib/keras_predict.py
@@ -1,89 +1,89 @@
-#!/usr/bin/env python
-
-""" This module contains the logic to make predictions of keras-based neural networks.
-
-This is module contains a class called KerasPredictor which is responsible of making predictions based
-on a specific model. This is a generic class used by all the keras-based models.
-
-This program is free software: you can redistribute it and/or modify it under
-the terms of the GNU General Public License as published by the Free Software
-Foundation, either version 3 of the License, or (at your option) any later
-version.
-This program is distributed in the hope that it will be useful, but WITHOUT
-ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
-FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
-You should have received a copy of the GNU General Public License along with
-this program. If not, see .
-
-Original idea from: https://github.com/JdeRobot/DetectionSuite/blob/master/DeepLearningSuite/DeepLearningSuiteLib/python_modules/keras_detect.py
-Code adapted by: fqez
-Original code by: vmartinezf and chanfr
-"""
-
-import os
-
-import cv2
-import numpy as np
-import tensorflow as tf
-from keras.backend import set_session
-from keras.models import load_model
-from utils.logger import logger
-
-os.environ['TF_CPP_MIN_LOG_LEVEL'] = '3'
-
-
-class KerasPredictor:
- """This class takes care of the prediction of the models that controls the behaviors of the robots.
-
- It's used for keras-based models and it's meant to predict a value (tipically a velocity) based on image inputs.
-
- Attributes:
- sess {tf.Session} -- Tensorflow session
- graph {tf.Graph} -- Tensorflow graph
- model -- Keras model instance
- img_width {int} -- Input images width
- img_height {int} -- Input images height
- """
-
- def __init__(self, path_to_hdf5):
- """Constructor of the class.
-
- Arguments:
- path_to_hdf5 {str} -- Path to the model file.
- """
-
- # Obtain the graph
- logger.info("Loading keras model {}".format(path_to_hdf5))
- self.sess = tf.compat.v1.Session()
- self.graph = tf.compat.v1.get_default_graph()
- tf.compat.v1.keras.backend.set_session(self.sess)
- self.model = tf.keras.models.load_model(path_to_hdf5)
-
- input_size = self.model.input.shape.as_list()
- self.img_height = input_size[1]
- self.img_width = input_size[2]
-
- def predict(self, img, type='classification'):
- """Make a prediction of a velocity based on an input images.
-
- The model takes the image one of the robot's cameras and makes a predictino based on that information.
-
- Arguments:
- img {robot.interfaces.camera.Image} -- Image obtanied from one of the robot's cameras.
- type {str} -- Specify if the network is a classification or regression network (default: 'classification')
-
- Returns:
- int, float -- Predicted class or value based on the image information depending on the type of network.
- """
-
- img_resized = cv2.resize(img, (self.img_width, self.img_height))
- input_img = np.stack([img_resized], axis=0)
-
- with self.graph.as_default():
- set_session(self.sess)
- y_pred = self.model.predict(input_img)
-
- if type == 'classification':
- return [np.argmax(prediction) for prediction in y_pred][0]
- else:
- return [float(prediction[0]) for prediction in y_pred][0]
+#!/usr/bin/env python
+
+""" This module contains the logic to make predictions of keras-based neural networks.
+
+This is module contains a class called KerasPredictor which is responsible of making predictions based
+on a specific model. This is a generic class used by all the keras-based models.
+
+This program is free software: you can redistribute it and/or modify it under
+the terms of the GNU General Public License as published by the Free Software
+Foundation, either version 3 of the License, or (at your option) any later
+version.
+This program is distributed in the hope that it will be useful, but WITHOUT
+ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
+You should have received a copy of the GNU General Public License along with
+this program. If not, see .
+
+Original idea from: https://github.com/JdeRobot/DetectionSuite/blob/master/DeepLearningSuite/DeepLearningSuiteLib/python_modules/keras_detect.py
+Code adapted by: fqez
+Original code by: vmartinezf and chanfr
+"""
+
+import os
+
+import cv2
+import numpy as np
+import tensorflow as tf
+from keras.backend import set_session
+from keras.models import load_model
+from utils.logger import logger
+
+os.environ['TF_CPP_MIN_LOG_LEVEL'] = '3'
+
+
+class KerasPredictor:
+ """This class takes care of the prediction of the models that controls the behaviors of the robots.
+
+ It's used for keras-based models and it's meant to predict a value (tipically a velocity) based on image inputs.
+
+ Attributes:
+ sess {tf.Session} -- Tensorflow session
+ graph {tf.Graph} -- Tensorflow graph
+ model -- Keras model instance
+ img_width {int} -- Input images width
+ img_height {int} -- Input images height
+ """
+
+ def __init__(self, path_to_hdf5):
+ """Constructor of the class.
+
+ Arguments:
+ path_to_hdf5 {str} -- Path to the model file.
+ """
+
+ # Obtain the graph
+ logger.info("Loading keras model {}".format(path_to_hdf5))
+ self.sess = tf.compat.v1.Session()
+ self.graph = tf.compat.v1.get_default_graph()
+ tf.compat.v1.keras.backend.set_session(self.sess)
+ self.model = tf.keras.models.load_model(path_to_hdf5)
+
+ input_size = self.model.input.shape.as_list()
+ self.img_height = input_size[1]
+ self.img_width = input_size[2]
+
+ def predict(self, img, type='classification'):
+ """Make a prediction of a velocity based on an input images.
+
+ The model takes the image one of the robot's cameras and makes a predictino based on that information.
+
+ Arguments:
+ img {robot.interfaces.camera.Image} -- Image obtanied from one of the robot's cameras.
+ type {str} -- Specify if the network is a classification or regression network (default: 'classification')
+
+ Returns:
+ int, float -- Predicted class or value based on the image information depending on the type of network.
+ """
+
+ img_resized = cv2.resize(img, (self.img_width, self.img_height))
+ input_img = np.stack([img_resized], axis=0)
+
+ with self.graph.as_default():
+ set_session(self.sess)
+ y_pred = self.model.predict(input_img)
+
+ if type == 'classification':
+ return [np.argmax(prediction) for prediction in y_pred][0]
+ else:
+ return [float(prediction[0]) for prediction in y_pred][0]
diff --git a/behavior_metrics/brains/__init__.py b/behavior_metrics/brains/__init__.py
index ada72e96..c0c1ead9 100644
--- a/behavior_metrics/brains/__init__.py
+++ b/behavior_metrics/brains/__init__.py
@@ -1 +1 @@
-from .brains_handler import Brains # FQDN
+from .brains_handler import Brains # FQDN
diff --git a/behavior_metrics/brains/brains_handler.py b/behavior_metrics/brains/brains_handler.py
old mode 100755
new mode 100644
index 3ac8dfbc..f17fb70d
--- a/behavior_metrics/brains/brains_handler.py
+++ b/behavior_metrics/brains/brains_handler.py
@@ -1,127 +1,127 @@
-import importlib
-import sys
-import subprocess
-import os
-import traceback
-from utils.logger import logger
-from abc import abstractmethod
-from albumentations import (
- Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare, Affine
-)
-
-
-""" TODO: fix neural brains """
-
-
-class Brains(object):
-
- def __init__(self, sensors, actuators, brain_path, controller, model=None, config=None):
-
- self.sensors = sensors
- self.actuators = actuators
- self.controller = controller
- self.brain_path = brain_path
- self.config = config
- self.model = model
- try:
- if brain_path:
- self.load_brain(brain_path)
- except AttributeError as e:
- print('Invalid brain path: {}\n[ERROR] {}'.format(brain_path, e))
- traceback.print_exc()
- exit(1)
-
- def load_brain(self, path, model=None):
-
- path_split = path.split("/")
- framework = path_split[-3]
- robot_type = path_split[-2]
- module_name = path_split[-1][:-3] # removing .py extension
-
-
- if len(path_split) == 4:
- import_name = 'brains.' + framework + '.' + robot_type + '.' + module_name
- else:
- import_name = 'brains.' + robot_type + '.' + module_name
-
- logger.info("import_name:" + import_name)
-
- if robot_type == 'CARLA':
- module = importlib.import_module(import_name)
- Brain = getattr(module, 'Brain')
- print('Brain: ', Brain)
- if self.model:
- self.active_brain = Brain(self.sensors, self.actuators, handler=self, model=self.model,
- config=self.config)
- else:
- self.active_brain = Brain(self.sensors, self.actuators, handler=self, config=self.config)
- print('config: ', self.sensors)
- else:
- if import_name in sys.modules: # for reloading sake
- del sys.modules[import_name]
- module = importlib.import_module(import_name)
- Brain = getattr(module, 'Brain')
- print('Brain: ', Brain)
- if robot_type == 'drone':
- self.active_brain = Brain(handler=self, config=self.config)
- else:
- if model:
- self.active_brain = Brain(self.sensors, self.actuators, model=model, handler=self,
- config=self.config)
- else:
- self.active_brain = Brain(self.sensors, self.actuators, handler=self, config=self.config)
-
- def get_image(self, camera_name):
- camera = self.sensors.get_camera(camera_name)
- return camera.getImage()
-
- def get_laser_data(self, laser_name):
- laser = self.sensors.get_laser(laser_name)
- return laser.getLaserData()
-
- def get_motors(self, motors_name):
- return self.actuators.get_motor(motors_name)
-
- def update_pose3d(self, pose_data):
- self.controller.update_pose3d(pose_data)
-
- def update_frame(self, frame_id, data):
- self.controller.update_frame(frame_id, data)
- # try:
- # frame = self.viewer.main_view.get_frame(frame_id)
- # frame.set_data(data)
- # return frame
- # except AttributeError as e:
- # print('Not found ', frame_id, 'ERROR: ', e)
- # pass
-
- def transform_image(self, image, option):
- augmentation_option = Compose([])
- if option == 'rain':
- augmentation_option = Compose([
- RandomRain(slant_lower=-10, slant_upper=10,
- drop_length=20, drop_width=1, drop_color=(200, 200, 200),
- blur_value=7, brightness_coefficient=0.7,
- rain_type='torrential', always_apply=True)
- ])
- elif option == 'night':
- augmentation_option = Compose([RandomBrightness([-0.5, -0.5], always_apply=True)])
- elif option == 'shadow':
- augmentation_option = Compose([RandomShadow(always_apply=True)])
- elif option == 'snow':
- augmentation_option = Compose([RandomSnow(always_apply=True)])
- elif option == 'fog':
- augmentation_option = Compose([RandomFog(always_apply=True)])
- elif option == 'sunflare':
- augmentation_option = Compose([RandomSunFlare(always_apply=True)])
- elif option == 'daytime':
- augmentation_option = Compose([RandomBrightness([0.3, 0.3], always_apply=True)])
- elif option == 'affine':
- augmentation_option = Compose([Affine(translate_percent={'x': -0.1, 'y': 0}, always_apply=True)])
- transformed_image = augmentation_option(image=image)
- transformed_image = transformed_image["image"]
- return transformed_image
-
- @abstractmethod
- def execute(self):
- pass
+import importlib
+import sys
+import subprocess
+import os
+import traceback
+from utils.logger import logger
+from abc import abstractmethod
+from albumentations import (
+ Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare, Affine
+)
+
+
+""" TODO: fix neural brains """
+
+
+class Brains(object):
+
+ def __init__(self, sensors, actuators, brain_path, controller, model=None, config=None):
+
+ self.sensors = sensors
+ self.actuators = actuators
+ self.controller = controller
+ self.brain_path = brain_path
+ self.config = config
+ self.model = model
+ try:
+ if brain_path:
+ self.load_brain(brain_path)
+ except AttributeError as e:
+ print('Invalid brain path: {}\n[ERROR] {}'.format(brain_path, e))
+ traceback.print_exc()
+ exit(1)
+
+ def load_brain(self, path, model=None):
+
+ path_split = path.split("/")
+ framework = path_split[-3]
+ robot_type = path_split[-2]
+ module_name = path_split[-1][:-3] # removing .py extension
+
+
+ if len(path_split) == 4:
+ import_name = 'brains.' + framework + '.' + robot_type + '.' + module_name
+ else:
+ import_name = 'brains.' + robot_type + '.' + module_name
+
+ logger.info("import_name:" + import_name)
+
+ if robot_type == 'CARLA':
+ module = importlib.import_module(import_name)
+ Brain = getattr(module, 'Brain')
+ print('Brain: ', Brain)
+ if self.model:
+ self.active_brain = Brain(self.sensors, self.actuators, handler=self, model=self.model,
+ config=self.config)
+ else:
+ self.active_brain = Brain(self.sensors, self.actuators, handler=self, config=self.config)
+ print('config: ', self.sensors)
+ else:
+ if import_name in sys.modules: # for reloading sake
+ del sys.modules[import_name]
+ module = importlib.import_module(import_name)
+ Brain = getattr(module, 'Brain')
+ print('Brain: ', Brain)
+ if robot_type == 'drone':
+ self.active_brain = Brain(handler=self, config=self.config)
+ else:
+ if model:
+ self.active_brain = Brain(self.sensors, self.actuators, model=model, handler=self,
+ config=self.config)
+ else:
+ self.active_brain = Brain(self.sensors, self.actuators, handler=self, config=self.config)
+
+ def get_image(self, camera_name):
+ camera = self.sensors.get_camera(camera_name)
+ return camera.getImage()
+
+ def get_laser_data(self, laser_name):
+ laser = self.sensors.get_laser(laser_name)
+ return laser.getLaserData()
+
+ def get_motors(self, motors_name):
+ return self.actuators.get_motor(motors_name)
+
+ def update_pose3d(self, pose_data):
+ self.controller.update_pose3d(pose_data)
+
+ def update_frame(self, frame_id, data):
+ self.controller.update_frame(frame_id, data)
+ # try:
+ # frame = self.viewer.main_view.get_frame(frame_id)
+ # frame.set_data(data)
+ # return frame
+ # except AttributeError as e:
+ # print('Not found ', frame_id, 'ERROR: ', e)
+ # pass
+
+ def transform_image(self, image, option):
+ augmentation_option = Compose([])
+ if option == 'rain':
+ augmentation_option = Compose([
+ RandomRain(slant_lower=-10, slant_upper=10,
+ drop_length=20, drop_width=1, drop_color=(200, 200, 200),
+ blur_value=7, brightness_coefficient=0.7,
+ rain_type='torrential', always_apply=True)
+ ])
+ elif option == 'night':
+ augmentation_option = Compose([RandomBrightness([-0.5, -0.5], always_apply=True)])
+ elif option == 'shadow':
+ augmentation_option = Compose([RandomShadow(always_apply=True)])
+ elif option == 'snow':
+ augmentation_option = Compose([RandomSnow(always_apply=True)])
+ elif option == 'fog':
+ augmentation_option = Compose([RandomFog(always_apply=True)])
+ elif option == 'sunflare':
+ augmentation_option = Compose([RandomSunFlare(always_apply=True)])
+ elif option == 'daytime':
+ augmentation_option = Compose([RandomBrightness([0.3, 0.3], always_apply=True)])
+ elif option == 'affine':
+ augmentation_option = Compose([Affine(translate_percent={'x': -0.1, 'y': 0}, always_apply=True)])
+ transformed_image = augmentation_option(image=image)
+ transformed_image = transformed_image["image"]
+ return transformed_image
+
+ @abstractmethod
+ def execute(self):
+ pass
diff --git a/behavior_metrics/brains/gazebo/agents/f1/f1_follow_line_camera_dqn.py b/behavior_metrics/brains/gazebo/agents/f1/f1_follow_line_camera_dqn.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/f1/f1_follow_line_qlearn.py b/behavior_metrics/brains/gazebo/agents/f1/f1_follow_line_qlearn.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/f1/liveplot.py b/behavior_metrics/brains/gazebo/agents/f1/liveplot.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/f1/memory.py b/behavior_metrics/brains/gazebo/agents/f1/memory.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/f1/qlearn.py b/behavior_metrics/brains/gazebo/agents/f1/qlearn.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/scripts/benchmark_runner b/behavior_metrics/brains/gazebo/agents/scripts/benchmark_runner
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/turtlebot/circuit2c_turtlebot_camera_dqn.py b/behavior_metrics/brains/gazebo/agents/turtlebot/circuit2c_turtlebot_camera_dqn.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/turtlebot/deepq.py b/behavior_metrics/brains/gazebo/agents/turtlebot/deepq.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/turtlebot/liveplot.py b/behavior_metrics/brains/gazebo/agents/turtlebot/liveplot.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/turtlebot/memory.py b/behavior_metrics/brains/gazebo/agents/turtlebot/memory.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/turtlebot/qlearn.py b/behavior_metrics/brains/gazebo/agents/turtlebot/qlearn.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/turtlebot/round_turtlebot_lidar_test.py b/behavior_metrics/brains/gazebo/agents/turtlebot/round_turtlebot_lidar_test.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/turtlebot/runtraining_dqn_circuit2_turtlebot_lidar.py b/behavior_metrics/brains/gazebo/agents/turtlebot/runtraining_dqn_circuit2_turtlebot_lidar.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/turtlebot/sarsa.py b/behavior_metrics/brains/gazebo/agents/turtlebot/sarsa.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/utilities/averaged_table.py b/behavior_metrics/brains/gazebo/agents/utilities/averaged_table.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/utilities/camera_visualizer.py b/behavior_metrics/brains/gazebo/agents/utilities/camera_visualizer.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/agents/utilities/display_plot.py b/behavior_metrics/brains/gazebo/agents/utilities/display_plot.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/car/brain_car_opencv2.py b/behavior_metrics/brains/gazebo/car/brain_car_opencv2.py
index 4ceaa1d3..1aada50d 100644
--- a/behavior_metrics/brains/gazebo/car/brain_car_opencv2.py
+++ b/behavior_metrics/brains/gazebo/car/brain_car_opencv2.py
@@ -1,32 +1,32 @@
-#!/usr/bin/python
-# -*- coding: utf-8 -*-
-
-
-class Brain:
-
- def __init__(self, sensors, actuators, handler=None):
- self.camera_c = sensors.get_camera('camera_c')
- self.camera_l = sensors.get_camera('camera_l')
- self.camera_r = sensors.get_camera('camera_r')
- self.pose = sensors.get_pose3d('pose3d_0')
- self.motors = actuators.get_motor('motors_0')
- self.handler = handler
-
- def update_frame(self, frame_id, data):
- self.handler.update_frame(frame_id, data)
-
- def update_pose(self, pose_data):
- self.handler.update_pose3d(pose_data)
-
- def execute(self):
- self.update_pose(self.pose.getPose3d())
- v = 0
- w = 0.8
- self.motors.sendV(v)
- self.motors.sendW(w)
- image_c = self.camera_c.getImage().data
- image_l = self.camera_l.getImage().data
- image_r = self.camera_r.getImage().data
- self.update_frame('frame_0', image_c)
- self.update_frame('frame_1', image_l)
- self.update_frame('frame_2', image_r)
+#!/usr/bin/python
+# -*- coding: utf-8 -*-
+
+
+class Brain:
+
+ def __init__(self, sensors, actuators, handler=None):
+ self.camera_c = sensors.get_camera('camera_c')
+ self.camera_l = sensors.get_camera('camera_l')
+ self.camera_r = sensors.get_camera('camera_r')
+ self.pose = sensors.get_pose3d('pose3d_0')
+ self.motors = actuators.get_motor('motors_0')
+ self.handler = handler
+
+ def update_frame(self, frame_id, data):
+ self.handler.update_frame(frame_id, data)
+
+ def update_pose(self, pose_data):
+ self.handler.update_pose3d(pose_data)
+
+ def execute(self):
+ self.update_pose(self.pose.getPose3d())
+ v = 0
+ w = 0.8
+ self.motors.sendV(v)
+ self.motors.sendW(w)
+ image_c = self.camera_c.getImage().data
+ image_l = self.camera_l.getImage().data
+ image_r = self.camera_r.getImage().data
+ self.update_frame('frame_0', image_c)
+ self.update_frame('frame_1', image_l)
+ self.update_frame('frame_2', image_r)
diff --git a/behavior_metrics/brains/gazebo/f1/__init__.py b/behavior_metrics/brains/gazebo/f1/__init__.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/f1/brain_f1_dummy.py b/behavior_metrics/brains/gazebo/f1/brain_f1_dummy.py
index 426948a4..4cc25f40 100644
--- a/behavior_metrics/brains/gazebo/f1/brain_f1_dummy.py
+++ b/behavior_metrics/brains/gazebo/f1/brain_f1_dummy.py
@@ -1,53 +1,53 @@
-#!/usr/bin/python
-# -*- coding: utf-8 -*-
-
-
-class Brain:
- """Specific dummy brain for the f1 robot."""
-
- def __init__(self, sensors, actuators, handler=None, config=None):
- """Constructor of the class.
-
- Arguments:
- sensors {robot.sensors.Sensors} -- Sensors instance of the robot
- actuators {robot.actuators.Actuators} -- Actuators instance of the robot
-
- Keyword Arguments:
- handler {brains.brain_handler.Brains} -- Handler of the current brain. Communication with the controller
- (default: {None})
- """
- self.camera = sensors.get_camera('camera_0')
- # self.laser = sensors.get_laser('laser_0')
- self.pose = sensors.get_pose3d('pose3d_0')
- self.motors = actuators.get_motor('motors_0')
- self.handler = handler
-
- def update_frame(self, frame_id, data):
- """Update the information to be shown in one of the GUI's frames.
-
- Arguments:
- frame_id {str} -- Id of the frame that will represent the data
- data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc)
- """
- self.handler.update_frame(frame_id, data)
-
- def update_pose(self, pose_data):
- """Update the pose 3D information obtained from the robot.
-
- Arguments:
- data {*} -- Data to be updated, will be retrieved later by the UI.
- """
- self.handler.update_pose3d(pose_data)
-
- def execute(self):
- """Main loop of the brain. This will be called iteratively each TIME_CYCLE (see pilot.py)"""
-
- self.update_pose(self.pose.getPose3d())
- v = 0
- w = 0.8
- self.motors.sendV(v)
- self.motors.sendW(w)
- image = self.camera.getImage().data
- self.update_frame('frame_0', image)
- # laser_data = self.laser.getLaserData()
- # self.update_frame('frame_0', laser_data)
+#!/usr/bin/python
+# -*- coding: utf-8 -*-
+
+
+class Brain:
+ """Specific dummy brain for the f1 robot."""
+
+ def __init__(self, sensors, actuators, handler=None, config=None):
+ """Constructor of the class.
+
+ Arguments:
+ sensors {robot.sensors.Sensors} -- Sensors instance of the robot
+ actuators {robot.actuators.Actuators} -- Actuators instance of the robot
+
+ Keyword Arguments:
+ handler {brains.brain_handler.Brains} -- Handler of the current brain. Communication with the controller
+ (default: {None})
+ """
+ self.camera = sensors.get_camera('camera_0')
+ # self.laser = sensors.get_laser('laser_0')
+ self.pose = sensors.get_pose3d('pose3d_0')
+ self.motors = actuators.get_motor('motors_0')
+ self.handler = handler
+
+ def update_frame(self, frame_id, data):
+ """Update the information to be shown in one of the GUI's frames.
+
+ Arguments:
+ frame_id {str} -- Id of the frame that will represent the data
+ data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc)
+ """
+ self.handler.update_frame(frame_id, data)
+
+ def update_pose(self, pose_data):
+ """Update the pose 3D information obtained from the robot.
+
+ Arguments:
+ data {*} -- Data to be updated, will be retrieved later by the UI.
+ """
+ self.handler.update_pose3d(pose_data)
+
+ def execute(self):
+ """Main loop of the brain. This will be called iteratively each TIME_CYCLE (see pilot.py)"""
+
+ self.update_pose(self.pose.getPose3d())
+ v = 0
+ w = 0.8
+ self.motors.sendV(v)
+ self.motors.sendW(w)
+ image = self.camera.getImage().data
+ self.update_frame('frame_0', image)
+ # laser_data = self.laser.getLaserData()
+ # self.update_frame('frame_0', laser_data)
diff --git a/behavior_metrics/brains/gazebo/f1/brain_f1_opencv.py b/behavior_metrics/brains/gazebo/f1/brain_f1_opencv.py
index c15f482b..b85cdfe4 100644
--- a/behavior_metrics/brains/gazebo/f1/brain_f1_opencv.py
+++ b/behavior_metrics/brains/gazebo/f1/brain_f1_opencv.py
@@ -1,266 +1,266 @@
-#!/usr/bin/python
-# -*- coding: utf-8 -*-
-import csv
-import cv2
-import math
-import numpy as np
-import threading
-import time
-from albumentations import (
- Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare
-)
-from utils.constants import DATASETS_DIR, ROOT_PATH
-
-error = 0
-integral = 0
-v = 0
-w = 0
-current = 'straight'
-RED = (255, 0, 0)
-GREEN = (0, 255, 0)
-BLUE = (0, 0, 255)
-MAGENTA = (255, 0, 255)
-TH = 500
-buf = np.ones(25)
-V = 4
-V_CURVE = 3.5
-V_MULT = 2
-v_mult = V_MULT
-
-GENERATED_DATASETS_DIR = ROOT_PATH + '/' + DATASETS_DIR
-
-
-class Brain:
-
- def __init__(self, sensors, actuators, handler, config=None):
- self.camera = sensors.get_camera('camera_0')
- self.motors = actuators.get_motor('motors_0')
- self.handler = handler
- self.config = config
-
- self.threshold_image = np.zeros((640, 360, 3), np.uint8)
- self.color_image = np.zeros((640, 360, 3), np.uint8)
- self.lock = threading.Lock()
- self.threshold_image_lock = threading.Lock()
- self.color_image_lock = threading.Lock()
- self.cont = 0
- self.iteration = 0
-
- # self.previous_timestamp = 0
- # self.previous_image = 0
-
- self.previous_v = None
- self.previous_w = None
- self.previous_w_normalized = None
- self.suddenness_distance = []
-
- # Save dataset
- '''
- header = ['image_name', 'v', 'w', 'timestamp']
- with open(GENERATED_DATASETS_DIR + 'difficult_situations_01_06_2022/many_curves_4/data.csv', 'w', encoding='UTF8') as f:
- writer = csv.writer(f)
- writer.writerow(header)
- '''
- time.sleep(2)
-
- def update_frame(self, frame_id, data, current_angular_speed=None, previous_angular_speed=None, distance=None):
- """Update the information to be shown in one of the GUI's frames.
-
- Arguments:
- frame_id {str} -- Id of the frame that will represent the data
- data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc)
- """
- if current_angular_speed:
- data = np.array(data, copy=True)
-
- x1, y1 = int(data.shape[:2][1] / 2), data.shape[:2][0] # ancho, alto
- length = 200
- angle = (90 + int(math.degrees(-current_angular_speed))) * 3.14 / 180.0
- x2 = int(x1 - length * math.cos(angle))
- y2 = int(y1 - length * math.sin(angle))
-
- line_thickness = 10
- cv2.line(data, (x1, y1), (x2, y2), (0, 0, 0), thickness=line_thickness)
- length = 150
- angle = (90 + int(math.degrees(-previous_angular_speed))) * 3.14 / 180.0
- x2 = int(x1 - length * math.cos(angle))
- y2 = int(y1 - length * math.sin(angle))
-
- cv2.line(data, (x1, y1), (x2, y2), (255, 0, 0), thickness=line_thickness)
- if float(distance) > 0.01:
- cv2.putText(data, distance, (10, 100), cv2.FONT_HERSHEY_SIMPLEX, 1, (255, 0, 0), 2, cv2.LINE_AA)
- else:
- cv2.putText(data, distance, (10, 100), cv2.FONT_HERSHEY_SIMPLEX, 1, (255, 255, 255), 2, cv2.LINE_AA)
-
- self.handler.update_frame(frame_id, data)
-
- def collinear3(self, x1, y1, x2, y2, x3, y3):
- line = 0
- line = np.abs((y1 - y2) * (x1 - x3) - (y1 - y3) * (x1 - x2))
- return line
-
- def detect(self, points):
- global current
- global buf
- l2 = 0
- l1 = self.collinear3(points[0][1], points[0][0], points[1][1], points[1][0], points[2][1], points[2][0])
- if l1 > TH:
- buf[0] = 0
- current = 'curve'
- else:
- buf = np.roll(buf, 1)
- buf[0] = 1
- if np.all(buf == 1):
- current = 'straight'
- return (l1, l2)
-
- def getPoint(self, index, img):
- mid = 0
- if np.count_nonzero(img[index]) > 0:
- left = np.min(np.nonzero(img[index]))
- right = np.max(np.nonzero(img[index]))
- mid = np.abs(left - right) / 2 + left
- return int(mid)
-
- def execute(self):
- global error
- global integral
- global current
- global v_mult
- global v
- global w
- red_upper = (179, 255, 255)
- # red_lower=(0,255,171)
- # red_lower = (0, 255, 15)
- red_lower = (0, 110, 15)
- # kernel = np.ones((8, 8), np.uint8)
- '''
- if type(self.previous_image) == int:
- self.previous_image = self.camera.getImage().data
- self.previous_timestamp = timestamp
- if (timestamp - self.previous_timestamp >= 0.085):
- self.previous_image = self.camera.getImage().data
- image = self.previous_image
- '''
-
- image = self.camera.getImage().data
- if image.shape == (3, 3, 3):
- time.sleep(3)
-
- '''
- save_dataset = False
- if (timestamp - self.previous_timestamp >= 0.085):
- #if (timestamp - self.previous_timestamp >= 0.045):
- #print(timestamp)
- self.previous_timestamp = timestamp
- save_dataset = True
- # Save dataset
- rgb_image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB)
- cv2.imwrite(GENERATED_DATASETS_DIR + 'difficult_situations_01_06_2022/many_curves_4/' + str(self.iteration) + '.png', rgb_image)
- '''
- image = self.handler.transform_image(image, self.config['ImageTranform'])
- # Save dataset
- # rgb_image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB)
- # cv2.imwrite(GENERATED_DATASETS_DIR + 'montreal_12_05_2022_opencv_anticlockwise_1/' + str(self.iteration) + '.png', rgb_image)
- image_cropped = image[230:, :, :]
- image_blur = cv2.GaussianBlur(image_cropped, (27, 27), 0)
-
- image_hsv = cv2.cvtColor(image_blur, cv2.COLOR_RGB2HSV)
- image_mask = cv2.inRange(image_hsv, red_lower, red_upper)
- # image_eroded = cv2.erode(image_mask, kernel, iterations=3)
-
- rows, cols = image_mask.shape
- rows = rows - 1 # para evitar desbordamiento
-
- alt = 0
- ff = cv2.reduce(image_mask, 1, cv2.REDUCE_SUM, dtype=cv2.CV_32S)
- if np.count_nonzero(ff[:, 0]) > 0:
- alt = np.min(np.nonzero(ff[:, 0]))
-
- points = []
- for i in range(3):
- if i == 0:
- index = alt
- else:
- index = rows // (2 * i)
- points.append((self.getPoint(index, image_mask), index))
-
- points.append((self.getPoint(rows, image_mask), rows))
-
- l, l2 = self.detect(points)
-
- if current == 'straight':
- kp = 0.001
- kd = 0.004
- ki = 0
- cv2.circle(image_mask, (0, cols // 2), 6, RED, -1)
-
- if image_cropped[0, cols // 2, 0] < 170 and v > 8:
- accel = -0.4
- else:
- accel = 0.3
-
- v_mult = v_mult + accel
- if v_mult > 6:
- v_mult = 6
- v = V * v_mult
- else:
- kp = 0.011 # 0.018
- kd = 0.011 # 0.011
- ki = 0
- v_mult = V_MULT
- v = V_CURVE * v_mult
-
- new_error = cols // 2 - points[0][0]
-
- proportional = kp * new_error
- error_diff = new_error - error
- error = new_error
- derivative = kd * error_diff
- integral = integral + error
- integral = ki * integral
-
- w = proportional + derivative + integral
- self.motors.sendW(w)
- self.motors.sendV(v)
-
- self.update_frame('frame_0', image)
- current_w_normalized = w
-
- v = np.interp(np.array([v]), (6.5, 24), (0, 1))[0]
- w = np.interp(np.array([w]), (-7.1, 7.1), (0, 1))[0]
- if self.previous_v != None:
- a = np.array((v, w))
- b = np.array((self.previous_v, self.previous_w))
- distance = np.linalg.norm(a - b)
- self.suddenness_distance.append(distance)
- self.previous_v = v
- self.previous_w = w
-
- if self.previous_w_normalized != None:
- self.update_frame('frame_2', image, current_w_normalized, self.previous_w_normalized, str(round(distance, 4)))
- self.previous_w_normalized = current_w_normalized
-
- '''
- if (save_dataset):
- # Save dataset
- iteration_data = [str(self.iteration) + '.png', v, w, self.previous_timestamp]
- with open(GENERATED_DATASETS_DIR + 'difficult_situations_01_06_2022/many_curves_4/data.csv', 'a', encoding='UTF8') as f:
- writer = csv.writer(f)
- writer.writerow(iteration_data)
- print(self.iteration)
- self.iteration += 1
- '''
- image_mask = cv2.cvtColor(image_mask, cv2.COLOR_GRAY2RGB)
- cv2.circle(image_mask, points[0], 6, GREEN, -1)
- cv2.circle(image_mask, points[1], 6, GREEN, -1) # punto central rows/2
- cv2.circle(image_mask, points[2], 6, GREEN, -1)
- cv2.circle(image_mask, points[3], 6, GREEN, -1)
- cv2.putText(image_mask, 'w: {:+.2f} v: {}'.format(w, v),
- (10, 30), cv2.FONT_HERSHEY_SIMPLEX, 1, MAGENTA, 2, cv2.LINE_AA)
- cv2.putText(image_mask, 'collinearU: {} collinearD: {}'.format(l, l2),
- (10, 90), cv2.FONT_HERSHEY_SIMPLEX, 1, MAGENTA, 2, cv2.LINE_AA)
- cv2.putText(image_mask, 'actual: {}'.format(current),
- (10, 60), cv2.FONT_HERSHEY_SIMPLEX, 1, MAGENTA, 2, cv2.LINE_AA)
-
- self.update_frame('frame_1', image_mask)
+#!/usr/bin/python
+# -*- coding: utf-8 -*-
+import csv
+import cv2
+import math
+import numpy as np
+import threading
+import time
+from albumentations import (
+ Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare
+)
+from utils.constants import DATASETS_DIR, ROOT_PATH
+
+error = 0
+integral = 0
+v = 0
+w = 0
+current = 'straight'
+RED = (255, 0, 0)
+GREEN = (0, 255, 0)
+BLUE = (0, 0, 255)
+MAGENTA = (255, 0, 255)
+TH = 500
+buf = np.ones(25)
+V = 4
+V_CURVE = 3.5
+V_MULT = 2
+v_mult = V_MULT
+
+GENERATED_DATASETS_DIR = ROOT_PATH + '/' + DATASETS_DIR
+
+
+class Brain:
+
+ def __init__(self, sensors, actuators, handler, config=None):
+ self.camera = sensors.get_camera('camera_0')
+ self.motors = actuators.get_motor('motors_0')
+ self.handler = handler
+ self.config = config
+
+ self.threshold_image = np.zeros((640, 360, 3), np.uint8)
+ self.color_image = np.zeros((640, 360, 3), np.uint8)
+ self.lock = threading.Lock()
+ self.threshold_image_lock = threading.Lock()
+ self.color_image_lock = threading.Lock()
+ self.cont = 0
+ self.iteration = 0
+
+ # self.previous_timestamp = 0
+ # self.previous_image = 0
+
+ self.previous_v = None
+ self.previous_w = None
+ self.previous_w_normalized = None
+ self.suddenness_distance = []
+
+ # Save dataset
+ '''
+ header = ['image_name', 'v', 'w', 'timestamp']
+ with open(GENERATED_DATASETS_DIR + 'difficult_situations_01_06_2022/many_curves_4/data.csv', 'w', encoding='UTF8') as f:
+ writer = csv.writer(f)
+ writer.writerow(header)
+ '''
+ time.sleep(2)
+
+ def update_frame(self, frame_id, data, current_angular_speed=None, previous_angular_speed=None, distance=None):
+ """Update the information to be shown in one of the GUI's frames.
+
+ Arguments:
+ frame_id {str} -- Id of the frame that will represent the data
+ data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc)
+ """
+ if current_angular_speed:
+ data = np.array(data, copy=True)
+
+ x1, y1 = int(data.shape[:2][1] / 2), data.shape[:2][0] # ancho, alto
+ length = 200
+ angle = (90 + int(math.degrees(-current_angular_speed))) * 3.14 / 180.0
+ x2 = int(x1 - length * math.cos(angle))
+ y2 = int(y1 - length * math.sin(angle))
+
+ line_thickness = 10
+ cv2.line(data, (x1, y1), (x2, y2), (0, 0, 0), thickness=line_thickness)
+ length = 150
+ angle = (90 + int(math.degrees(-previous_angular_speed))) * 3.14 / 180.0
+ x2 = int(x1 - length * math.cos(angle))
+ y2 = int(y1 - length * math.sin(angle))
+
+ cv2.line(data, (x1, y1), (x2, y2), (255, 0, 0), thickness=line_thickness)
+ if float(distance) > 0.01:
+ cv2.putText(data, distance, (10, 100), cv2.FONT_HERSHEY_SIMPLEX, 1, (255, 0, 0), 2, cv2.LINE_AA)
+ else:
+ cv2.putText(data, distance, (10, 100), cv2.FONT_HERSHEY_SIMPLEX, 1, (255, 255, 255), 2, cv2.LINE_AA)
+
+ self.handler.update_frame(frame_id, data)
+
+ def collinear3(self, x1, y1, x2, y2, x3, y3):
+ line = 0
+ line = np.abs((y1 - y2) * (x1 - x3) - (y1 - y3) * (x1 - x2))
+ return line
+
+ def detect(self, points):
+ global current
+ global buf
+ l2 = 0
+ l1 = self.collinear3(points[0][1], points[0][0], points[1][1], points[1][0], points[2][1], points[2][0])
+ if l1 > TH:
+ buf[0] = 0
+ current = 'curve'
+ else:
+ buf = np.roll(buf, 1)
+ buf[0] = 1
+ if np.all(buf == 1):
+ current = 'straight'
+ return (l1, l2)
+
+ def getPoint(self, index, img):
+ mid = 0
+ if np.count_nonzero(img[index]) > 0:
+ left = np.min(np.nonzero(img[index]))
+ right = np.max(np.nonzero(img[index]))
+ mid = np.abs(left - right) / 2 + left
+ return int(mid)
+
+ def execute(self):
+ global error
+ global integral
+ global current
+ global v_mult
+ global v
+ global w
+ red_upper = (179, 255, 255)
+ # red_lower=(0,255,171)
+ # red_lower = (0, 255, 15)
+ red_lower = (0, 110, 15)
+ # kernel = np.ones((8, 8), np.uint8)
+ '''
+ if type(self.previous_image) == int:
+ self.previous_image = self.camera.getImage().data
+ self.previous_timestamp = timestamp
+ if (timestamp - self.previous_timestamp >= 0.085):
+ self.previous_image = self.camera.getImage().data
+ image = self.previous_image
+ '''
+
+ image = self.camera.getImage().data
+ if image.shape == (3, 3, 3):
+ time.sleep(3)
+
+ '''
+ save_dataset = False
+ if (timestamp - self.previous_timestamp >= 0.085):
+ #if (timestamp - self.previous_timestamp >= 0.045):
+ #print(timestamp)
+ self.previous_timestamp = timestamp
+ save_dataset = True
+ # Save dataset
+ rgb_image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB)
+ cv2.imwrite(GENERATED_DATASETS_DIR + 'difficult_situations_01_06_2022/many_curves_4/' + str(self.iteration) + '.png', rgb_image)
+ '''
+ image = self.handler.transform_image(image, self.config['ImageTranform'])
+ # Save dataset
+ # rgb_image = cv2.cvtColor(image, cv2.COLOR_BGR2RGB)
+ # cv2.imwrite(GENERATED_DATASETS_DIR + 'montreal_12_05_2022_opencv_anticlockwise_1/' + str(self.iteration) + '.png', rgb_image)
+ image_cropped = image[230:, :, :]
+ image_blur = cv2.GaussianBlur(image_cropped, (27, 27), 0)
+
+ image_hsv = cv2.cvtColor(image_blur, cv2.COLOR_RGB2HSV)
+ image_mask = cv2.inRange(image_hsv, red_lower, red_upper)
+ # image_eroded = cv2.erode(image_mask, kernel, iterations=3)
+
+ rows, cols = image_mask.shape
+ rows = rows - 1 # para evitar desbordamiento
+
+ alt = 0
+ ff = cv2.reduce(image_mask, 1, cv2.REDUCE_SUM, dtype=cv2.CV_32S)
+ if np.count_nonzero(ff[:, 0]) > 0:
+ alt = np.min(np.nonzero(ff[:, 0]))
+
+ points = []
+ for i in range(3):
+ if i == 0:
+ index = alt
+ else:
+ index = rows // (2 * i)
+ points.append((self.getPoint(index, image_mask), index))
+
+ points.append((self.getPoint(rows, image_mask), rows))
+
+ l, l2 = self.detect(points)
+
+ if current == 'straight':
+ kp = 0.001
+ kd = 0.004
+ ki = 0
+ cv2.circle(image_mask, (0, cols // 2), 6, RED, -1)
+
+ if image_cropped[0, cols // 2, 0] < 170 and v > 8:
+ accel = -0.4
+ else:
+ accel = 0.3
+
+ v_mult = v_mult + accel
+ if v_mult > 6:
+ v_mult = 6
+ v = V * v_mult
+ else:
+ kp = 0.011 # 0.018
+ kd = 0.011 # 0.011
+ ki = 0
+ v_mult = V_MULT
+ v = V_CURVE * v_mult
+
+ new_error = cols // 2 - points[0][0]
+
+ proportional = kp * new_error
+ error_diff = new_error - error
+ error = new_error
+ derivative = kd * error_diff
+ integral = integral + error
+ integral = ki * integral
+
+ w = proportional + derivative + integral
+ self.motors.sendW(w)
+ self.motors.sendV(v)
+
+ self.update_frame('frame_0', image)
+ current_w_normalized = w
+
+ v = np.interp(np.array([v]), (6.5, 24), (0, 1))[0]
+ w = np.interp(np.array([w]), (-7.1, 7.1), (0, 1))[0]
+ if self.previous_v != None:
+ a = np.array((v, w))
+ b = np.array((self.previous_v, self.previous_w))
+ distance = np.linalg.norm(a - b)
+ self.suddenness_distance.append(distance)
+ self.previous_v = v
+ self.previous_w = w
+
+ if self.previous_w_normalized != None:
+ self.update_frame('frame_2', image, current_w_normalized, self.previous_w_normalized, str(round(distance, 4)))
+ self.previous_w_normalized = current_w_normalized
+
+ '''
+ if (save_dataset):
+ # Save dataset
+ iteration_data = [str(self.iteration) + '.png', v, w, self.previous_timestamp]
+ with open(GENERATED_DATASETS_DIR + 'difficult_situations_01_06_2022/many_curves_4/data.csv', 'a', encoding='UTF8') as f:
+ writer = csv.writer(f)
+ writer.writerow(iteration_data)
+ print(self.iteration)
+ self.iteration += 1
+ '''
+ image_mask = cv2.cvtColor(image_mask, cv2.COLOR_GRAY2RGB)
+ cv2.circle(image_mask, points[0], 6, GREEN, -1)
+ cv2.circle(image_mask, points[1], 6, GREEN, -1) # punto central rows/2
+ cv2.circle(image_mask, points[2], 6, GREEN, -1)
+ cv2.circle(image_mask, points[3], 6, GREEN, -1)
+ cv2.putText(image_mask, 'w: {:+.2f} v: {}'.format(w, v),
+ (10, 30), cv2.FONT_HERSHEY_SIMPLEX, 1, MAGENTA, 2, cv2.LINE_AA)
+ cv2.putText(image_mask, 'collinearU: {} collinearD: {}'.format(l, l2),
+ (10, 90), cv2.FONT_HERSHEY_SIMPLEX, 1, MAGENTA, 2, cv2.LINE_AA)
+ cv2.putText(image_mask, 'actual: {}'.format(current),
+ (10, 60), cv2.FONT_HERSHEY_SIMPLEX, 1, MAGENTA, 2, cv2.LINE_AA)
+
+ self.update_frame('frame_1', image_mask)
diff --git a/behavior_metrics/brains/gazebo/f1rl/brain_f1_dummy.py b/behavior_metrics/brains/gazebo/f1rl/brain_f1_dummy.py
index 238714ad..71e97bc1 100644
--- a/behavior_metrics/brains/gazebo/f1rl/brain_f1_dummy.py
+++ b/behavior_metrics/brains/gazebo/f1rl/brain_f1_dummy.py
@@ -1,53 +1,53 @@
-#!/usr/bin/python
-# -*- coding: utf-8 -*-
-
-
-class Brain:
- """Specific dummy brain for the f1 robot."""
-
- def __init__(self, sensors, actuators, handler=None):
- """Constructor of the class.
-
- Arguments:
- sensors {robot.sensors.Sensors} -- Sensors instance of the robot
- actuators {robot.actuators.Actuators} -- Actuators instance of the robot
-
- Keyword Arguments:
- handler {brains.brain_handler.Brains} -- Handler of the current brain. Communication with the controller
- (default: {None})
- """
- self.camera = sensors.get_camera('camera_0')
- # self.laser = sensors.get_laser('laser_0')
- self.pose = sensors.get_pose3d('pose3d_0')
- self.motors = actuators.get_motor('motors_0')
- self.handler = handler
-
- def update_frame(self, frame_id, data):
- """Update the information to be shown in one of the GUI's frames.
-
- Arguments:
- frame_id {str} -- Id of the frame that will represent the data
- data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc)
- """
- self.handler.update_frame(frame_id, data)
-
- def update_pose(self, pose_data):
- """Update the pose 3D information obtained from the robot.
-
- Arguments:
- data {*} -- Data to be updated, will be retrieved later by the UI.
- """
- self.handler.update_pose3d(pose_data)
-
- def execute(self):
- """Main loop of the brain. This will be called iteratively each TIME_CYCLE (see pilot.py)"""
-
- self.update_pose(self.pose.getPose3d())
- v = 0
- w = 0.8
- self.motors.sendV(v)
- self.motors.sendW(w)
- image = self.camera.getImage().data
- self.update_frame('frame_0', image)
- # laser_data = self.laser.getLaserData()
- # self.update_frame('frame_0', laser_data)
+#!/usr/bin/python
+# -*- coding: utf-8 -*-
+
+
+class Brain:
+ """Specific dummy brain for the f1 robot."""
+
+ def __init__(self, sensors, actuators, handler=None):
+ """Constructor of the class.
+
+ Arguments:
+ sensors {robot.sensors.Sensors} -- Sensors instance of the robot
+ actuators {robot.actuators.Actuators} -- Actuators instance of the robot
+
+ Keyword Arguments:
+ handler {brains.brain_handler.Brains} -- Handler of the current brain. Communication with the controller
+ (default: {None})
+ """
+ self.camera = sensors.get_camera('camera_0')
+ # self.laser = sensors.get_laser('laser_0')
+ self.pose = sensors.get_pose3d('pose3d_0')
+ self.motors = actuators.get_motor('motors_0')
+ self.handler = handler
+
+ def update_frame(self, frame_id, data):
+ """Update the information to be shown in one of the GUI's frames.
+
+ Arguments:
+ frame_id {str} -- Id of the frame that will represent the data
+ data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc)
+ """
+ self.handler.update_frame(frame_id, data)
+
+ def update_pose(self, pose_data):
+ """Update the pose 3D information obtained from the robot.
+
+ Arguments:
+ data {*} -- Data to be updated, will be retrieved later by the UI.
+ """
+ self.handler.update_pose3d(pose_data)
+
+ def execute(self):
+ """Main loop of the brain. This will be called iteratively each TIME_CYCLE (see pilot.py)"""
+
+ self.update_pose(self.pose.getPose3d())
+ v = 0
+ w = 0.8
+ self.motors.sendV(v)
+ self.motors.sendW(w)
+ image = self.camera.getImage().data
+ self.update_frame('frame_0', image)
+ # laser_data = self.laser.getLaserData()
+ # self.update_frame('frame_0', laser_data)
diff --git a/behavior_metrics/brains/gazebo/f1rl/f1_follow_line_camera_dqn.py b/behavior_metrics/brains/gazebo/f1rl/f1_follow_line_camera_dqn.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/f1rl/f1_follow_line_qlearn.py b/behavior_metrics/brains/gazebo/f1rl/f1_follow_line_qlearn.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/f1rl/f1_follow_line_qlearn_laser.py b/behavior_metrics/brains/gazebo/f1rl/f1_follow_line_qlearn_laser.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/f1rl/train.py b/behavior_metrics/brains/gazebo/f1rl/train.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/brains/gazebo/turtlebot/brain_turtlebot_opencv2.py b/behavior_metrics/brains/gazebo/turtlebot/brain_turtlebot_opencv2.py
index 573d6d55..36ea0c00 100644
--- a/behavior_metrics/brains/gazebo/turtlebot/brain_turtlebot_opencv2.py
+++ b/behavior_metrics/brains/gazebo/turtlebot/brain_turtlebot_opencv2.py
@@ -1,32 +1,32 @@
-#!/usr/bin/python
-# -*- coding: utf-8 -*-
-
-
-class Brain:
-
- def __init__(self, sensors, actuators, handler=None):
- self.camera_l = sensors.get_camera('camera_0')
- self.camera_r = sensors.get_camera('camera_1')
- self.laser = sensors.get_laser('laser_0')
- self.pose = sensors.get_pose3d('pose3d_0')
- self.motors = actuators.get_motor('motors_0')
- self.handler = handler
-
- def update_frame(self, frame_id, data):
- self.handler.update_frame(frame_id, data)
-
- def update_pose(self, pose_data):
- self.handler.update_pose3d(pose_data)
-
- def execute(self):
- self.update_pose(self.pose.getPose3d())
- v = 0
- w = 0.8
- self.motors.sendV(v)
- self.motors.sendW(w)
- image_l = self.camera_l.getImage().data
- image_r = self.camera_r.getImage().data
- laser_data = self.laser.getLaserData()
- self.update_frame('frame_0', image_l)
- self.update_frame('frame_1', image_r)
- self.update_frame('frame_3', laser_data)
+#!/usr/bin/python
+# -*- coding: utf-8 -*-
+
+
+class Brain:
+
+ def __init__(self, sensors, actuators, handler=None):
+ self.camera_l = sensors.get_camera('camera_0')
+ self.camera_r = sensors.get_camera('camera_1')
+ self.laser = sensors.get_laser('laser_0')
+ self.pose = sensors.get_pose3d('pose3d_0')
+ self.motors = actuators.get_motor('motors_0')
+ self.handler = handler
+
+ def update_frame(self, frame_id, data):
+ self.handler.update_frame(frame_id, data)
+
+ def update_pose(self, pose_data):
+ self.handler.update_pose3d(pose_data)
+
+ def execute(self):
+ self.update_pose(self.pose.getPose3d())
+ v = 0
+ w = 0.8
+ self.motors.sendV(v)
+ self.motors.sendW(w)
+ image_l = self.camera_l.getImage().data
+ image_r = self.camera_r.getImage().data
+ laser_data = self.laser.getLaserData()
+ self.update_frame('frame_0', image_l)
+ self.update_frame('frame_1', image_r)
+ self.update_frame('frame_3', laser_data)
diff --git a/behavior_metrics/carla_maps_waypoints/carla_map_10HD_waypoints.csv.csv b/behavior_metrics/carla_maps_waypoints/carla_map_10HD_waypoints.csv.csv
index 3cd90e3a..b2c4424e 100644
--- a/behavior_metrics/carla_maps_waypoints/carla_map_10HD_waypoints.csv.csv
+++ b/behavior_metrics/carla_maps_waypoints/carla_map_10HD_waypoints.csv.csv
@@ -1,3067 +1,3067 @@
-X,Y
--27.017662048339844,66.21400451660156
--28.86618423461914,66.14916229248047
--30.66202735900879,65.89645385742188
--32.42102813720703,65.45503234863281
--34.12340545654297,64.82988739013672
--35.75004196166992,64.02803039550781
--37.282649993896484,63.0584716796875
--38.63057327270508,61.96412658691406
--39.74671936035156,60.686317443847656
--40.627471923828125,59.23619842529297
--41.24679946899414,57.65663528442383
--41.58638381958008,55.99433135986328
--41.653968811035156,54.193668365478516
--41.65959930419922,52.19367599487305
--48.57393264770508,82.6451187133789
--52.07392120361328,82.65496826171875
--48.579559326171875,80.64512634277344
--52.07954788208008,80.65497589111328
--48.58518981933594,78.64513397216797
--52.08517837524414,78.65498352050781
--48.590816497802734,76.6451416015625
--52.09080505371094,76.65499114990234
--48.59644317626953,74.64514923095703
--52.096431732177734,74.65499877929688
--48.602073669433594,72.64515686035156
--52.1020622253418,72.6550064086914
--48.60770034790039,70.6451644897461
--52.107688903808594,70.65501403808594
--48.61333084106445,68.64517211914062
--52.113319396972656,68.65502166748047
--48.61895751953125,66.64517974853516
--52.11894607543945,66.655029296875
--48.62458419799805,64.64518737792969
--52.12457275390625,64.65503692626953
--48.63021469116211,62.64520263671875
--52.13020324707031,62.655052185058594
--48.635841369628906,60.64521026611328
--52.13582992553711,60.655059814453125
--48.6414680480957,58.64521789550781
--52.141456604003906,58.655067443847656
--48.647098541259766,56.645225524902344
--52.14708709716797,56.65507507324219
--48.65272521972656,54.645233154296875
--52.152713775634766,54.65508270263672
--48.658355712890625,52.645240783691406
--52.15834426879883,52.65509033203125
-26.435718536376953,16.757444381713867
-26.44544219970703,13.257457733154297
-28.43570899963379,16.76300048828125
-28.445432662963867,13.26301383972168
-30.435701370239258,16.768558502197266
-30.445425033569336,13.268571853637695
-32.43569564819336,16.77411460876465
-32.44541931152344,13.274127960205078
-34.435691833496094,16.779672622680664
-34.44541549682617,13.279685974121094
-36.43568420410156,16.785228729248047
-36.44540786743164,13.285242080688477
-38.435672760009766,16.790786743164062
-38.445396423339844,13.290800094604492
-40.435665130615234,16.796342849731445
-40.44538879394531,13.296356201171875
-42.4356575012207,16.80190086364746
-42.44538116455078,13.30191421508789
-44.43564987182617,16.807456970214844
-44.44537353515625,13.307470321655273
-46.43564224243164,16.81301498413086
-46.44536590576172,13.313028335571289
-48.43563461303711,16.818571090698242
-48.44535827636719,13.318584442138672
-50.43562698364258,16.82413101196289
-50.445350646972656,13.32414436340332
-52.43561935424805,16.829687118530273
-52.445343017578125,13.329700469970703
-54.435611724853516,16.83524513244629
-54.445335388183594,13.335258483886719
-56.43560028076172,16.84079933166504
-56.4453239440918,13.340812683105469
-26.40376853942871,28.25739860534668
-26.41349220275879,24.75741195678711
-28.403759002685547,28.262954711914062
-28.413482666015625,24.762968063354492
-30.403751373291016,28.268512725830078
-30.413475036621094,24.768526077270508
-32.403743743896484,28.27406883239746
-32.41346740722656,24.77408218383789
-34.40373992919922,28.279626846313477
-34.4134635925293,24.779640197753906
-36.40373229980469,28.28518295288086
-36.413455963134766,24.78519630432129
-38.40372085571289,28.290740966796875
-38.41344451904297,24.790754318237305
-40.40371322631836,28.296297073364258
-40.41343688964844,24.796310424804688
-42.40370559692383,28.301855087280273
-42.413429260253906,24.801868438720703
-44.4036979675293,28.307411193847656
-44.413421630859375,24.807424545288086
-46.403690338134766,28.312969207763672
-46.413414001464844,24.8129825592041
-48.403682708740234,28.318525314331055
-48.41340637207031,24.818538665771484
-50.4036750793457,28.324085235595703
-50.41339874267578,24.824098587036133
-52.40366744995117,28.329641342163086
-52.41339111328125,24.829654693603516
-54.40365982055664,28.3351993560791
-54.41338348388672,24.83521270751953
-56.403648376464844,28.34075355529785
-56.41337203979492,24.84076690673828
-43.88934326171875,41.89961624145508
-43.86312484741211,39.89978790283203
-43.863258361816406,38.02463150024414
-44.10757064819336,36.347923278808594
-44.637516021728516,34.7385139465332
-45.43720245361328,33.24468231201172
-46.482635498046875,31.91122817993164
-47.7593879699707,30.743762969970703
-49.197444915771484,29.782909393310547
-50.765567779541016,29.053367614746094
-52.426841735839844,28.572307586669922
-54.142154693603516,28.351058959960938
-56.04743576049805,28.339763641357422
--106.7159194946289,-2.2476232051849365
--106.73834228515625,-0.2477264553308487
--106.76075744628906,1.7521477937698364
--106.65607452392578,3.465054750442505
--106.25785064697266,5.106363773345947
--105.57762908935547,6.652252674102783
--104.63652801513672,8.054685592651367
--103.46380615234375,9.270086288452148
--102.05567169189453,10.304855346679688
--100.48445892333984,11.197660446166992
--98.82495880126953,11.913121223449707
--97.09711456298828,12.442638397216797
--95.32169342041016,12.779848098754883
--93.52003479003906,12.920698165893555
--91.5557861328125,12.929587364196777
--89.55579376220703,12.935144424438477
--88.67606353759766,24.437633514404297
--90.67620086669922,24.43207550048828
--92.67619323730469,24.4265193939209
--94.67618560791016,24.420961380004883
--96.92293548583984,24.256216049194336
--99.12898254394531,23.7534236907959
--101.23404693603516,22.923866271972656
--103.19002532958984,21.786497116088867
--104.95222473144531,20.3673038482666
--106.47366333007812,18.71123504638672
--107.74635314941406,16.8935546875
--108.7806396484375,14.930402755737305
--109.56012725830078,12.85287857055664
--110.07247161865234,10.693896293640137
--110.3095474243164,8.487656593322754
--110.31298065185547,6.391233921051025
--110.29056549072266,4.391359806060791
--110.26815032958984,2.3914854526519775
--110.2457275390625,0.391611248254776
--110.22331237792969,-1.6080056428909302
--107.23321533203125,43.899478912353516
--107.21080017089844,41.89960479736328
--107.1883773803711,39.89973068237305
--107.16596221923828,37.89985656738281
--107.14354705810547,35.89998245239258
--107.12112426757812,33.900108337402344
--107.09870910644531,31.900232315063477
--107.0762939453125,29.900358200073242
--107.05387115478516,27.900484085083008
--107.03145599365234,25.900609970092773
--107.00904083251953,23.90073585510254
--106.98661804199219,21.900861740112305
--106.96420288085938,19.900985717773438
--106.94178771972656,17.901111602783203
--106.91936492919922,15.901237487792969
--106.8969497680664,13.901363372802734
--106.87452697753906,11.9014892578125
--106.85211181640625,9.901615142822266
--106.82969665527344,7.9017415046691895
--106.8072738647461,5.901867389678955
--106.78485870361328,3.9019930362701416
--106.76244354248047,1.9021190404891968
--106.74002075195312,-0.09775511920452118
--106.71760559082031,-2.0976293087005615
-85.98224639892578,66.35848999023438
-87.98269653320312,66.36105346679688
-89.87236785888672,66.34451293945312
-91.54315185546875,66.09268951416016
-93.14398193359375,65.55207061767578
-94.62535095214844,64.73937225341797
-95.94143676757812,63.67972946166992
-97.05847930908203,62.40235137939453
-97.94198608398438,60.952213287353516
-98.56529998779297,59.372676849365234
-98.91018676757812,57.70998764038086
-98.98468017578125,55.90883255004883
-98.99832153320312,53.90888214111328
-83.04327392578125,24.91476058959961
-85.04326629638672,24.920316696166992
-87.04325866699219,24.925874710083008
-89.04325103759766,24.93143081665039
-91.04324340820312,24.936988830566406
-93.26031494140625,24.802600860595703
-95.44329071044922,24.386388778686523
-97.55535888671875,23.695146560668945
-99.56200408935547,22.74016761779785
-101.43045806884766,21.537046432495117
-103.13019561767578,20.10544204711914
-104.63346099853516,18.468734741210938
-105.91030883789062,16.723594665527344
-107.0205307006836,14.871212005615234
-107.95658111572266,12.925009727478027
-108.71060943603516,10.901317596435547
-109.27629852294922,8.817115783691406
-109.64889526367188,6.689895153045654
-109.82527160644531,4.537504196166992
-109.8492660522461,2.486750364303589
-109.86289978027344,0.4867967665195465
-109.87653350830078,-1.5129233598709106
-109.89017486572266,-3.512876510620117
-106.07840728759766,42.18954086303711
-106.09205627441406,40.18917465209961
-106.1056900024414,38.1892204284668
-106.11933135986328,36.189266204833984
-106.13297271728516,34.18931198120117
-106.14661407470703,32.18935775756836
-106.16024780273438,30.18940544128418
-106.13570404052734,28.065265655517578
-105.82524871826172,25.831296920776367
-105.1906509399414,23.666975021362305
-104.24563598632812,21.61906623840332
-103.0105972290039,19.731821060180664
-101.51223754882812,18.046016693115234
-99.80238342285156,16.60074234008789
-97.91151428222656,15.403153419494629
-95.87468719482422,14.475281715393066
-93.73014831542969,13.834546089172363
-91.51814270019531,13.492974281311035
-89.37653350830078,13.432313919067383
-87.37654113769531,13.426756858825684
-85.37654876708984,13.421199798583984
-83.37641906738281,13.415641784667969
-83.0335464477539,28.41474723815918
-85.0335464477539,28.420303344726562
-87.03353118896484,28.425859451293945
-88.89058685302734,28.472421646118164
-90.62525177001953,28.740413665771484
-92.30603790283203,29.246244430541992
-93.9004898071289,29.980152130126953
-95.37783813476562,30.927968978881836
-96.65447235107422,32.0466194152832
-97.68544006347656,33.3599853515625
-98.4537353515625,34.842403411865234
-98.93246459960938,36.441986083984375
-99.1048812866211,38.10274124145508
-99.0926742553711,40.073665618896484
-99.07903289794922,42.07429885864258
-109.57832336425781,42.213409423828125
-106.07840728759766,42.18954086303711
-109.59196472167969,40.21345520019531
-106.09204864501953,40.1895866394043
-109.60560607910156,38.2135009765625
-106.1056900024414,38.189632415771484
-109.6192398071289,36.21355056762695
-106.11932373046875,36.18968200683594
-109.63288116455078,34.21359634399414
-106.13296508789062,34.189727783203125
-109.64652252197266,32.21364212036133
-106.1466064453125,32.18977355957031
-109.66016387939453,30.213685989379883
-106.16024780273438,30.189817428588867
-109.67379760742188,28.21373176574707
-106.17388153076172,28.189863204956055
-109.68743896484375,26.21377944946289
-106.1875228881836,26.189910888671875
-109.70108032226562,24.213825225830078
-106.20116424560547,24.189956665039062
-109.7147216796875,22.2138729095459
-106.21480560302734,22.190004348754883
-109.72835540771484,20.213918685913086
-106.22843933105469,20.19005012512207
-109.74199676513672,18.213966369628906
-106.24208068847656,18.19009780883789
-109.7556381225586,16.214012145996094
-106.25572204589844,16.190143585205078
-109.76927947998047,14.214058876037598
-106.26936340332031,14.190189361572266
-109.78292083740234,12.214106559753418
-106.28300476074219,12.190237045288086
-109.79655456542969,10.214152336120605
-106.29663848876953,10.190282821655273
-109.81019592285156,8.214198112487793
-106.3102798461914,8.190328598022461
-109.82383728027344,6.2142438888549805
-106.32392120361328,6.190374851226807
-109.83747863769531,4.214293479919434
-106.33756256103516,4.19042444229126
-109.85111236572266,2.214339256286621
-106.3511962890625,2.190469980239868
-109.86475372314453,0.21438491344451904
-106.36483764648438,0.19051580131053925
-109.8783950805664,-1.7855693101882935
-106.37847900390625,-1.8094384670257568
-109.89203643798828,-3.7855234146118164
-106.39212036132812,-3.8093926906585693
-102.57848358154297,42.16566848754883
-99.07856750488281,42.14179992675781
-102.59212493896484,40.165714263916016
-99.09220886230469,40.141845703125
-102.60576629638672,38.1657600402832
-99.10585021972656,38.14189147949219
-102.61940002441406,36.165809631347656
-99.1194839477539,36.14194107055664
-102.63304138183594,34.165855407714844
-99.13312530517578,34.14198684692383
-102.64668273925781,32.16590118408203
-99.14676666259766,32.142032623291016
-102.66032409667969,30.16594886779785
-99.16040802001953,30.142080307006836
-102.67395782470703,28.16599464416504
-99.17404174804688,28.142126083374023
-102.6875991821289,26.16604232788086
-99.18768310546875,26.142173767089844
-102.70124053955078,24.166088104248047
-99.20132446289062,24.14221954345703
-102.71488189697266,22.166135787963867
-99.2149658203125,22.14226722717285
-102.728515625,20.166181564331055
-99.22859954833984,20.14231300354004
-102.74215698242188,18.166229248046875
-99.24224090576172,18.14236068725586
-102.75579833984375,16.166275024414062
-99.2558822631836,16.142406463623047
-102.76943969726562,14.16632080078125
-99.26952362060547,14.142451286315918
-102.7830810546875,12.16636848449707
-99.28316497802734,12.142498970031738
-102.79671478271484,10.166414260864258
-99.29679870605469,10.142544746398926
-102.81035614013672,8.166460037231445
-99.31044006347656,8.142590522766113
-102.8239974975586,6.166505336761475
-99.32408142089844,6.142636299133301
-102.83763885498047,4.166554927825928
-99.33772277832031,4.142685890197754
-102.85127258300781,2.1666009426116943
-99.35135650634766,2.1427316665649414
-102.86491394042969,0.16664667427539825
-99.36499786376953,0.14277756214141846
-102.87855529785156,-1.8333075046539307
-99.3786392211914,-1.857176661491394
-102.89219665527344,-3.833261728286743
-99.39228057861328,-3.857131004333496
--28.517200469970703,130.03573608398438
--30.30147361755371,129.92938232421875
--32.03142166137695,129.5891876220703
--33.700050354003906,129.0198516845703
--35.27717971801758,128.23175048828125
--36.734256744384766,127.23908996582031
--38.04182052612305,126.0622329711914
--39.16381072998047,124.72201538085938
--40.0830192565918,123.23536682128906
--40.78063201904297,121.63275146484375
--41.24235153198242,119.94696807861328
--41.458736419677734,118.2125473022461
--41.47919845581055,116.2996597290039
--70.48973083496094,128.9029083251953
--68.70108795166016,129.21397399902344
--66.88970184326172,129.33590698242188
--65.07550048828125,129.26742553710938
--63.27846145629883,129.00926208496094
--61.51835632324219,128.5642547607422
--59.81455993652344,127.93727111816406
--58.185829162597656,127.13525390625
--56.70155334472656,126.18061065673828
--55.390159606933594,125.03644561767578
--54.2611083984375,123.71202850341797
--53.33891677856445,122.236083984375
--52.643585205078125,120.64066314697266
--52.19021987915039,118.96038818359375
--51.9886589050293,117.23174285888672
--51.98202133178711,115.31092834472656
--71.26968383789062,132.3148956298828
--69.39166259765625,132.69732666015625
--67.4975814819336,132.99000549316406
--65.59546661376953,133.19189453125
--63.81114959716797,133.224853515625
--62.03615951538086,133.03965759277344
--60.29707336425781,132.63906860351562
--58.619930267333984,132.02906799316406
--57.02983856201172,131.21884155273438
--55.55060958862305,130.220458984375
--54.10551452636719,128.99887084960938
--52.78818893432617,127.7421875
--51.633087158203125,126.35982513427734
--50.64110565185547,124.85610961914062
--49.82487869262695,123.25019836425781
--49.19478988647461,121.56254577636719
--48.758880615234375,119.81464385986328
--48.5226936340332,118.02875518798828
--48.47959899902344,116.16610717773438
--52.142601013183594,-43.38029861450195
--48.6427001953125,-43.35388946533203
--45.142799377441406,-43.327484130859375
--41.64289855957031,-43.30107498168945
--52.157691955566406,-41.38035583496094
--48.65779113769531,-41.353946685791016
--45.15789031982422,-41.32754135131836
--41.657989501953125,-41.30113220214844
--52.17278289794922,-39.38041305541992
--48.672882080078125,-39.35400390625
--45.17298126220703,-39.327598571777344
--41.67308044433594,-39.30118942260742
--52.18787384033203,-37.380470275878906
--48.68797302246094,-37.354061126708984
--45.188072204589844,-37.32765579223633
--41.68817138671875,-37.301246643066406
--52.202964782714844,-35.38052749633789
--48.70306396484375,-35.35411834716797
--45.203163146972656,-35.32771301269531
--41.70326232910156,-35.30130386352539
--52.218055725097656,-33.380584716796875
--48.71815490722656,-33.35417556762695
--45.21825408935547,-33.3277702331543
--41.718353271484375,-33.301361083984375
--52.23314666748047,-31.38064193725586
--48.733245849609375,-31.354232788085938
--45.23334503173828,-31.327823638916016
--41.73344421386719,-31.301414489746094
--52.24823760986328,-29.380699157714844
--48.74833679199219,-29.354290008544922
--45.248435974121094,-29.327880859375
--41.74853515625,-29.301471710205078
--52.263328552246094,-27.380756378173828
--48.763427734375,-27.354347229003906
--45.263526916503906,-27.327938079833984
--41.76362609863281,-27.301528930664062
--52.278419494628906,-25.380813598632812
--48.77851867675781,-25.35440444946289
--45.27861785888672,-25.32799530029297
--41.778717041015625,-25.301586151123047
--52.29351043701172,-23.380870819091797
--48.793609619140625,-23.354461669921875
--45.29370880126953,-23.328052520751953
--41.79380798339844,-23.30164337158203
--52.30860137939453,-21.38092613220215
--48.80870056152344,-21.354516983032227
--45.308799743652344,-21.328107833862305
--41.80889892578125,-21.301698684692383
--52.323692321777344,-19.380983352661133
--48.82379150390625,-19.35457420349121
--45.323890686035156,-19.32816505432129
--41.82398986816406,-19.301755905151367
--52.338783264160156,-17.381040573120117
--48.83888244628906,-17.354631423950195
--45.33898162841797,-17.328222274780273
--41.839080810546875,-17.30181312561035
-57.403648376464844,28.34353256225586
-57.41337203979492,24.84354591369629
-57.43560028076172,16.843578338623047
-57.44532775878906,13.343591690063477
-59.40364074707031,28.349088668823242
-59.41336441040039,24.849102020263672
-59.43559265136719,16.84913444519043
-59.44532012939453,13.34914779663086
-61.40363311767578,28.354646682739258
-61.41335678100586,24.854660034179688
-61.435585021972656,16.854692459106445
-61.4453125,13.354705810546875
-63.40362548828125,28.36020278930664
-63.41334915161133,24.86021614074707
-63.435577392578125,16.860248565673828
-63.44530487060547,13.360261917114258
-65.40361022949219,28.365760803222656
-65.41333770751953,24.865774154663086
-65.43556213378906,16.865806579589844
-65.4452896118164,13.365819931030273
-67.40360260009766,28.37131690979004
-67.413330078125,24.87133026123047
-67.43555450439453,16.871362686157227
-67.44528198242188,13.371376037597656
-69.40359497070312,28.376874923706055
-69.41332244873047,24.876888275146484
-69.435546875,16.876920700073242
-69.44527435302734,13.376934051513672
-71.4035873413086,28.382431030273438
-71.41331481933594,24.882444381713867
-71.43553924560547,16.882476806640625
-71.44526672363281,13.382490158081055
-73.40357971191406,28.387989044189453
-73.4133071899414,24.888002395629883
-73.43553161621094,16.88803482055664
-73.44525909423828,13.38804817199707
-75.40357208251953,28.393545150756836
-75.41329956054688,24.893558502197266
-75.4355239868164,16.893590927124023
-75.44525146484375,13.393604278564453
-77.40357208251953,28.39910316467285
-77.41329956054688,24.89911651611328
-77.4355239868164,16.89914894104004
-77.44525146484375,13.399162292480469
-79.40355682373047,28.404659271240234
-79.41328430175781,24.904672622680664
-79.43550872802734,16.904705047607422
-79.44523620605469,13.404718399047852
-81.40354919433594,28.41021728515625
-81.41327667236328,24.91023063659668
-81.43550109863281,16.910263061523438
-81.44522857666016,13.410276412963867
--28.71629524230957,24.604232788085938
--30.71660614013672,24.598674774169922
--32.90773010253906,24.49801254272461
--35.12482833862305,24.075864791870117
--37.25544738769531,23.331411361694336
--39.25299835205078,22.280921936035156
--41.073814392089844,20.947364807128906
--42.67808151245117,19.35989761352539
--44.03073501586914,17.55322265625
--45.10219192504883,15.566841125488281
--45.859161376953125,13.515207290649414
--46.47522735595703,11.612456321716309
--47.09511947631836,9.681135177612305
--47.653873443603516,7.663947105407715
--48.10423278808594,5.619825839996338
--48.444908142089844,3.5545921325683594
--48.6749382019043,1.474125862121582
--48.793663024902344,-0.6156484484672546
--88.685791015625,27.937620162963867
--90.68607330322266,27.93206024169922
--92.68606567382812,27.926504135131836
--94.6860580444336,27.92094612121582
--96.8669204711914,27.824932098388672
--99.07166290283203,27.43034553527832
--101.20113372802734,26.736164093017578
--103.21484375,25.75558853149414
--105.07449340820312,24.50726890563965
--106.76020812988281,22.98198127746582
--108.18182373046875,21.178382873535156
--109.27572631835938,19.15913963317871
--110.00997924804688,16.983177185058594
--110.36316680908203,14.713991165161133
--110.3823013305664,12.574618339538574
--110.35987854003906,10.57474422454834
--110.33746337890625,8.574869155883789
--110.31504821777344,6.574995040893555
--110.2926254272461,4.575120449066162
--110.27021026611328,2.575246572494507
--110.24779510498047,0.5753723978996277
--110.22537231445312,-1.4242451190948486
-109.30042266845703,82.96246337890625
-105.80050659179688,82.93859100341797
-109.31405639648438,80.96250915527344
-105.81414031982422,80.93863677978516
-109.32769775390625,78.96255493164062
-105.8277816772461,78.93868255615234
-109.34133911132812,76.96260070800781
-105.84142303466797,76.93872833251953
-109.35498046875,74.962646484375
-105.85506439208984,74.93877410888672
-109.36862182617188,72.96269226074219
-105.86870574951172,72.9388198852539
-109.38225555419922,70.96273803710938
-105.88233947753906,70.9388656616211
-109.3958969116211,68.9627914428711
-105.89598083496094,68.93891906738281
-109.40953826904297,66.96283721923828
-105.90962219238281,66.93896484375
-109.42317962646484,64.96288299560547
-105.92326354980469,64.93901062011719
-109.43682098388672,62.962928771972656
-105.93690490722656,62.93906021118164
-109.45045471191406,60.962974548339844
-105.9505386352539,60.93910598754883
-109.46409606933594,58.96302032470703
-105.96417999267578,58.939151763916016
-109.47773742675781,56.96306610107422
-105.97782135009766,56.9391975402832
-109.49137115478516,54.963111877441406
-105.991455078125,54.93924331665039
-83.07522583007812,13.41480541229248
-85.03021240234375,13.414726257324219
-86.83293914794922,13.274620056152344
-88.60968780517578,12.939041137695312
-90.33931732177734,12.411982536315918
-92.00128173828125,11.699708938598633
-93.57579803466797,10.810693740844727
-95.04048919677734,9.758234024047852
-96.3056640625,8.567916870117188
-97.37969970703125,7.202645301818848
-98.23870086669922,5.6927995681762695
-98.86356353759766,4.071972846984863
-99.24036407470703,2.3762311935424805
-99.36173248291016,0.622090756893158
-99.37537384033203,-1.3778626918792725
-99.3890151977539,-3.3778162002563477
--28.72602081298828,28.104219436645508
--28.71629524230957,24.604232788085938
--28.694067001342773,16.604265213012695
--28.684343338012695,13.104278564453125
--26.726028442382812,28.10977554321289
--26.7163028717041,24.60978889465332
--26.694074630737305,16.609821319580078
--26.684350967407227,13.109834671020508
--24.726036071777344,28.115333557128906
--24.716310501098633,24.615346908569336
--24.694082260131836,16.615379333496094
--24.684358596801758,13.115392684936523
--22.726043701171875,28.12088966369629
--22.716318130493164,24.62090301513672
--22.694089889526367,16.620935440063477
--22.68436622619629,13.120948791503906
--20.726051330566406,28.126447677612305
--20.716325759887695,24.626461029052734
--20.6940975189209,16.626493453979492
--20.68437385559082,13.126506805419922
--18.726058959960938,28.132003784179688
--18.716333389282227,24.632017135620117
--18.69410514831543,16.632049560546875
--18.68438148498535,13.132062911987305
--16.7260684967041,28.137561798095703
--16.71634292602539,24.637575149536133
--16.694114685058594,16.63760757446289
--16.684391021728516,13.13762092590332
--14.726075172424316,28.143117904663086
--14.716350555419922,24.643131256103516
--14.694122314453125,16.643163681030273
--14.684396743774414,13.143177032470703
--12.726082801818848,28.1486759185791
--12.716358184814453,24.64868927001953
--12.694129943847656,16.64872169494629
--12.684404373168945,13.148735046386719
--10.726089477539062,28.154232025146484
--10.716364860534668,24.654245376586914
--10.694136619567871,16.654277801513672
--10.68441104888916,13.154291152954102
--8.726097106933594,28.1597900390625
--8.7163724899292,24.65980339050293
--8.694144248962402,16.659835815429688
--8.684418678283691,13.159849166870117
--6.726106643676758,28.165346145629883
--6.716381549835205,24.665359497070312
--6.694153308868408,16.66539192199707
--6.684428691864014,13.1654052734375
--4.726114273071289,28.1709041595459
--4.716389179229736,24.670917510986328
--4.6941609382629395,16.670949935913086
--4.684436321258545,13.170963287353516
--2.726121664047241,28.17646026611328
--2.7163968086242676,24.67647361755371
--2.69416880607605,16.67650604248047
--2.684443950653076,13.176519393920898
--0.7261292934417725,28.182018280029297
--0.7164044976234436,24.682031631469727
--0.6941763162612915,16.682064056396484
--0.6844515204429626,13.182077407836914
-1.2738630771636963,28.18757438659668
-1.2835878133773804,24.68758773803711
-1.3058159351348877,16.687620162963867
-1.3155407905578613,13.187633514404297
-3.273855447769165,28.193132400512695
-3.2835803031921387,24.693145751953125
-3.3058083057403564,16.693178176879883
-3.31553316116333,13.193191528320312
-5.2738494873046875,28.198688507080078
-5.28357458114624,24.698701858520508
-5.305802822113037,16.698734283447266
-5.315527439117432,13.198747634887695
-7.273841857910156,28.204246520996094
-7.283566951751709,24.704259872436523
-7.305795192718506,16.70429229736328
-7.3155198097229,13.204305648803711
-9.273834228515625,28.209802627563477
-9.28355884552002,24.709815979003906
-9.305787086486816,16.709848403930664
-9.315512657165527,13.209861755371094
-11.273826599121094,28.215360641479492
-11.283551216125488,24.715373992919922
-11.305779457092285,16.71540641784668
-11.315505027770996,13.21541976928711
-13.273818969726562,28.220916748046875
-13.283543586730957,24.720930099487305
-13.305771827697754,16.720962524414062
-13.315497398376465,13.220975875854492
-15.273807525634766,28.22647476196289
-15.28353214263916,24.72648811340332
-15.305760383605957,16.726520538330078
-15.315485954284668,13.226533889770508
-17.273799896240234,28.232030868530273
-17.283525466918945,24.732044219970703
-17.305753707885742,16.73207664489746
-17.31547737121582,13.23208999633789
-19.273792266845703,28.23758888244629
-19.283517837524414,24.73760223388672
-19.30574607849121,16.737634658813477
-19.31546974182129,13.237648010253906
-21.273784637451172,28.243144989013672
-21.283510208129883,24.7431583404541
-21.30573844909668,16.74319076538086
-21.315462112426758,13.243204116821289
-23.27377700805664,28.248703002929688
-23.28350257873535,24.748716354370117
-23.30573081970215,16.748748779296875
-23.315454483032227,13.248762130737305
-25.27376937866211,28.25425910949707
-25.28349494934082,24.7542724609375
-25.305723190307617,16.754304885864258
-25.315446853637695,13.254318237304688
--103.21614074707031,-2.2083919048309326
--103.23856353759766,-0.2086300402879715
--103.2192153930664,1.6438419818878174
--102.96272277832031,3.357247829437256
--102.44989776611328,5.01210880279541
--101.69257354736328,6.5703125
--100.70816802978516,7.995970726013184
--99.51937103271484,9.25624942779541
--98.13174438476562,10.363348007202148
--96.61287689208984,11.290770530700684
--94.99005126953125,12.021167755126953
--93.28866577148438,12.543092727661133
--91.5354232788086,12.848367691040039
--89.72577667236328,12.934672355651855
--66.8261489868164,24.498342514038086
--64.82615661621094,24.50389862060547
--62.80895233154297,24.508527755737305
--60.624412536621094,24.374526977539062
--58.46719741821289,24.004953384399414
--56.362632751464844,23.404142379760742
--54.335426330566406,22.579153060913086
--52.40938949584961,21.5396671295166
--50.60712432861328,20.297895431518555
--48.94979476928711,18.868408203125
--47.46052932739258,17.27355194091797
--46.146366119384766,15.564069747924805
--44.99060821533203,13.743748664855957
--44.00253677368164,11.827221870422363
--43.19010925292969,9.829895973205566
--42.55984115600586,7.767829895019531
--42.11681365966797,5.657598495483398
--41.86457443237305,3.5161664485931396
--41.80257034301758,1.3860589265823364
--41.80820083618164,-0.6141355633735657
--78.07583618164062,27.967100143432617
--78.06610870361328,24.467113494873047
--78.04388427734375,16.467145919799805
--78.0341567993164,12.967159271240234
--76.07584381103516,27.97265625
--76.06611633300781,24.47266960144043
--76.04389190673828,16.472702026367188
--76.03416442871094,12.972715377807617
--74.07585144042969,27.978214263916016
--74.06612396240234,24.478227615356445
--74.04389953613281,16.478260040283203
--74.03417205810547,12.978273391723633
--72.07585906982422,27.9837703704834
--72.06613159179688,24.483783721923828
--72.04390716552734,16.483816146850586
--72.0341796875,12.983829498291016
--70.07586669921875,27.989328384399414
--70.0661392211914,24.489341735839844
--70.04391479492188,16.4893741607666
--70.03418731689453,12.989387512207031
--68.07587432861328,27.994884490966797
--68.06614685058594,24.494897842407227
--68.0439224243164,16.494930267333984
--68.03419494628906,12.994943618774414
--114.23278045654297,43.821014404296875
--114.21036529541016,41.82114028930664
--114.18794250488281,39.82085037231445
--114.16552734375,37.82097625732422
--114.14310455322266,35.821102142333984
--114.11214447021484,33.769737243652344
--113.88878631591797,31.570682525634766
--113.40167999267578,29.414657592773438
--112.65792846679688,27.33317756652832
--111.66839599609375,25.356672286987305
--110.44757843017578,23.5140380859375
--109.01329040527344,21.83220672607422
--107.37828063964844,20.333969116210938
--105.56774139404297,19.05193519592285
--103.61077880859375,18.00696563720703
--101.53826141357422,17.215547561645508
--99.38288879394531,16.690162658691406
--97.17865753173828,16.439104080200195
--95.08568572998047,16.4197940826416
--93.085693359375,16.425350189208984
--91.08570098876953,16.430908203125
--89.0857162475586,16.436464309692383
--88.685791015625,27.937620162963867
--88.67606353759766,24.437633514404297
--88.65383911132812,16.437665939331055
--88.64411163330078,12.937679290771484
--86.68579864501953,27.94317626953125
--86.67607116699219,24.44318962097168
--86.65384674072266,16.443222045898438
--86.64411926269531,12.943235397338867
--84.68580627441406,27.948734283447266
--84.67607879638672,24.448747634887695
--84.65385437011719,16.448780059814453
--84.64412689208984,12.948793411254883
--82.6858139038086,27.95429039001465
--82.67608642578125,24.454303741455078
--82.65386199951172,16.454336166381836
--82.64413452148438,12.954349517822266
--80.68582153320312,27.959848403930664
--80.67609405517578,24.459861755371094
--80.65386962890625,16.45989418029785
--80.6441421508789,12.959907531738281
--78.68582916259766,27.965404510498047
--78.67610168457031,24.465417861938477
--78.65387725830078,16.465450286865234
--78.64414978027344,12.965463638305664
-7.407855033874512,-67.89999389648438
-7.409285068511963,-64.39999389648438
-7.410714626312256,-60.899993896484375
-7.412144660949707,-57.399993896484375
-5.44331169128418,-67.90583801269531
-5.421112537384033,-64.4059066772461
-5.3989129066467285,-60.90597915649414
-5.376713752746582,-57.40605163574219
-3.478853940963745,-67.92493438720703
-3.433025360107422,-64.42523193359375
-3.3871965408325195,-60.925533294677734
-3.3413679599761963,-57.42583465576172
-1.4941807985305786,-67.95541381835938
-1.4382917881011963,-64.45585632324219
-1.3824028968811035,-60.95630645751953
-1.3265138864517212,-57.456748962402344
--0.5055642127990723,-67.98735046386719
--0.5614531636238098,-64.48779296875
--0.6173421740531921,-60.988243103027344
--0.6732311248779297,-57.488685607910156
--2.5168769359588623,-68.01824188232422
--2.565066337585449,-64.51856994628906
--2.613255500793457,-61.01890182495117
--2.661444902420044,-57.51923370361328
--4.5343427658081055,-68.04209899902344
--4.570794582366943,-64.54228973388672
--4.607245922088623,-61.04248046875
--4.643697738647461,-57.54267120361328
--41.82001876831055,-4.8147735595703125
--45.32000732421875,-4.804924488067627
--48.81999206542969,-4.795074939727783
--52.31998062133789,-4.785225868225098
--41.825645446777344,-6.814765453338623
--45.32563400268555,-6.8049163818359375
--48.825618743896484,-6.795066833496094
--52.32560729980469,-6.785217761993408
--41.83384323120117,-8.829364776611328
--45.33378601074219,-8.809771537780762
--48.83373260498047,-8.790177345275879
--52.333675384521484,-8.770584106445312
--41.84503936767578,-10.829333305358887
--45.3449821472168,-10.80974006652832
--48.84492874145508,-10.790145874023438
--52.344871520996094,-10.770552635192871
--41.85272979736328,-12.809256553649902
--45.352725982666016,-12.8030366897583
--48.852718353271484,-12.7968168258667
--52.35271453857422,-12.790596961975098
--41.85203552246094,-14.78698444366455
--45.35202407836914,-14.795611381530762
--48.85201644897461,-14.804238319396973
--52.35200500488281,-14.812865257263184
--41.84298324584961,-16.764692306518555
--45.34290313720703,-16.788166046142578
--48.84282684326172,-16.81163787841797
--52.34274673461914,-16.835111618041992
--41.81126403808594,-1.7042442560195923
--45.31125259399414,-1.6943949460983276
--48.81123733520508,-1.684545636177063
--52.31122589111328,-1.6746963262557983
--41.816890716552734,-3.7042365074157715
--45.31687927246094,-3.694387197494507
--48.816864013671875,-3.684537649154663
--52.31685256958008,-3.6746883392333984
--41.483009338378906,114.94529724121094
--44.98299789428711,114.95514678955078
--48.48298263549805,114.9649887084961
--51.98297119140625,114.97483825683594
--41.4886360168457,112.94530487060547
--44.988624572753906,112.95515441894531
--48.488609313964844,112.96499633789062
--51.98859786987305,112.97484588623047
--41.494266510009766,110.9453125
--44.99425506591797,110.95516204833984
--48.494239807128906,110.96500396728516
--51.99422836303711,110.974853515625
--41.49989318847656,108.94532012939453
--44.999881744384766,108.95516967773438
--48.4998664855957,108.96501159667969
--51.999855041503906,108.97486114501953
--41.50551986694336,106.94532775878906
--45.00550842285156,106.9551773071289
--48.5054931640625,106.96501922607422
--52.0054817199707,106.97486877441406
--41.51115036010742,104.9453353881836
--45.011138916015625,104.95518493652344
--48.51112365722656,104.96502685546875
--52.011112213134766,104.9748764038086
--41.51677703857422,102.94534301757812
--45.01676559448242,102.95519256591797
--48.51675033569336,102.96503448486328
--52.01673889160156,102.97488403320312
--41.52240753173828,100.94535064697266
--45.022396087646484,100.9552001953125
--48.52238082885742,100.96504211425781
--52.022369384765625,100.97489166259766
--41.52803421020508,98.94535827636719
--45.02802276611328,98.95520782470703
--48.52800750732422,98.96504974365234
--52.02799606323242,98.97489929199219
--41.533660888671875,96.94536590576172
--45.03364944458008,96.95521545410156
--48.533634185791016,96.96505737304688
--52.03362274169922,96.97490692138672
--41.53929138183594,94.94537353515625
--45.03927993774414,94.9552230834961
--48.53926467895508,94.9650650024414
--52.03925323486328,94.97491455078125
--41.544918060302734,92.94538879394531
--45.04490661621094,92.95523834228516
--48.544891357421875,92.96508026123047
--52.04487991333008,92.97492980957031
--41.55054473876953,90.94538879394531
--45.050533294677734,90.95523834228516
--48.55051803588867,90.96508026123047
--52.050506591796875,90.97492980957031
--41.556175231933594,88.94540405273438
--45.0561637878418,88.95525360107422
--48.556148529052734,88.96509552001953
--52.05613708496094,88.97494506835938
--41.56180191040039,86.94540405273438
--45.061790466308594,86.95525360107422
--48.56177520751953,86.96509552001953
--52.061763763427734,86.97494506835938
--41.56743240356445,84.94541931152344
--45.067420959472656,84.95526885986328
--48.567405700683594,84.9651107788086
--52.0673942565918,84.97496032714844
--41.57305908203125,82.94541931152344
--45.07304763793945,82.95526885986328
--48.57303237915039,82.9651107788086
--52.073020935058594,82.97496032714844
--66.80392456054688,16.498376846313477
--66.79419708251953,12.998390197753906
--64.8039321899414,16.50393295288086
--64.79420471191406,13.003946304321289
--62.80393600463867,16.509490966796875
--62.79420852661133,13.009504318237305
--60.8039436340332,16.515047073364258
--60.79421615600586,13.015060424804688
--58.803951263427734,16.520605087280273
--58.79422378540039,13.020618438720703
--56.803958892822266,16.526161193847656
--56.79423141479492,13.026174545288086
--54.8039665222168,16.531719207763672
--54.79423904418945,13.031732559204102
--52.80397415161133,16.537275314331055
--52.794246673583984,13.037288665771484
--50.80398178100586,16.54283332824707
--50.794254302978516,13.0428466796875
--48.80398941040039,16.548389434814453
--48.79426193237305,13.048402786254883
--46.80399703979492,16.55394744873047
--46.79426956176758,13.053960800170898
--44.80400466918945,16.55950355529785
--44.79427719116211,13.059516906738281
--42.804012298583984,16.565061569213867
--42.79428482055664,13.065074920654297
--40.804019927978516,16.57061767578125
--40.79429244995117,13.07063102722168
--38.80402755737305,16.576175689697266
--38.7943000793457,13.076189041137695
--36.80403518676758,16.58173179626465
--36.794307708740234,13.081745147705078
--34.80404281616211,16.587289810180664
--34.794315338134766,13.087303161621094
--32.80405044555664,16.592845916748047
--32.7943229675293,13.092859268188477
--30.804058074951172,16.598403930664062
--30.794334411621094,13.098417282104492
--28.804065704345703,16.603960037231445
--28.794342041015625,13.103973388671875
-109.92987823486328,-9.334196090698242
-106.42996215820312,-9.358065605163574
-102.93003845214844,-9.38193416595459
-99.43012237548828,-9.405803680419922
-109.94214630126953,-11.346802711486816
-106.44218444824219,-11.362241744995117
-102.94221496582031,-11.377681732177734
-99.44225311279297,-11.393120765686035
-109.947021484375,-13.367796897888184
-106.447021484375,-13.36923599243164
-102.947021484375,-13.370674133300781
-99.447021484375,-13.372113227844238
-109.94380187988281,-15.38857650756836
-106.4438247680664,-15.376158714294434
-102.94384002685547,-15.363741874694824
-99.44386291503906,-15.351324081420898
-109.93930053710938,-17.36873435974121
-106.43930053710938,-17.36954116821289
-102.93930053710938,-17.370346069335938
-99.43930053710938,-17.371152877807617
-109.94525146484375,-19.339298248291016
-106.4453125,-19.35972023010254
-102.94537353515625,-19.380144119262695
-99.4454345703125,-19.40056610107422
-109.96227264404297,-21.309799194335938
-106.4625015258789,-21.349836349487305
-102.96273040771484,-21.38987159729004
-99.46295928955078,-21.429908752441406
--66.8261489868164,24.498342514038086
--64.82615661621094,24.50389862060547
--62.693565368652344,24.456562042236328
--60.5024528503418,24.16035270690918
--58.36332321166992,23.601032257080078
--56.30764389038086,22.786832809448242
--54.36567306518555,21.729732513427734
--52.56597900390625,20.445283889770508
--50.95553207397461,18.977115631103516
--49.49954605102539,17.50987434387207
--48.090599060058594,15.758028984069824
--46.94546890258789,13.823406219482422
--46.08749008178711,11.74543285369873
--45.53415298461914,9.566461563110352
--45.29673767089844,7.330901145935059
--45.29166793823242,5.265802383422852
--45.29729461669922,3.265810012817383
--45.302921295166016,1.2658182382583618
--45.30855178833008,-0.7341741323471069
-106.07840728759766,42.18954086303711
-106.09205627441406,40.18917465209961
-106.1056900024414,38.1892204284668
-106.11933135986328,36.189266204833984
-106.07976531982422,34.063968658447266
-105.82299041748047,31.89616584777832
-105.34017181396484,29.767274856567383
-104.63664245605469,27.700794219970703
-103.72016906738281,25.719541549682617
-102.60087585449219,23.845382690429688
-101.26289367675781,22.078367233276367
-99.6535415649414,20.48746681213379
-97.82252502441406,19.157672882080078
-95.81178283691406,18.11945152282715
-93.66738891601562,17.396581649780273
-91.4384536743164,17.005624771118164
-89.27434539794922,16.932044982910156
-87.27435302734375,16.92648696899414
-85.27436065673828,16.920930862426758
-83.27420806884766,16.91537094116211
--67.15464782714844,-58.193748474121094
--67.11819458007812,-61.69355773925781
--65.15475463867188,-58.172916412353516
--65.11830139160156,-61.672725677490234
--63.15486526489258,-58.1520881652832
--63.11841583251953,-61.65189743041992
--61.154972076416016,-58.13125991821289
--61.11852264404297,-61.63106918334961
--59.15507888793945,-58.11042785644531
--59.118629455566406,-61.61023712158203
--57.155189514160156,-58.089599609375
--57.11874008178711,-61.58940887451172
--55.155296325683594,-58.06877136230469
--55.11884689331055,-61.568580627441406
--53.1554069519043,-58.04793930053711
--53.11895751953125,-61.54774856567383
--51.155513763427734,-58.0271110534668
--51.11906433105469,-61.526920318603516
--49.15562057495117,-58.00627899169922
--49.119171142578125,-61.50608825683594
--47.155731201171875,-57.985450744628906
--47.11928176879883,-61.485260009765625
--45.15584182739258,-57.964622497558594
--45.11939239501953,-61.46443176269531
--43.155948638916016,-57.943790435791016
--43.11949920654297,-61.443599700927734
--41.15605545043945,-57.9229621887207
--41.119606018066406,-61.42277145385742
--39.15616226196289,-57.90213394165039
--39.119712829589844,-61.40194320678711
--37.156272888183594,-57.88130187988281
--37.11982345581055,-61.38111114501953
--35.1563835144043,-57.8604736328125
--35.11993408203125,-61.36028289794922
--33.156490325927734,-57.83964538574219
--33.12004089355469,-61.339454650878906
--31.156599044799805,-57.81881332397461
--31.120147705078125,-61.31862258911133
--29.156709671020508,-57.7979850769043
--29.120258331298828,-61.297794342041016
-83.04327392578125,24.91476058959961
-85.04326629638672,24.920316696166992
-87.04325866699219,24.925872802734375
-89.04325103759766,24.93143081665039
-91.04324340820312,24.936986923217773
-93.22521209716797,24.87339210510254
-95.5011215209961,24.424331665039062
-97.65592193603516,23.565095901489258
-99.61637115478516,22.324880599975586
-101.3158187866211,20.745853424072266
-102.69650268554688,18.881675720214844
-103.71170043945312,16.950847625732422
-104.54739379882812,14.98498821258545
-105.22718048095703,12.959928512573242
-105.7469253540039,10.888010025024414
-106.10345458984375,8.781859397888184
-106.29459381103516,6.65431547164917
-106.33491516113281,4.578386306762695
-106.34855651855469,2.578432559967041
-106.36219787597656,0.5784792304039001
-106.3758316040039,-1.4213203191757202
-106.38947296142578,-3.421273708343506
--45.18675994873047,42.54542922973633
--45.192386627197266,40.54543685913086
--45.19801712036133,38.54544448852539
--45.25642776489258,36.431758880615234
--45.4990348815918,34.29103088378906
--45.93022155761719,32.1801872253418
--46.54659652709961,30.11580467224121
--47.34332275390625,28.11410140991211
--48.31414031982422,26.1907958984375
--49.45142364501953,24.36099624633789
--50.76707458496094,22.622722625732422
--52.311439514160156,21.023685455322266
--54.047752380371094,19.63545036315918
--55.94745635986328,18.480846405029297
--57.979305267333984,17.578861236572266
--60.10987854003906,16.944332122802734
--62.304141998291016,16.58769416809082
--64.46632385253906,16.504871368408203
--66.46631622314453,16.499313354492188
-109.50276184082031,53.29315185546875
-106.00284576416016,53.269283294677734
-102.50292205810547,53.24541091918945
-99.00300598144531,53.22154235839844
-109.51640319824219,51.29319763183594
-106.01648712158203,51.26932907104492
-102.51656341552734,51.24545669555664
-99.01664733886719,51.221588134765625
-109.53004455566406,49.293243408203125
-106.0301284790039,49.26937484741211
-102.53020477294922,49.24550247192383
-99.03028869628906,49.22163391113281
-109.5436782836914,47.29329299926758
-106.04376220703125,47.26942443847656
-102.54383850097656,47.24555206298828
-99.0439224243164,47.221683502197266
-109.55731964111328,45.293338775634766
-106.05740356445312,45.26947021484375
-102.55747985839844,45.24559783935547
-99.05756378173828,45.22172927856445
-109.57096099853516,43.29338455200195
-106.071044921875,43.26951599121094
-102.57112121582031,43.245643615722656
-99.07120513916016,43.22177505493164
-27.14229393005371,66.28325653076172
-29.14229393005371,66.28581237792969
-31.023746490478516,66.26502990722656
-32.707393646240234,66.00928497314453
-34.32426071166992,65.47466278076172
-35.8285026550293,64.67633819580078
-37.17747116088867,63.636940002441406
-38.338077545166016,62.382720947265625
-39.280731201171875,60.95339584350586
-39.97834396362305,59.38977813720703
-40.41234588623047,57.7335090637207
-40.5711669921875,56.02871322631836
-40.548606872558594,54.07141876220703
--41.68677520751953,42.535579681396484
--41.688926696777344,40.57392883300781
--41.542572021484375,38.80292892456055
--41.17356491088867,37.06462860107422
--40.587806701660156,35.386905670166016
--39.794700622558594,33.796669006347656
--38.80697250366211,32.319427490234375
--37.65940475463867,31.02106475830078
--36.33360290527344,29.9392147064209
--34.8490104675293,29.088247299194336
--33.24543762207031,28.490991592407227
--31.565889358520508,28.163454055786133
--29.766407012939453,28.101327896118164
--67.08174133300781,-65.19336700439453
--67.0452880859375,-68.69317626953125
--65.08184814453125,-65.17253875732422
--65.04539489746094,-68.67234802246094
--63.08196258544922,-65.1517105102539
--63.04551315307617,-68.65151977539062
--61.082069396972656,-65.1308822631836
--61.04561996459961,-68.63069152832031
--59.082176208496094,-65.11004638671875
--59.04572677612305,-68.60985565185547
--57.0822868347168,-65.08921813964844
--57.04583740234375,-68.58902740478516
--55.082393646240234,-65.06838989257812
--55.04594421386719,-68.56819915771484
--53.08250427246094,-65.04756164550781
--53.04605484008789,-68.54737091064453
--51.082611083984375,-65.0267333984375
--51.04616165161133,-68.52654266357422
--49.08271789550781,-65.00589752197266
--49.046268463134766,-68.50570678710938
--47.082828521728516,-64.98506927490234
--47.04637908935547,-68.48487854003906
--45.08293914794922,-64.96424102783203
--45.04648971557617,-68.46405029296875
--43.083045959472656,-64.94341278076172
--43.04659652709961,-68.44322204589844
--41.083152770996094,-64.9225845336914
--41.04670333862305,-68.42239379882812
--39.08325958251953,-64.9017562866211
--39.046810150146484,-68.40156555175781
--37.083370208740234,-64.88092041015625
--37.04692077636719,-68.38072967529297
--35.08348083496094,-64.86009216308594
--35.04703140258789,-68.35990142822266
--33.083587646484375,-64.83926391601562
--33.04713821411133,-68.33907318115234
--31.083694458007812,-64.81843566894531
--31.047243118286133,-68.31824493408203
--29.083805084228516,-64.797607421875
--29.047353744506836,-68.29741668701172
-109.89640045166016,-4.425507068634033
-106.396484375,-4.449376106262207
-102.89656066894531,-4.473245620727539
-99.39664459228516,-4.497114658355713
-109.91004180908203,-6.4254608154296875
-106.41012573242188,-6.449329853057861
-102.91020202636719,-6.473199367523193
-99.41028594970703,-6.497068405151367
-109.9236831665039,-8.425414085388184
-106.42376708984375,-8.449283599853516
-102.92384338378906,-8.473152160644531
-99.4239273071289,-8.497021675109863
--48.6427001953125,-43.3538932800293
--48.62760925292969,-45.35411834716797
--48.612518310546875,-47.354061126708984
--48.481910705566406,-49.532466888427734
--48.12403869628906,-51.68540573120117
--47.54281997680664,-53.789066314697266
--46.7446403503418,-55.820350646972656
--45.73826599121094,-57.7569465637207
--44.52067565917969,-59.59299087524414
--42.97726058959961,-61.29964828491211
--41.16213607788086,-62.71391296386719
--39.12992477416992,-63.79323196411133
--36.9417724609375,-64.505126953125
--34.663516998291016,-64.82818603515625
--32.55117416381836,-64.8337173461914
--30.55128288269043,-64.8128890991211
--28.5513916015625,-64.79206085205078
-58.05227279663086,66.3227767944336
-56.05227279663086,66.32022094726562
-54.052276611328125,66.31766510009766
-52.052276611328125,66.31510162353516
-50.05228042602539,66.31254577636719
-48.05228042602539,66.30998992919922
-46.05228042602539,66.30743408203125
-44.052284240722656,66.30487823486328
-42.05228805541992,66.30232238769531
-40.05228805541992,66.29975891113281
-38.05228805541992,66.29720306396484
-36.05228805541992,66.29464721679688
-34.05229187011719,66.2920913696289
-32.05229568481445,66.28953552246094
-30.05229377746582,66.28697204589844
-28.052295684814453,66.28441619873047
--0.14773565530776978,130.2100830078125
--0.16924521327018738,133.71002197265625
--0.19075477123260498,137.2099609375
--0.21226432919502258,140.70989990234375
--2.147697925567627,130.19778442382812
--2.1692073345184326,133.69772338867188
--2.1907169818878174,137.19766235351562
--2.212226390838623,140.69760131835938
--4.147660255432129,130.18551635742188
--4.169169902801514,133.68544006347656
--4.19067907333374,137.1853790283203
--4.212188720703125,140.685302734375
--6.147622108459473,130.1732177734375
--6.169131755828857,133.6731414794922
--6.190640926361084,137.17308044433594
--6.212150573730469,140.67300415039062
--8.147583961486816,130.16091918945312
--8.16909408569336,133.66085815429688
--8.190603256225586,137.16079711914062
--8.212113380432129,140.66073608398438
--10.147546768188477,130.14862060546875
--10.16905689239502,133.6485595703125
--10.190566062927246,137.14849853515625
--10.212076187133789,140.6484375
--12.14750862121582,130.1363525390625
--12.169018745422363,133.6362762451172
--12.19052791595459,137.13621520996094
--12.212038040161133,140.63613891601562
--14.14747142791748,130.12405395507812
--14.168981552124023,133.6239776611328
--14.19049072265625,137.12391662597656
--14.212000846862793,140.62384033203125
--16.147432327270508,130.11175537109375
--16.168941497802734,133.6116943359375
--16.190452575683594,137.11163330078125
--16.21196174621582,140.611572265625
--18.147396087646484,130.09945678710938
--18.16890525817871,133.59939575195312
--18.19041633605957,137.09933471679688
--18.211925506591797,140.59927368164062
--20.147357940673828,130.08718872070312
--20.168867111206055,133.5871124267578
--20.190378189086914,137.08705139160156
--20.21188735961914,140.58697509765625
--22.147319793701172,130.07489013671875
--22.1688289642334,133.57481384277344
--22.190340042114258,137.0747528076172
--22.211849212646484,140.57467651367188
--24.147281646728516,130.06259155273438
--24.168790817260742,133.56253051757812
--24.1903018951416,137.06246948242188
--24.211811065673828,140.56240844726562
--26.147245407104492,130.05029296875
--26.16875457763672,133.55023193359375
--26.190265655517578,137.0501708984375
--26.211774826049805,140.55010986328125
--28.147207260131836,130.03802490234375
--28.168716430664062,133.53794860839844
--28.190227508544922,137.0378875732422
--28.21173667907715,140.53781127929688
--70.48992156982422,128.90286254882812
--71.26968383789062,132.3148956298828
--72.0494384765625,135.72694396972656
--72.8292007446289,139.13897705078125
--72.18624114990234,128.47250366210938
--73.12738800048828,131.84359741210938
--74.06853485107422,135.21469116210938
--75.00968170166016,138.58578491210938
--73.86016845703125,127.96195220947266
--74.96057891845703,131.2844696044922
--76.06098175048828,134.6069793701172
--77.16139221191406,137.92950439453125
--75.5079345703125,127.37236785888672
--76.76510620117188,130.6387939453125
--78.02227783203125,133.90521240234375
--79.27944946289062,137.171630859375
--77.12578582763672,126.70508575439453
--78.53688049316406,129.90802001953125
--79.94798278808594,133.1109619140625
--81.35907745361328,136.31390380859375
--78.71007537841797,125.96162414550781
--80.27189636230469,129.0938262939453
--81.83372497558594,132.2260284423828
--83.39554595947266,135.3582305908203
--80.25720977783203,125.14366149902344
--81.96623229980469,128.1980438232422
--83.67524719238281,131.25242614746094
--85.38426971435547,134.3068084716797
--81.7636947631836,124.2530288696289
--83.61604309082031,127.2226791381836
--85.4683837890625,130.19232177734375
--87.32073211669922,133.16197204589844
--83.22611999511719,123.29176330566406
--85.21759796142578,126.16996002197266
--87.2090835571289,129.04815673828125
--89.2005615234375,131.9263458251953
--84.64117431640625,122.26204681396484
--86.76728057861328,125.04227447509766
--88.89339447021484,127.82250213623047
--91.01950073242188,130.60272216796875
--86.00565338134766,121.16619110107422
--88.26158142089844,123.84215545654297
--90.51750183105469,126.51811981201172
--92.77342987060547,129.194091796875
--87.31647491455078,120.00668334960938
--89.69711303710938,122.57233428955078
--92.0777587890625,125.13797760009766
--94.4583969116211,127.70362854003906
--88.57066345214844,118.78614044189453
--91.07062530517578,121.23567199707031
--93.57059478759766,123.68519592285156
--96.070556640625,126.13472747802734
--89.76539611816406,117.50733947753906
--92.37902069091797,119.83519744873047
--94.9926528930664,122.1630630493164
--97.60627746582031,124.49092102050781
--90.89795684814453,116.17316436767578
--93.61933898925781,118.37409210205078
--96.34071350097656,120.57501983642578
--99.06209564208984,122.77594757080078
--91.96578216552734,114.78662872314453
--94.78875732421875,116.85564422607422
--97.61172485351562,118.9246597290039
--100.43470001220703,120.9936752319336
--92.97467041015625,113.33920288085938
--95.88758087158203,115.27954864501953
--98.80049896240234,117.21988677978516
--101.71340942382812,119.16023254394531
--93.98038482666016,111.78266143798828
--96.94639587402344,113.64083099365234
--99.91239929199219,115.4990005493164
--102.87841033935547,117.35717010498047
--94.94220733642578,110.19862365722656
--97.95899200439453,111.9731674194336
--100.97577667236328,113.7477035522461
--103.99256134033203,115.52224731445312
--95.859375,108.58831024169922
--98.9245834350586,110.27783966064453
--101.98978424072266,111.96736907958984
--105.05499267578125,113.65689849853516
--96.7311782836914,106.9530029296875
--99.8424072265625,108.55620574951172
--102.95364379882812,110.1594009399414
--106.06487274169922,111.76260375976562
--97.55693054199219,105.29396057128906
--100.71175384521484,106.80957794189453
--103.86658477783203,108.32518768310547
--107.02140808105469,109.84080505371094
--98.33599853515625,103.61248779296875
--101.53195190429688,105.0393295288086
--104.7279052734375,106.46617889404297
--107.92385864257812,107.89302062988281
--99.06775665283203,101.90989685058594
--102.30233764648438,103.24685668945312
--105.53692626953125,104.58381652832031
--108.7715072631836,105.9207763671875
--99.75164031982422,100.1875228881836
--103.02233123779297,101.43354797363281
--106.29302215576172,102.67958068847656
--109.56371307373047,103.92560577392578
--100.38712310791016,98.44670867919922
--103.69136047363281,99.600830078125
--106.99560546875,100.75495910644531
--110.29984283447266,101.9090805053711
--100.97370147705078,96.68880462646484
--104.30890655517578,97.7501220703125
--107.64411163330078,98.81144714355469
--110.97931671142578,99.87276458740234
--101.51091766357422,94.91519927978516
--104.87448120117188,95.88288879394531
--108.23805236816406,96.85057067871094
--111.60161590576172,97.8182601928711
--101.99834442138672,93.12726593017578
--105.38764190673828,94.00056457519531
--108.77693939208984,94.87385559082031
--112.1662368774414,95.74715423583984
--102.43561553955078,91.32640075683594
--105.8479995727539,92.10462951660156
--109.26038360595703,92.88285827636719
--112.67276763916016,93.66108703613281
--102.82238006591797,89.51403045654297
--106.25518035888672,90.19657897949219
--109.68798065185547,90.87911987304688
--113.12078094482422,91.5616683959961
--103.1583251953125,87.69155883789062
--106.60887145996094,88.27788543701172
--110.05940246582031,88.86421966552734
--113.50994873046875,89.45054626464844
--103.44322204589844,85.86040496826172
--106.90879821777344,86.35006713867188
--110.37437438964844,86.8397216796875
--113.83995056152344,87.32938385009766
--103.67681121826172,84.02200317382812
--107.15472412109375,84.41460418701172
--110.63262939453125,84.80721282958984
--114.11054229736328,85.19981384277344
--103.85893249511719,82.17778778076172
--107.3464584350586,82.47303009033203
--110.83397674560547,82.76827239990234
--114.32150268554688,83.06351470947266
--103.98943328857422,80.32920837402344
--107.48384857177734,80.52686309814453
--110.97826385498047,80.7245101928711
--114.4726791381836,80.92216491699219
--104.0682144165039,78.47769927978516
--107.56678771972656,78.57760620117188
--111.06536865234375,78.67750549316406
--114.5639419555664,78.77741241455078
--104.09522247314453,76.62471771240234
--107.59522247314453,76.62680053710938
--111.09522247314453,76.62887573242188
--114.59522247314453,76.6309585571289
--104.0781021118164,74.68677520751953
--107.577880859375,74.64754486083984
--111.07766723632812,74.60831451416016
--114.57744598388672,74.56908416748047
--104.0556869506836,72.68689727783203
--107.55546569824219,72.64766693115234
--111.05525207519531,72.60843658447266
--114.5550308227539,72.56920623779297
--104.03327178955078,70.68702697753906
--107.53305053710938,70.64779663085938
--111.0328369140625,70.60856628417969
--114.5326156616211,70.5693359375
--104.01084899902344,68.68714904785156
--107.51062774658203,68.64791870117188
--111.01041412353516,68.60868835449219
--114.51019287109375,68.5694580078125
--103.98843383789062,66.6872787475586
--107.48821258544922,66.6480484008789
--110.98799896240234,66.60881805419922
--114.48777770996094,66.56958770751953
--103.96601867675781,64.6874008178711
--107.4657974243164,64.6481704711914
--110.96558380126953,64.60894012451172
--114.46536254882812,64.56970977783203
--103.94359588623047,62.687530517578125
--107.44337463378906,62.64830017089844
--110.94316101074219,62.60906982421875
--114.44293975830078,62.56983947753906
--103.92118072509766,60.687652587890625
--107.42095947265625,60.64842224121094
--110.92074584960938,60.60919189453125
--114.42052459716797,60.56996154785156
--103.89876556396484,58.687782287597656
--107.39854431152344,58.64855194091797
--110.89833068847656,58.60932159423828
--114.39810943603516,58.570091247558594
--103.8763427734375,56.687904357910156
--107.3761215209961,56.64867401123047
--110.87590789794922,56.60944366455078
--114.37568664550781,56.570213317871094
--103.85392761230469,54.68803405761719
--107.35370635986328,54.6488037109375
--110.8534927368164,54.60957336425781
--114.353271484375,54.570343017578125
--103.83151245117188,52.68815612792969
--107.33129119873047,52.64892578125
--110.8310775756836,52.60969543457031
--114.33085632324219,52.570465087890625
--103.80908966064453,50.68828201293945
--107.30886840820312,50.649051666259766
--110.80865478515625,50.60982131958008
--114.30843353271484,50.57059097290039
--103.78667449951172,48.68840789794922
--107.28645324707031,48.64917755126953
--110.78623962402344,48.609947204589844
--114.28601837158203,48.570716857910156
--103.7642593383789,46.688533782958984
--107.2640380859375,46.6493034362793
--110.76382446289062,46.61007308959961
--114.26360321044922,46.57084274291992
--103.74183654785156,44.68865966796875
--107.24161529541016,44.64942932128906
--110.74140167236328,44.610198974609375
--114.24118041992188,44.57096862792969
--103.21614074707031,-2.2083921432495117
--106.7159194946289,-2.2476232051849365
--110.21570587158203,-2.2868540287017822
--113.71548461914062,-2.326085090637207
--103.1937255859375,-4.208266258239746
--106.6935043334961,-4.247497081756592
--110.19329071044922,-4.286728382110596
--113.69306945800781,-4.325959205627441
--103.17130279541016,-6.208140850067139
--106.67108154296875,-6.247371673583984
--110.17086791992188,-6.286602973937988
--113.67064666748047,-6.325833797454834
--103.14888763427734,-8.208015441894531
--106.64866638183594,-8.247246742248535
--110.14845275878906,-8.286477088928223
--113.64823150634766,-8.325708389282227
--103.12647247314453,-10.207889556884766
--106.62625122070312,-10.24712085723877
--110.12603759765625,-10.286351203918457
--113.62581634521484,-10.325582504272461
--103.10404968261719,-12.207763671875
--106.60382843017578,-12.246994972229004
--110.1036148071289,-12.286225318908691
--113.6033935546875,-12.325456619262695
--103.08163452148438,-14.20763874053955
--106.58141326904297,-14.246870040893555
--110.0811996459961,-14.286100387573242
--113.58097839355469,-14.325331687927246
--103.05921936035156,-16.20751190185547
--106.55899810791016,-16.24674415588379
--110.05878448486328,-16.285974502563477
--113.55856323242188,-16.325206756591797
--103.03679656982422,-18.207386016845703
--106.53657531738281,-18.246618270874023
--110.03636169433594,-18.28584861755371
--113.53614044189453,-18.32508087158203
--103.0143814086914,-20.207260131835938
--106.51416015625,-20.246492385864258
--110.01394653320312,-20.285722732543945
--113.51372528076172,-20.324954986572266
--102.99175262451172,-22.180795669555664
--106.49128723144531,-22.23758316040039
--109.99082946777344,-22.294368743896484
--113.49036407470703,-22.35115623474121
--102.92448425292969,-23.950885772705078
--106.4182357788086,-24.15987777709961
--109.91199493408203,-24.36886978149414
--113.40574645996094,-24.577861785888672
--102.78025817871094,-25.71637535095215
--106.26161193847656,-26.077177047729492
--109.74296569824219,-26.437978744506836
--113.22431945800781,-26.79878044128418
--102.55935668945312,-27.473915100097656
--106.02172088623047,-27.985843658447266
--109.48407745361328,-28.497772216796875
--112.94644165039062,-29.009700775146484
--102.26219940185547,-29.220182418823242
--105.69900512695312,-29.882266998291016
--109.13581848144531,-30.544353485107422
--112.57262420654297,-31.206438064575195
--101.88935089111328,-30.951866149902344
--105.29409790039062,-31.762855529785156
--108.69883728027344,-32.57384490966797
--112.10358428955078,-33.38483428955078
--101.4415054321289,-32.66568374633789
--104.8077392578125,-33.62403869628906
--108.17398071289062,-34.5823974609375
--111.54021453857422,-35.54075241088867
--100.91951751708984,-34.358402252197266
--104.24087524414062,-35.462310791015625
--107.56222534179688,-36.56621551513672
--110.88358306884766,-37.67012405395508
--100.32437896728516,-36.026798248291016
--103.59455871582031,-37.274169921875
--106.86473083496094,-38.52153778076172
--110.1349105834961,-39.7689094543457
--99.65721893310547,-37.667724609375
--102.87002563476562,-39.05619430541992
--106.08283996582031,-40.44466018676758
--109.29564666748047,-41.8331298828125
--98.9192886352539,-39.278072357177734
--102.06864929199219,-40.80501174926758
--105.21800231933594,-42.33195114135742
--108.36736297607422,-43.858890533447266
--98.11199951171875,-40.85478591918945
--101.19194030761719,-42.517303466796875
--104.27188110351562,-44.17981719970703
--107.35182189941406,-45.84233474731445
--97.23687744140625,-42.3948860168457
--100.24156951904297,-44.1898307800293
--103.24625396728516,-45.98477554321289
--106.25094604492188,-47.779720306396484
--96.29557037353516,-43.89544677734375
--99.21932220458984,-45.81942367553711
--102.14307403564453,-47.7433967590332
--105.06682586669922,-49.66737365722656
--95.28986358642578,-45.3536376953125
--98.12713623046875,-47.40299606323242
--100.96441650390625,-49.45235824584961
--103.80168914794922,-51.50171661376953
--94.22167205810547,-46.766685485839844
--96.96709442138672,-48.93754959106445
--99.71251678466797,-51.10841751098633
--102.45793914794922,-53.27928161621094
--93.1077880859375,-48.112548828125
--95.74552917480469,-50.413055419921875
--98.38327026367188,-52.71356201171875
--101.02101135253906,-55.014068603515625
--91.95550537109375,-49.359474182128906
--94.4566421508789,-51.807804107666016
--96.9577865600586,-54.25613021850586
--99.45892333984375,-56.70446014404297
--90.73345184326172,-50.5380973815918
--93.0897216796875,-53.12615203857422
--95.44598388671875,-55.714202880859375
--97.80225372314453,-58.3022575378418
--89.44567108154297,-51.64453125
--91.6492691040039,-54.36375045776367
--93.85286712646484,-57.08296585083008
--96.05646514892578,-59.80218505859375
--88.0964126586914,-52.675106048583984
--90.14006042480469,-55.51649475097656
--92.1837158203125,-58.357887268066406
--94.22736358642578,-61.199275970458984
--86.69014739990234,-53.62641525268555
--88.56708526611328,-56.58058166503906
--90.44402313232422,-59.534751892089844
--92.32096099853516,-62.48891830444336
--85.23152160644531,-54.49531555175781
--86.93553924560547,-57.552490234375
--88.63956451416016,-60.60966491699219
--90.34358215332031,-63.666839599609375
--83.7253646850586,-55.278934478759766
--85.2508316040039,-58.42900848388672
--86.77629852294922,-61.579078674316406
--88.30176544189453,-64.7291488647461
--82.1766586303711,-55.97468185424805
--83.51852416992188,-59.20723342895508
--84.86039733886719,-62.43978500366211
--86.20226287841797,-65.67233276367188
--80.59050750732422,-56.58024978637695
--81.74433898925781,-59.88459014892578
--82.89817810058594,-63.188934326171875
--84.05200958251953,-66.49327087402344
--78.97217559814453,-57.09364318847656
--79.93415832519531,-60.45884704589844
--80.89614868164062,-63.82405090332031
--81.8581314086914,-67.18925476074219
--77.3270034790039,-57.51316452026367
--78.09395599365234,-60.9281005859375
--78.86090850830078,-64.34303283691406
--79.62786102294922,-67.75797271728516
--75.66044616699219,-57.83741760253906
--76.22982788085938,-61.290794372558594
--76.79920959472656,-64.74417114257812
--77.36859130859375,-68.19754791259766
--73.9780044555664,-58.065338134765625
--74.34793090820312,-61.54573440551758
--74.71786499023438,-65.02613067626953
--75.0877914428711,-68.50652313232422
--72.28523254394531,-58.1961669921875
--72.4544906616211,-61.692073822021484
--72.62374114990234,-65.18798065185547
--72.79299926757812,-68.68388366699219
--70.5877456665039,-58.22947692871094
--70.55577087402344,-61.729331970214844
--70.52378845214844,-65.22918701171875
--70.49181365966797,-68.72904205322266
--68.59456634521484,-58.208744049072266
--68.55811309814453,-61.708553314208984
--68.52165985107422,-65.20836639404297
--68.4852066040039,-68.70817565917969
--28.517202377319336,130.03573608398438
--28.538711547851562,133.53567504882812
--30.51716423034668,130.02346801757812
--30.538673400878906,133.5233917236328
--32.51712417602539,130.01116943359375
--32.53863525390625,133.51109313964844
--34.517086029052734,129.99887084960938
--34.538597106933594,133.49880981445312
--36.51704788208008,129.986572265625
--36.53855895996094,133.48651123046875
--38.51700973510742,129.97427368164062
--38.53852081298828,133.47421264648438
--40.516971588134766,129.96200561523438
--40.538482666015625,133.46192932128906
--42.51693344116211,129.94970703125
--42.53844451904297,133.4496307373047
--44.51689529418945,129.93740844726562
--44.53840637207031,133.43734741210938
--46.5168571472168,129.92510986328125
--46.538368225097656,133.425048828125
--48.516822814941406,129.912841796875
--48.538333892822266,133.4127655029297
--50.51678466796875,129.90054321289062
--50.53829574584961,133.4004669189453
--52.516746520996094,129.88824462890625
--52.53825759887695,133.38818359375
--54.51670837402344,129.87594604492188
--54.5382194519043,133.37588500976562
--56.51667022705078,129.86367797851562
--56.53818130493164,133.3636016845703
--58.516632080078125,129.85137939453125
--58.538143157958984,133.35130310058594
--60.51659393310547,129.83908081054688
--60.53810501098633,133.33901977539062
--62.51655960083008,129.8267822265625
--62.53807067871094,133.32672119140625
--64.26628112792969,129.77456665039062
--64.45392608642578,133.26953125
--66.01110076904297,129.63919067382812
--66.36474609375,133.12127685546875
--67.74750518798828,129.42098999023438
--68.26634979248047,132.88232421875
--69.47157287597656,129.12046813964844
--70.1544418334961,132.55320739746094
--27.836780548095703,-57.784236907958984
--27.800329208374023,-61.2840461730957
--27.76387596130371,-64.78385925292969
--27.72742462158203,-68.2836685180664
--25.836889266967773,-57.76340866088867
--25.800437927246094,-61.26321792602539
--25.76398468017578,-64.76303100585938
--25.7275333404541,-68.2628402709961
--23.836997985839844,-57.742576599121094
--23.800546646118164,-61.24238586425781
--23.76409339904785,-64.74219512939453
--23.727642059326172,-68.24200439453125
--21.837106704711914,-57.72174835205078
--21.800655364990234,-61.2215576171875
--21.764202117919922,-64.72136688232422
--21.727750778198242,-68.22117614746094
--19.83721351623535,-57.70092010498047
--19.800762176513672,-61.20072937011719
--19.76430892944336,-64.7005386352539
--19.72785758972168,-68.20034790039062
--17.837324142456055,-57.68008804321289
--17.800872802734375,-61.17989730834961
--17.764419555664062,-64.6797103881836
--17.727968215942383,-68.17951965332031
--15.837430953979492,-57.65925979614258
--15.800978660583496,-61.1590690612793
--15.764527320861816,-64.65888214111328
--15.72807502746582,-68.15869140625
--13.837539672851562,-57.638427734375
--13.801087379455566,-61.13823699951172
--13.764636039733887,-64.63804626464844
--13.72818374633789,-68.13785552978516
--11.837648391723633,-57.61759948730469
--11.801196098327637,-61.117408752441406
--11.764744758605957,-64.61721801757812
--11.728292465209961,-68.11702728271484
--9.837757110595703,-57.596771240234375
--9.801304817199707,-61.096580505371094
--9.764853477478027,-64.59638977050781
--9.728401184082031,-68.09619903564453
--7.837865829467773,-57.5759391784668
--7.8014140129089355,-61.075748443603516
--7.7649617195129395,-64.5755615234375
--7.728509902954102,-68.07537078857422
--5.837974548339844,-57.555110931396484
--5.801522731781006,-61.0549201965332
--5.76507043838501,-64.55473327636719
--5.728618621826172,-68.0545425415039
--67.15464782714844,-58.19374465942383
--65.15410614013672,-58.172908782958984
--63.24685287475586,-58.13529586791992
--61.503944396972656,-57.9042854309082
--59.809104919433594,-57.43671798706055
--58.19428634643555,-56.74140167236328
--56.6899299621582,-55.83144760131836
--55.3316535949707,-54.729557037353516
--54.19142150878906,-53.46065139770508
--53.27783966064453,-52.019962310791016
--52.61628723144531,-50.447509765625
--52.225162506103516,-48.787017822265625
--52.114803314208984,-47.06452560424805
--52.1298942565918,-45.06428909301758
--28.560218811035156,137.03561401367188
--28.581727981567383,140.53555297851562
--30.5601806640625,137.02333068847656
--30.581689834594727,140.52325439453125
--32.560142517089844,137.0110321044922
--32.5816535949707,140.51095581054688
--34.56010437011719,136.99874877929688
--34.58161544799805,140.49868774414062
--36.56006622314453,136.9864501953125
--36.58157730102539,140.48638916015625
--38.560028076171875,136.97415161132812
--38.581539154052734,140.47409057617188
--40.55998992919922,136.9618682861328
--40.58150100708008,140.4617919921875
--42.55995178222656,136.94956970214844
--42.58146286010742,140.44949340820312
--44.559913635253906,136.93728637695312
--44.581424713134766,140.43722534179688
--46.55987548828125,136.92498779296875
--46.58138656616211,140.4249267578125
--48.55984115600586,136.91270446777344
--48.58135223388672,140.41262817382812
--50.5598030090332,136.90040588378906
--50.58131408691406,140.40032958984375
--52.55976486206055,136.88812255859375
--52.581275939941406,140.3880615234375
--54.55972671508789,136.87582397460938
--54.58123779296875,140.37576293945312
--56.559688568115234,136.86354064941406
--56.581199645996094,140.36346435546875
--58.55965042114258,136.8512420654297
--58.58116149902344,140.35116577148438
--60.55961227416992,136.83895874023438
--60.58112335205078,140.33889770507812
--62.55957794189453,136.82666015625
--62.58108901977539,140.32659912109375
--64.64156341552734,136.76449584960938
--64.82920837402344,140.25946044921875
--66.7183837890625,136.60336303710938
--67.07202911376953,140.08544921875
--68.78519439697266,136.34365844726562
--69.30403900146484,139.80499267578125
--70.83731842041016,135.98594665527344
--71.52018737792969,139.41868591308594
--0.21226438879966736,140.70989990234375
--0.19075478613376617,137.2099609375
--0.16924519836902618,133.71002197265625
--0.147735595703125,130.2100830078125
-1.7829740047454834,140.7223663330078
-1.8076318502426147,137.2224578857422
-1.8322898149490356,133.72254943847656
-1.856947660446167,130.22264099121094
-3.7618916034698486,140.74024963378906
-3.800549030303955,137.24046325683594
-3.8392062187194824,133.7406768798828
-3.877863645553589,130.2408905029297
-5.740721702575684,140.7660675048828
-5.793377876281738,137.26646423339844
-5.846034049987793,133.76686096191406
-5.898690223693848,130.2672576904297
-7.719432830810547,140.7998046875
-7.7860870361328125,137.30043029785156
-7.852741241455078,133.8010711669922
-7.919395446777344,130.30169677734375
-9.711109161376953,140.8401641845703
-9.783038139343262,137.34091186523438
-9.854968070983887,133.84164428710938
-9.926897048950195,130.34239196777344
-11.725129127502441,140.87965393066406
-11.787455558776855,137.38021850585938
-11.84978199005127,133.88076782226562
-11.912108421325684,130.38133239746094
-13.745875358581543,140.91160583496094
-13.79420280456543,137.4119415283203
-13.842531204223633,133.9122772216797
-13.89085865020752,130.41261291503906
-15.766733169555664,140.9354705810547
-15.80106258392334,137.43563842773438
-15.8353910446167,133.93582153320312
-15.869720458984375,130.4359893798828
-17.787670135498047,140.95126342773438
-17.808000564575195,137.45132446289062
-17.82832908630371,133.95138549804688
-17.84865951538086,130.45144653320312
-44.02894973754883,52.548702239990234
-40.52924728393555,52.59458541870117
-44.00273132324219,50.54887390136719
-40.503028869628906,50.594757080078125
-43.97651672363281,48.54904556274414
-40.47681427001953,48.59492874145508
-43.95029830932617,46.549217224121094
-40.45059585571289,46.59510040283203
-43.92407989501953,44.54938888549805
-40.42437744140625,44.595272064208984
-43.89786148071289,42.549560546875
-40.39815902709961,42.59544372558594
-109.97942352294922,-22.602590560913086
-106.47980499267578,-22.654197692871094
-102.98018646240234,-22.70580291748047
-99.4805679321289,-22.757410049438477
-109.9553451538086,-24.868633270263672
-106.45761108398438,-24.742660522460938
-102.95988464355469,-24.616687774658203
-99.46215057373047,-24.49071502685547
-109.81635284423828,-27.130535125732422
-106.32951354980469,-26.827306747436523
-102.84266662597656,-26.524080276489258
-99.35582733154297,-26.22085189819336
-109.56280517578125,-29.382476806640625
-106.09583282470703,-28.902774810791016
-102.62886810302734,-28.423072814941406
-99.16189575195312,-27.943370819091797
-109.19536590576172,-31.6186580657959
-105.75718688964844,-30.963716506958008
-102.31901550292969,-30.308774948120117
-98.8808364868164,-29.653833389282227
-108.71495819091797,-33.83332061767578
-105.3144302368164,-33.00482940673828
-101.91390228271484,-32.17633056640625
-98.51337432861328,-31.347837448120117
-108.12284088134766,-36.02077102661133
-104.76871490478516,-35.02085494995117
-101.41458892822266,-34.020938873291016
-98.06046295166016,-33.02102279663086
-107.4205322265625,-38.17536926269531
-104.1214370727539,-37.00660705566406
-100.82234954833984,-35.83784484863281
-97.52325439453125,-34.66908264160156
-106.6098403930664,-40.29156494140625
-103.37428283691406,-38.956966400146484
-100.13871765136719,-37.622371673583984
-96.90316009521484,-36.28777313232422
-105.6928482055664,-42.36391830444336
-102.52914428710938,-40.866920471191406
-99.36544799804688,-39.36991882324219
-96.20174407958984,-37.872920989990234
-104.67192077636719,-44.387088775634766
-101.58822631835938,-42.731544494628906
-98.50453186035156,-41.07599639892578
-95.42083740234375,-39.42045211791992
-103.5496826171875,-46.355873107910156
-100.5539321899414,-44.546043395996094
-97.55818939208984,-42.73621368408203
-94.56243896484375,-40.92638397216797
-102.32901763916016,-48.265201568603516
-99.42892456054688,-46.305747985839844
-96.52883911132812,-44.346290588378906
-93.62874603271484,-42.386837005615234
-101.01309204101562,-50.11015319824219
-98.21612548828125,-48.0061149597168
-95.41915893554688,-45.90208053588867
-92.6221923828125,-43.79804229736328
-99.60527038574219,-51.88597869873047
-96.91862487792969,-49.64278030395508
-94.23197937011719,-47.39957809448242
-91.54533386230469,-45.15637969970703
-98.10918426513672,-53.58811569213867
-95.53977966308594,-51.211524963378906
-92.97038269042969,-48.834938049316406
-90.4009780883789,-46.45834732055664
-96.5286865234375,-55.21216583251953
-94.08313751220703,-52.708309173583984
-91.6375961303711,-50.20444869995117
-89.19204711914062,-47.700592041015625
-94.86785125732422,-56.753963470458984
-92.55245971679688,-54.12928009033203
-90.237060546875,-51.504600524902344
-87.92166900634766,-48.87991714477539
-93.13094329833984,-58.20953369140625
-90.95166015625,-55.47078323364258
-88.77238464355469,-52.73203659057617
-86.59310150146484,-49.9932861328125
-91.32244110107422,-59.57512283325195
-89.28488159179688,-56.7293586730957
-87.24732971191406,-53.88359451293945
-85.20977020263672,-51.0378303527832
-89.44699096679688,-60.84722137451172
-87.55640411376953,-57.90176773071289
-85.66582489013672,-54.95631790161133
-83.77523803710938,-52.0108642578125
-87.50944519042969,-62.022552490234375
-85.77069854736328,-58.9849967956543
-84.03194427490234,-55.94743728637695
-82.29319763183594,-52.909881591796875
-85.51476287841797,-63.09809875488281
-83.93232727050781,-59.976253509521484
-82.34989929199219,-56.85441207885742
-80.76746368408203,-53.732566833496094
-83.46810150146484,-64.07107543945312
-82.04605102539062,-60.872982025146484
-80.62400817871094,-57.67489242553711
-79.20195770263672,-54.47679901123047
-81.37471008300781,-64.9389877319336
-80.11671447753906,-61.672882080078125
-78.85871887207031,-58.406776428222656
-77.60072326660156,-55.14067077636719
-79.24000549316406,-65.69960021972656
-78.14929962158203,-62.3738899230957
-77.05858612060547,-59.04817581176758
-75.96788024902344,-55.72246551513672
-77.0694580078125,-66.3509521484375
-76.14884185791016,-62.97419738769531
-75.22823333740234,-59.597442626953125
-74.3076171875,-56.22068786621094
-74.86866760253906,-66.89136505126953
-74.12052154541016,-63.47226333618164
-73.37236785888672,-60.053157806396484
-72.62422180175781,-56.63405227661133
-72.64330291748047,-67.3194580078125
-72.06954956054688,-63.86680603027344
-71.49578857421875,-60.414154052734375
-70.92203521728516,-56.96150207519531
-70.39908599853516,-67.63411712646484
-70.0011978149414,-64.15680694580078
-69.60330963134766,-60.67949676513672
-69.2054214477539,-57.202186584472656
-68.14179229736328,-67.83453369140625
-67.9207992553711,-64.34152221679688
-67.6998062133789,-60.84850311279297
-67.47881317138672,-57.35548782348633
-65.87725067138672,-67.92019653320312
-65.8337173461914,-64.42047119140625
-65.7901840209961,-60.920738220214844
-65.74665069580078,-57.42101287841797
-63.809814453125,-67.92304229736328
-63.81124496459961,-64.42304229736328
-63.81267166137695,-60.92304229736328
-63.81410217285156,-57.42304229736328
-61.809814453125,-67.92222595214844
-61.81124496459961,-64.42222595214844
-61.81267166137695,-60.92222595214844
-61.81410217285156,-57.42222595214844
-59.809814453125,-67.9214096069336
-59.81124496459961,-64.4214096069336
-59.81267166137695,-60.921409606933594
-59.81410217285156,-57.421409606933594
-57.809814453125,-67.92058563232422
-57.81124496459961,-64.42058563232422
-57.81267166137695,-60.920589447021484
-57.81410217285156,-57.420589447021484
-55.809814453125,-67.91976928710938
-55.81124496459961,-64.41976928710938
-55.81267166137695,-60.91977310180664
-55.81410217285156,-57.41977310180664
-53.809814453125,-67.91895294189453
-53.81124496459961,-64.41895294189453
-53.81267166137695,-60.9189567565918
-53.81410217285156,-57.4189567565918
-51.809814453125,-67.91813659667969
-51.81124496459961,-64.41813659667969
-51.81267166137695,-60.91814041137695
-51.81410217285156,-57.41814041137695
-49.809814453125,-67.91732025146484
-49.81124496459961,-64.41732025146484
-49.81267166137695,-60.91732406616211
-49.81410217285156,-57.41732406616211
-47.809814453125,-67.91650390625
-47.81124496459961,-64.41650390625
-47.81267166137695,-60.91650390625
-47.81410217285156,-57.41650390625
-45.809814453125,-67.91568756103516
-45.81124496459961,-64.41568756103516
-45.81267166137695,-60.915687561035156
-45.81410217285156,-57.415687561035156
-43.809814453125,-67.91487121582031
-43.81124496459961,-64.41487121582031
-43.81267166137695,-60.91487121582031
-43.81410217285156,-57.41487121582031
-41.809814453125,-67.91405487060547
-41.81124496459961,-64.41405487060547
-41.81267166137695,-60.91405487060547
-41.81410217285156,-57.41405487060547
-39.809814453125,-67.91323852539062
-39.81124496459961,-64.41323852539062
-39.81267166137695,-60.913238525390625
-39.81410217285156,-57.413238525390625
-37.809814453125,-67.91241455078125
-37.81124496459961,-64.41241455078125
-37.81267166137695,-60.912418365478516
-37.81410217285156,-57.412418365478516
-35.809814453125,-67.9115982055664
-35.81124496459961,-64.4115982055664
-35.81267166137695,-60.91160202026367
-35.81410217285156,-57.41160202026367
-33.809814453125,-67.91078186035156
-33.81124496459961,-64.41078186035156
-33.81267166137695,-60.91078567504883
-33.81410217285156,-57.41078567504883
-31.809812545776367,-67.90996551513672
-31.811243057250977,-64.40996551513672
-31.812673568725586,-60.909969329833984
-31.814104080200195,-57.409969329833984
-29.809812545776367,-67.90914916992188
-29.811243057250977,-64.40914916992188
-29.812673568725586,-60.90915298461914
-29.814104080200195,-57.40915298461914
-27.809812545776367,-67.90833282470703
-27.811243057250977,-64.40833282470703
-27.812673568725586,-60.90833282470703
-27.814104080200195,-57.40833282470703
-25.809816360473633,-67.90751647949219
-25.811246871948242,-64.40751647949219
-25.81267738342285,-60.90751647949219
-25.81410789489746,-57.40751647949219
-23.809816360473633,-67.90670013427734
-23.811246871948242,-64.40670013427734
-23.81267738342285,-60.906700134277344
-23.81410789489746,-57.406700134277344
-21.809816360473633,-67.9058837890625
-21.811246871948242,-64.4058837890625
-21.81267738342285,-60.9058837890625
-21.81410789489746,-57.4058837890625
-19.809816360473633,-67.90506744384766
-19.811246871948242,-64.40506744384766
-19.81267738342285,-60.905067443847656
-19.81410789489746,-57.405067443847656
-17.809816360473633,-67.90425109863281
-17.811246871948242,-64.40425109863281
-17.81267738342285,-60.90425109863281
-17.81410789489746,-57.40425109863281
-15.80981731414795,-67.90342712402344
-15.811246871948242,-64.40342712402344
-15.812677383422852,-60.9034309387207
-15.814106941223145,-57.4034309387207
-13.80981731414795,-67.9026107788086
-13.811246871948242,-64.4026107788086
-13.812677383422852,-60.90261459350586
-13.814106941223145,-57.40261459350586
-11.80981731414795,-67.90179443359375
-11.811246871948242,-64.40179443359375
-11.812677383422852,-60.901798248291016
-11.814106941223145,-57.401798248291016
-9.80981731414795,-67.9009780883789
-9.811246871948242,-64.4009780883789
-9.812677383422852,-60.90098190307617
-9.814106941223145,-57.40098190307617
-7.809817314147949,-67.90016174316406
-7.8112473487854,-64.40016174316406
-7.812676906585693,-60.90016555786133
-7.8141069412231445,-57.40016555786133
--41.57395935058594,82.62542724609375
--41.579586029052734,80.62543487548828
--41.525909423828125,78.82386016845703
--41.19239807128906,77.17517852783203
--40.568546295166016,75.61306762695312
--39.67458724975586,74.18819427490234
--38.53953170776367,72.94681549072266
--37.16744613647461,71.88114166259766
--35.64335250854492,71.00440979003906
--34.013580322265625,70.34459686279297
--32.30881881713867,69.91413116455078
--30.56117820739746,69.72110748291016
--28.63589096069336,69.71194458007812
-85.98224639892578,66.35848999023438
-85.97777557373047,69.85848999023438
-83.98224639892578,66.3559341430664
-83.97777557373047,69.8559341430664
-81.98224639892578,66.35337829589844
-81.97777557373047,69.85337829589844
-79.98225402832031,66.35081481933594
-79.977783203125,69.85081481933594
-77.98225402832031,66.34825897216797
-77.977783203125,69.84825897216797
-75.98225402832031,66.345703125
-75.977783203125,69.845703125
-73.98225402832031,66.34314727783203
-73.977783203125,69.84314727783203
-71.98226165771484,66.34059143066406
-71.97779083251953,69.84059143066406
-69.98226165771484,66.3380355834961
-69.97779083251953,69.8380355834961
-67.98226165771484,66.3354721069336
-67.97779083251953,69.8354721069336
-65.98226165771484,66.33291625976562
-65.97779083251953,69.83291625976562
-63.98226547241211,66.33036041259766
-63.977787017822266,69.83036041259766
-61.982269287109375,66.32780456542969
-61.97779083251953,69.82780456542969
-59.98227310180664,66.32524871826172
-59.9777946472168,69.82524871826172
-102.30058288574219,82.91472625732422
-98.80066680908203,82.89085388183594
-102.31421661376953,80.9147720336914
-98.81430053710938,80.89089965820312
-102.3278579711914,78.9148178100586
-98.82794189453125,78.89094543457031
-102.34149932861328,76.91486358642578
-98.84158325195312,76.8909912109375
-102.35514068603516,74.91490936279297
-98.855224609375,74.89103698730469
-102.36878204345703,72.91495513916016
-98.86886596679688,72.89108276367188
-102.38241577148438,70.91500091552734
-98.88249969482422,70.89112854003906
-102.39605712890625,68.91505432128906
-98.8961410522461,68.89118194580078
-102.40969848632812,66.91510009765625
-98.90978240966797,66.89122772216797
-102.42333984375,64.91514587402344
-98.92342376708984,64.89127349853516
-102.43698120117188,62.91518783569336
-98.93706512451172,62.891319274902344
-102.45061492919922,60.91523361206055
-98.95069885253906,60.89136505126953
-102.4642562866211,58.915279388427734
-98.96434020996094,58.89141082763672
-102.47789764404297,56.91532516479492
-98.97798156738281,56.891456604003906
-102.49153137207031,54.91537094116211
-98.99161529541016,54.891502380371094
--27.836780548095703,-57.784236907958984
--29.6750545501709,-57.75445556640625
--31.392126083374023,-57.48530960083008
--33.05033493041992,-56.96461868286133
--34.613040924072266,-56.20388412475586
--36.04573059082031,-55.21992111206055
--37.316734313964844,-54.03445816040039
--38.4940299987793,-52.63148880004883
--39.49547576904297,-51.1412353515625
--40.31724548339844,-49.54485321044922
--40.948238372802734,-47.86389923095703
--41.37992858886719,-46.121089935302734
--41.60648727416992,-44.339962005615234
--110.73300170898438,43.86024856567383
--114.23278045654297,43.82101821899414
--110.71058654785156,41.860374450683594
--114.21036529541016,41.821144104003906
--110.68816375732422,39.86050033569336
--114.18794250488281,39.82126998901367
--110.6657485961914,37.860626220703125
--114.16552734375,37.82139587402344
--110.6433334350586,35.86075210571289
--114.14311218261719,35.8215217590332
--110.62091064453125,33.860877990722656
--114.12068939208984,33.82164764404297
--110.59849548339844,31.86100196838379
--114.09827423095703,31.82176971435547
--110.57608032226562,29.861127853393555
--114.07585906982422,29.821895599365234
--110.55365753173828,27.86125373840332
--114.05343627929688,27.822021484375
--110.53124237060547,25.861379623413086
--114.03102111816406,25.822147369384766
--110.50882720947266,23.86150550842285
--114.00860595703125,23.82227325439453
--110.48640441894531,21.861631393432617
--113.9861831665039,21.822399139404297
--110.4639892578125,19.86175537109375
--113.9637680053711,19.822525024414062
--110.44157409667969,17.861881256103516
--113.94135284423828,17.822650909423828
--110.41915130615234,15.862007141113281
--113.91893005371094,15.822775840759277
--110.39673614501953,13.862133026123047
--113.89651489257812,13.822901725769043
--110.37431335449219,11.862258911132812
--113.87409210205078,11.823027610778809
--110.35189819335938,9.862384796142578
--113.85167694091797,9.823153495788574
--110.32948303222656,7.8625102043151855
--113.82926177978516,7.82327938079834
--110.30706024169922,5.862636089324951
--113.80683898925781,5.8234052658081055
--110.2846450805664,3.862762212753296
--113.784423828125,3.823531150817871
--110.2622299194336,1.862887978553772
--113.76200866699219,1.8236570358276367
--110.23980712890625,-0.13698609173297882
--113.73958587646484,-0.17621707916259766
--110.21739196777344,-2.1368601322174072
--113.71717071533203,-2.176091194152832
-83.0335464477539,28.41474723815918
-85.0335464477539,28.420303344726562
-86.99187469482422,28.431671142578125
-88.83265686035156,28.561765670776367
-90.65487670898438,28.85317039489746
-92.44442749023438,29.303630828857422
-94.18744659423828,29.909656524658203
-95.87045288085938,30.666555404663086
-97.48040008544922,31.568470001220703
-98.89628601074219,32.58076095581055
-100.10743713378906,33.788692474365234
-101.10472106933594,35.17844772338867
-101.86125183105469,36.712608337402344
-102.35667419433594,38.34984588623047
-102.57763671875,40.04606628417969
-102.57994842529297,41.95169448852539
--67.0452880859375,-68.69317626953125
--65.04474639892578,-68.6723403930664
--63.04485321044922,-68.6515121459961
--61.004295349121094,-68.62614440917969
--58.7590446472168,-68.38240814208984
--56.57477951049805,-67.80834197998047
--54.49982452392578,-66.91664123535156
--52.580078125,-65.72703552246094
--50.8580207824707,-64.2658462524414
--49.3718376159668,-62.56550979614258
--48.1550178527832,-60.7596435546875
--47.12841796875,-58.83924865722656
--46.30270767211914,-56.824302673339844
--45.68648147583008,-54.73574447631836
--45.286136627197266,-52.59528732299805
--45.10584259033203,-50.42519760131836
--45.104854583740234,-48.35634231567383
--45.11994552612305,-46.35639953613281
--45.13503646850586,-44.3564567565918
-27.14229393005371,66.28325653076172
-27.137819290161133,69.78325653076172
-25.142295837402344,66.28070068359375
-25.137821197509766,69.78070068359375
-23.142297744750977,66.27814483642578
-23.1378231048584,69.77814483642578
-21.142297744750977,66.27558135986328
-21.1378231048584,69.77558135986328
-19.142301559448242,66.27302551269531
-19.137826919555664,69.77302551269531
-17.142301559448242,66.27046966552734
-17.137826919555664,69.77046966552734
-15.142303466796875,66.26791381835938
-15.137828826904297,69.76791381835938
-13.142305374145508,66.2653579711914
-13.13783073425293,69.7653579711914
-11.14230728149414,66.26280212402344
-11.137832641601562,69.76280212402344
-9.142309188842773,66.26023864746094
-9.137834548950195,69.76023864746094
-7.142311096191406,66.25768280029297
-7.137836456298828,69.75768280029297
-5.142311096191406,66.255126953125
-5.137836456298828,69.755126953125
-3.142313241958618,66.25257110595703
-3.137838125228882,69.75257110595703
-1.1423150300979614,66.25001525878906
-1.1378401517868042,69.75001525878906
--0.8576830625534058,66.24745178222656
--0.862157940864563,69.74745178222656
--2.8576810359954834,66.2448959350586
--2.8621561527252197,69.7448959350586
--4.85767936706543,66.24234008789062
--4.862154006958008,69.74234008789062
--6.85767936706543,66.23978424072266
--6.862154006958008,69.73978424072266
--8.857675552368164,66.23722839355469
--8.862150192260742,69.73722839355469
--10.857675552368164,66.23467254638672
--10.862150192260742,69.73467254638672
--12.857671737670898,66.23210906982422
--12.862146377563477,69.73210906982422
--14.857671737670898,66.22955322265625
--14.862146377563477,69.72955322265625
--16.8576717376709,66.22699737548828
--16.862146377563477,69.72699737548828
--18.857667922973633,66.22444152832031
--18.86214256286621,69.72444152832031
--20.857667922973633,66.22188568115234
--20.86214256286621,69.72188568115234
--22.857664108276367,66.21932220458984
--22.862138748168945,69.71932220458984
--24.857664108276367,66.21676635742188
--24.862138748168945,69.71676635742188
--26.8576602935791,66.2142105102539
--26.86213493347168,69.7142105102539
--28.517200469970703,130.03573608398438
--30.479185104370117,130.01951599121094
--32.290748596191406,129.8743896484375
--34.077491760253906,129.5421600341797
--35.82014083862305,129.0264434814453
--37.49991226196289,128.332763671875
--39.098690032958984,127.46863555908203
--40.59678268432617,126.44512939453125
--41.8831901550293,125.2926254272461
--42.97636795043945,123.95542907714844
--43.85012435913086,122.465576171875
--44.483543395996094,120.85874938964844
--44.861446380615234,119.17343139648438
--44.97604751586914,117.42443084716797
--44.98167419433594,115.42443084716797
--67.08174133300781,-65.19336700439453
--65.08104705810547,-65.17253112792969
--63.08115768432617,-65.15169525146484
--61.04294204711914,-65.12653350830078
--58.815914154052734,-64.90087127685547
--56.64070510864258,-64.37262725830078
--54.5582275390625,-63.55173110961914
--52.60764694213867,-62.45363235473633
--50.82565689086914,-61.098976135253906
--49.24726104736328,-59.515892028808594
--47.89688491821289,-57.74089431762695
--46.79288864135742,-55.80302429199219
--45.95462417602539,-53.73627853393555
--45.396793365478516,-51.5768928527832
--45.12916946411133,-49.36273193359375
--45.1131591796875,-47.255462646484375
--45.12825012207031,-45.25551986694336
-58.047794342041016,69.8227767944336
-56.047794342041016,69.82022094726562
-54.04779815673828,69.81766510009766
-52.04779815673828,69.81510162353516
-50.04780197143555,69.81254577636719
-48.04780197143555,69.80998992919922
-46.04780197143555,69.80743408203125
-44.04780578613281,69.80487823486328
-42.04780960083008,69.80232238769531
-40.04780960083008,69.79975891113281
-38.04780960083008,69.79720306396484
-36.04780960083008,69.79464721679688
-34.047813415527344,69.7920913696289
-32.04781723022461,69.78953552246094
-30.047819137573242,69.78697204589844
-28.047821044921875,69.78441619873047
--41.66096878051758,51.705543518066406
--45.16095733642578,51.71539306640625
--48.66094207763672,51.725242614746094
--52.16093063354492,51.73509216308594
--41.666595458984375,49.70555114746094
--45.16658401489258,49.71540069580078
--48.666568756103516,49.725250244140625
--52.16655731201172,49.73509979248047
--41.67222595214844,47.70555877685547
--45.17221450805664,47.71540832519531
--48.67219924926758,47.725257873535156
--52.17218780517578,47.735107421875
--41.677852630615234,45.70556640625
--45.17784118652344,45.715415954589844
--48.677825927734375,45.72526550292969
--52.17781448364258,45.73511505126953
--41.68347930908203,43.70557403564453
--45.183467864990234,43.715423583984375
--48.68345260620117,43.72527313232422
--52.183441162109375,43.73512268066406
--41.8112678527832,-1.7042436599731445
--41.805641174316406,0.29588666558265686
--41.69941329956055,2.0741705894470215
--41.35930252075195,3.804919719696045
--40.79069519042969,5.474608421325684
--40.00382995605469,7.053216934204102
--39.012840270996094,8.51236629486084
--37.84077453613281,9.818121910095215
--36.50387954711914,10.92912483215332
--35.017189025878906,11.829895973205566
--33.41349792480469,12.500568389892578
--31.72817039489746,12.926355361938477
--29.998367309570312,13.097864151000977
--66.83586883544922,27.998329162597656
--64.83587646484375,28.00388526916504
--62.83588790893555,28.009443283081055
--60.96198272705078,28.037200927734375
--59.320926666259766,28.318063735961914
--57.762474060058594,28.903867721557617
--56.34273910522461,29.77351951599121
--55.11284255981445,30.895706176757812
--54.06452560424805,32.26249694824219
--53.229007720947266,33.781429290771484
--52.631980895996094,35.40894317626953
--52.28708267211914,37.10784912109375
--52.19707107543945,38.89096450805664
--52.19144058227539,40.891414642333984
--110.73300170898438,43.86024856567383
--110.71058654785156,41.860374450683594
--110.68816375732422,39.86050033569336
--110.6657485961914,37.860626220703125
--110.6433334350586,35.86075210571289
--110.61959838867188,33.841243743896484
--110.43726348876953,31.63846206665039
--109.99047088623047,29.473773956298828
--109.2857666015625,27.378807067871094
--108.33344268798828,25.384170532226562
--107.14742279052734,23.51900863647461
--105.80815887451172,21.844375610351562
--104.22147369384766,20.24699592590332
--102.42084503173828,18.895343780517578
--100.4439926147461,17.817724227905273
--98.33230590820312,17.036706924438477
--96.1300048828125,16.568639755249023
--93.89205169677734,16.423110961914062
--91.89205932617188,16.428667068481445
--89.8920669555664,16.43422508239746
-58.047794342041016,69.8227767944336
-56.04737854003906,69.82022094726562
-54.04738235473633,69.81766510009766
-51.988121032714844,69.80863189697266
-49.6430778503418,69.47372436523438
-47.42210006713867,68.64990234375
-45.42589569091797,67.37451934814453
-43.748924255371094,65.71070861816406
-42.45146560668945,63.83143997192383
-41.4772834777832,61.766014099121094
-40.85236740112305,59.56953430175781
-40.59340286254883,57.300621032714844
-40.56429672241211,55.268001556396484
-40.53807830810547,53.26817321777344
--107.23320770263672,43.89921951293945
--107.2107925415039,41.89934539794922
--107.18836975097656,39.899471282958984
--107.16299438476562,37.936710357666016
--106.99881744384766,36.15324020385742
--106.6243896484375,34.40181350708008
--106.04498291015625,32.707115173339844
--105.26876068115234,31.093053817749023
--104.30668640136719,29.58238410949707
--103.17849731445312,28.205001831054688
--101.89923858642578,27.02199935913086
--100.461181640625,26.038129806518555
--98.89506530761719,25.2744140625
--97.23432922363281,24.747173309326172
--95.51448059082031,24.467668533325195
--93.67462158203125,24.423744201660156
--91.67462921142578,24.42930030822754
--89.67448425292969,24.434858322143555
--27.800329208374023,-61.2840461730957
--29.64684295654297,-61.25670623779297
--31.37819480895996,-60.99969482421875
--33.05583190917969,-60.500526428222656
--34.64606475830078,-59.769222259521484
--36.11695098876953,-58.820472717285156
--37.4389533996582,-57.6733283996582
--38.60688018798828,-56.338409423828125
--39.60588836669922,-54.86180877685547
--40.41543197631836,-53.273414611816406
--41.023193359375,-51.597415924072266
--41.41991424560547,-49.85932540893555
--41.59955596923828,-48.085601806640625
--41.6214714050293,-46.14118957519531
--41.63656234741211,-44.1412467956543
-58.05227279663086,66.3227767944336
-56.067020416259766,66.31979370117188
-54.31907272338867,66.1801528930664
-52.60772705078125,65.79791259765625
-50.96648406982422,65.18055725097656
-49.42747116088867,64.34015655517578
-48.02082061767578,63.2932014465332
-46.79072570800781,62.068260192871094
-45.765785217285156,60.67502212524414
-44.9659538269043,59.14142608642578
-44.41005325317383,57.503562927246094
-44.11115646362305,55.79995346069336
-44.047298431396484,53.948402404785156
--41.57395935058594,82.62542724609375
--45.07394790649414,82.6352767944336
--41.579586029052734,80.62543487548828
--45.07957458496094,80.63528442382812
--41.5852165222168,78.62544250488281
--45.085205078125,78.63529205322266
--41.590843200683594,76.62545013427734
--45.0908317565918,76.63529968261719
--41.59646987915039,74.62545776367188
--45.096458435058594,74.63530731201172
--41.60210037231445,72.6254653930664
--45.102088928222656,72.63531494140625
--41.60772705078125,70.62547302246094
--45.10771560668945,70.63532257080078
--41.61335754394531,68.62548065185547
--45.113346099853516,68.63533020019531
--41.61898422241211,66.62548828125
--45.11897277832031,66.63533782958984
--41.624610900878906,64.62549591064453
--45.12459945678711,64.63534545898438
--41.63024139404297,62.62550354003906
--45.13022994995117,62.635353088378906
--41.635868072509766,60.625511169433594
--45.13585662841797,60.63536071777344
--41.64149475097656,58.625518798828125
--45.141483306884766,58.63536834716797
--41.647125244140625,56.625526428222656
--45.14711380004883,56.6353759765625
--41.65275192260742,54.62553405761719
--45.152740478515625,54.63538360595703
--41.658382415771484,52.62554168701172
--45.15837097167969,52.63539123535156
-44.02894973754883,52.548702239990234
-44.055171966552734,54.54882049560547
-44.01411819458008,56.72224426269531
-43.62957000732422,58.97473907470703
-42.88161087036133,61.133949279785156
-41.790401458740234,63.141658782958984
-40.38536071777344,64.94373321533203
-38.77177810668945,66.47734069824219
-36.912357330322266,67.79409790039062
-34.866397857666016,68.79676818847656
-32.68648910522461,69.45955657958984
-30.42867088317871,69.76544189453125
-28.331613540649414,69.78478240966797
-26.403766632080078,28.25739860534668
-28.388469696044922,28.263391494750977
-30.135652542114258,28.406394958496094
-31.845666885375977,28.792335510253906
-33.48490524291992,29.413618087768555
-35.02115249633789,30.258039474487305
-36.42421340942383,31.308998107910156
-37.650108337402344,32.537899017333984
-38.67073059082031,33.93463897705078
-39.46599197387695,35.47091293334961
-40.017215728759766,37.11064147949219
-40.311466217041016,38.815330505371094
-40.37294387817383,40.67201232910156
--41.686771392822266,42.535579681396484
--45.18675994873047,42.54542922973633
--41.69239807128906,40.535587310791016
--45.192386627197266,40.54543685913086
--41.698028564453125,38.53559494018555
--45.19801712036133,38.54544448852539
--41.70365524291992,36.53560256958008
--45.203643798828125,36.54545211791992
--41.70928192138672,34.53561019897461
--45.20927047729492,34.54545974731445
--41.71491241455078,32.53561782836914
--45.214900970458984,32.545467376708984
--41.72053909301758,30.535627365112305
--45.22052764892578,30.54547691345215
--41.72616958618164,28.535634994506836
--45.226158142089844,28.54548454284668
--41.73179626464844,26.535642623901367
--45.23178482055664,26.54549217224121
--41.737422943115234,24.5356502532959
--45.23741149902344,24.545499801635742
--41.7430534362793,22.535659790039062
--45.2430419921875,22.545509338378906
--41.748680114746094,20.535667419433594
--45.2486686706543,20.545516967773438
--41.75430679321289,18.535675048828125
--45.254295349121094,18.54552459716797
--41.75993728637695,16.535682678222656
--45.259925842285156,16.5455322265625
--41.76556396484375,14.535690307617188
--45.26555252075195,14.545539855957031
--41.77119445800781,12.535697937011719
--45.271183013916016,12.545547485351562
--41.77682113647461,10.53570556640625
--45.27680969238281,10.545555114746094
--41.782447814941406,8.535713195800781
--45.28243637084961,8.545562744140625
--41.78807830810547,6.535721302032471
--45.28806686401367,6.545570373535156
--41.793704986572266,4.535728931427002
--45.29369354248047,4.5455780029296875
--41.79933166503906,2.5357401371002197
--45.299320220947266,2.5455894470214844
--41.804962158203125,0.5357478260993958
--45.30495071411133,0.5455971956253052
--41.81058883666992,-1.4642444849014282
--45.310577392578125,-1.4543951749801636
--66.79419708251953,12.998388290405273
--64.79407501220703,13.003945350646973
--62.95246505737305,12.963264465332031
--61.24401092529297,12.681835174560547
--59.598121643066406,12.14417552947998
--58.0529899597168,11.362762451171875
--56.644474029541016,10.355727195739746
--55.40166091918945,9.143378257751465
--54.33807373046875,7.753330230712891
--53.48170471191406,6.226869106292725
--52.84976577758789,4.594662189483643
--52.45494842529297,2.8895034790039062
--52.3051872253418,1.1456518173217773
--52.30883026123047,-0.8236172795295715
-98.8006591796875,82.89085388183594
-98.8143081665039,80.89006805419922
-98.82794952392578,78.8901138305664
-98.72276306152344,77.18574523925781
-98.30300903320312,75.58283233642578
-97.5813217163086,74.0912857055664
-96.58493041992188,72.76737976074219
-95.34532165527344,71.65087890625
-93.9169692993164,70.78024291992188
-92.35247802734375,70.18814849853516
-90.7055892944336,69.89494323730469
-88.85015106201172,69.8621597290039
-86.85015869140625,69.85960388183594
--48.686744689941406,42.55527877807617
--48.69237518310547,40.55512237548828
--48.69800567626953,38.55513000488281
--48.70363235473633,36.555137634277344
--48.66004943847656,34.438323974609375
--48.41246032714844,32.279457092285156
--47.951908111572266,30.155811309814453
--47.282928466796875,28.088333129882812
--46.41213607788086,26.097429275512695
--45.348106384277344,24.20273780822754
--44.09283447265625,22.413785934448242
--42.56835174560547,20.750102996826172
--40.81555938720703,19.328977584838867
--38.87264633178711,18.18138313293457
--36.78195571899414,17.33232879638672
--34.589054107666016,16.80031394958496
--32.341712951660156,16.596933364868164
--30.308218002319336,16.599781036376953
--103.73343658447266,43.9387092590332
--103.71101379394531,41.938575744628906
--103.61397552490234,40.124244689941406
--103.29901123046875,38.373069763183594
--102.76738739013672,36.675071716308594
--102.0274658203125,35.05694580078125
--101.09088897705078,33.54412078857422
--99.97235870361328,32.1603889465332
--98.69608306884766,30.942018508911133
--97.26941680908203,29.90922737121582
--95.7161865234375,29.078859329223633
--94.06493377685547,28.466171264648438
--92.34599304199219,28.082420349121094
--90.59093475341797,27.93465805053711
--66.83587646484375,27.99833106994629
--66.8261489868164,24.49834442138672
--64.83588409423828,28.003887176513672
--64.82615661621094,24.5039005279541
--62.83588790893555,28.009445190429688
--62.82616424560547,24.509458541870117
--60.83589553833008,28.01500129699707
--60.826171875,24.5150146484375
--58.83590316772461,28.020559310913086
--58.82617950439453,24.520572662353516
--56.83591079711914,28.02611541748047
--56.82618713378906,24.5261287689209
--54.83591842651367,28.031673431396484
--54.826194763183594,24.531686782836914
--52.8359260559082,28.037229537963867
--52.826202392578125,24.537242889404297
--50.835933685302734,28.042787551879883
--50.826210021972656,24.542800903320312
--48.835941314697266,28.048343658447266
--48.82621765136719,24.548357009887695
--46.8359489440918,28.05390167236328
--46.82622528076172,24.55391502380371
--44.83595657348633,28.059457778930664
--44.82623291015625,24.559471130371094
--42.83596420288086,28.06501579284668
--42.82624053955078,24.56502914428711
--40.83597183227539,28.070571899414062
--40.82624816894531,24.570585250854492
--38.83597946166992,28.076129913330078
--38.826255798339844,24.576143264770508
--36.83598709106445,28.08168601989746
--36.826263427734375,24.58169937133789
--34.835994720458984,28.087244033813477
--34.826271057128906,24.587257385253906
--32.836002349853516,28.09280014038086
--32.82627868652344,24.59281349182129
--30.83601188659668,28.098358154296875
--30.82628631591797,24.598371505737305
--28.83601951599121,28.103914260864258
--28.8262939453125,24.603927612304688
-19.330636978149414,140.9599151611328
-19.35021209716797,137.4599609375
-19.36978530883789,133.96002197265625
-19.389360427856445,130.46006774902344
-21.33060646057129,140.97109985351562
-21.350181579589844,137.4711456298828
-21.369754791259766,133.97120666503906
-21.38932991027832,130.47125244140625
-23.33057403564453,140.98228454589844
-23.350149154663086,137.48233032226562
-23.369722366333008,133.98239135742188
-23.389297485351562,130.48243713378906
-25.330543518066406,140.99346923828125
-25.35011863708496,137.49351501464844
-25.369691848754883,133.9935760498047
-25.389266967773438,130.49362182617188
-27.33051300048828,141.00465393066406
-27.350088119506836,137.50469970703125
-27.369661331176758,134.0047607421875
-27.389236450195312,130.5048065185547
-29.330480575561523,141.01583862304688
-29.350055694580078,137.51588439941406
-29.36962890625,134.0159454345703
-29.389204025268555,130.5159912109375
-31.330448150634766,141.0270233154297
-31.35002326965332,137.52706909179688
-31.369596481323242,134.02713012695312
-31.389171600341797,130.5271759033203
-33.33041763305664,141.0382080078125
-33.34999084472656,137.5382537841797
-33.36956787109375,134.03831481933594
-33.38914108276367,130.53836059570312
-35.330387115478516,141.04940795898438
-35.34996032714844,137.54945373535156
-35.369537353515625,134.0495147705078
-35.38911056518555,130.549560546875
-37.33035659790039,141.0605926513672
-37.34992980957031,137.56063842773438
-37.3695068359375,134.06069946289062
-37.38908004760742,130.5607452392578
-39.330326080322266,141.07177734375
-39.34989929199219,137.5718231201172
-39.369476318359375,134.07188415527344
-39.3890495300293,130.57192993164062
-41.33029556274414,141.0829620361328
-41.34986877441406,137.5830078125
-41.36944580078125,134.08306884765625
-41.38901901245117,130.58311462402344
-43.33026123046875,141.09414672851562
-43.34983444213867,137.5941925048828
-43.36941146850586,134.09425354003906
-43.38898468017578,130.59429931640625
-45.330230712890625,141.10533142089844
-45.34980392456055,137.60537719726562
-45.369380950927734,134.10543823242188
-45.388954162597656,130.60548400878906
-47.330196380615234,141.11651611328125
-47.349769592285156,137.61656188964844
-47.369346618652344,134.1166229248047
-47.388919830322266,130.61666870117188
-49.33016586303711,141.12770080566406
-49.34973907470703,137.62774658203125
-49.36931610107422,134.1278076171875
-49.38888931274414,130.6278533935547
-51.330135345458984,141.13888549804688
-51.349708557128906,137.63893127441406
-51.369285583496094,134.1389923095703
-51.388858795166016,130.6390380859375
-53.33010482788086,141.1500701904297
-53.34967803955078,137.65011596679688
-53.36925506591797,134.15017700195312
-53.38882827758789,130.6502227783203
-55.330074310302734,141.1612548828125
-55.349647521972656,137.6613006591797
-55.369224548339844,134.16136169433594
-55.388797760009766,130.66140747070312
-57.33004379272461,141.1724395751953
-57.34961700439453,137.6724853515625
-57.36919403076172,134.17254638671875
-57.38876724243164,130.67259216308594
-59.330013275146484,141.18362426757812
-59.349586486816406,137.6836700439453
-59.369163513183594,134.18373107910156
-59.388736724853516,130.68377685546875
-61.32998275756836,141.19480895996094
-61.34955596923828,137.69485473632812
-61.36913299560547,134.19491577148438
-61.38870620727539,130.69496154785156
-63.329952239990234,141.20599365234375
-63.349525451660156,137.70603942871094
-63.369102478027344,134.2061004638672
-63.388675689697266,130.70614624023438
-65.42821502685547,141.21044921875
-65.38225555419922,137.71075439453125
-65.33629608154297,134.2110595703125
-65.29033660888672,130.71136474609375
-67.71540832519531,141.11734008789062
-67.47671508789062,137.62548828125
-67.23802185058594,134.13363647460938
-66.99932861328125,130.64178466796875
-69.99400329589844,140.8983612060547
-69.56330108642578,137.42495727539062
-69.1325912475586,133.95156860351562
-68.70188903808594,130.47816467285156
-72.25706481933594,140.55416870117188
-71.63565826416016,137.10977172851562
-71.0142593383789,133.66537475585938
-70.39285278320312,130.22097778320312
-74.49773406982422,140.08583068847656
-73.68751525878906,136.680908203125
-72.87728881835938,133.27597045898438
-72.06707000732422,129.8710479736328
-76.70919799804688,139.49476623535156
-75.7126235961914,136.1396484375
-74.7160415649414,132.78451538085938
-73.71946716308594,129.4293975830078
-78.88473510742188,138.7827606201172
-77.704833984375,135.48764038085938
-76.52493286132812,132.1925048828125
-75.34503173828125,128.8973846435547
-81.01774597167969,137.9519805908203
-79.6581039428711,134.72686767578125
-78.29845428466797,131.50173950195312
-76.93881225585938,128.27662658691406
-83.10175323486328,137.0049591064453
-81.56649780273438,133.85964965820312
-80.03123474121094,130.71432495117188
-78.49597930908203,127.56902313232422
-85.13041687011719,135.94454956054688
-83.42420959472656,132.88858032226562
-81.71800231933594,129.8326416015625
-80.01179504394531,126.77667999267578
-87.09757232666016,134.77398681640625
-85.22560119628906,131.81666564941406
-83.35362243652344,128.85935974121094
-81.48165130615234,125.90203857421875
-88.99726867675781,133.496826171875
-86.9652099609375,130.6471405029297
-84.93315124511719,127.79744720458984
-82.90109252929688,124.94775390625
-90.82369995117188,132.11697387695312
-88.63773345947266,129.38356018066406
-86.45177459716797,126.65013885498047
-84.26580810546875,123.9167251586914
-92.57135772705078,130.63856506347656
-90.23812103271484,128.02972412109375
-87.9048843383789,125.42089080810547
-85.57164764404297,122.81205749511719
-94.23490142822266,129.06613159179688
-91.76148223876953,126.58980560302734
-89.2880630493164,124.11347198486328
-86.81464385986328,121.63714599609375
-95.80928802490234,127.40443420410156
-93.20320129394531,125.06813049316406
-90.59710693359375,122.73182678222656
-87.99102020263672,120.39552307128906
-97.27974700927734,125.672119140625
-94.55594635009766,123.47418212890625
-91.83214569091797,121.2762451171875
-89.10834503173828,119.07830810546875
-98.63536834716797,123.91968536376953
-95.8235855102539,121.83549499511719
-93.01180267333984,119.75129699707031
-90.20001983642578,117.66710662841797
-99.91785430908203,122.11304473876953
-97.0228271484375,120.14611053466797
-94.1278076171875,118.1791763305664
-91.23278045654297,116.21224212646484
-101.12505340576172,120.25525665283203
-98.15167236328125,118.40890502929688
-95.17829895019531,116.56254577636719
-92.20491790771484,114.71619415283203
-102.25491333007812,118.34944915771484
-99.20819854736328,116.62678527832031
-96.16149139404297,114.90412902832031
-93.11477661132812,113.18146514892578
-103.30553436279297,116.3988265991211
-100.19063568115234,114.80277252197266
-97.07573699951172,113.20671844482422
-93.9608383178711,111.61066436767578
-104.27513885498047,114.40670776367188
-101.09730529785156,112.93994903564453
-97.91947937011719,111.47319793701172
-94.74164581298828,110.00643920898438
-105.162109375,112.37643432617188
-101.92670440673828,111.04145050048828
-98.6913070678711,109.70647430419922
-95.45590209960938,108.37149047851562
-105.96492004394531,110.31144714355469
-102.67741394042969,109.11048889160156
-99.38990783691406,107.90953063964844
-96.10240173339844,106.70857238769531
-106.68224334716797,108.21521759033203
-103.34817504882812,107.15031433105469
-100.01411437988281,106.08541870117188
-96.68004608154297,105.02051544189453
-107.3128433227539,106.09129333496094
-103.93785095214844,105.16424560546875
-100.56285095214844,104.23719787597656
-97.18785858154297,103.31015014648438
-107.85566711425781,103.94326782226562
-104.44544219970703,103.15563201904297
-101.03520965576172,102.36800384521484
-97.62498474121094,101.58036804199219
-108.30980682373047,101.77474975585938
-104.87010192871094,101.12786102294922
-101.43040466308594,100.4809799194336
-97.9906997680664,99.83409118652344
-108.67446899414062,99.58940887451172
-105.21109771728516,99.08436584472656
-101.74773406982422,98.57931518554688
-98.28436279296875,98.07427215576172
-108.94906616210938,97.39093017578125
-105.4678726196289,97.02857208251953
-101.98668670654297,96.66622161865234
-98.5054931640625,96.30386352539062
-109.13312530517578,95.18302917480469
-105.63998413085938,94.96398162841797
-102.1468505859375,94.74492645263672
-98.6537094116211,94.52587890625
-109.22633361816406,92.96942901611328
-105.7271499633789,92.89405059814453
-102.22795867919922,92.81867218017578
-98.72877502441406,92.74329376220703
-109.246337890625,90.89227294921875
-105.74642181396484,90.86840057373047
-102.24649810791016,90.84453582763672
-98.74658203125,90.82066345214844
-109.25997924804688,88.89232635498047
-105.76006317138672,88.86845397949219
-102.26013946533203,88.84458923339844
-98.76022338867188,88.82071685791016
-109.27362060546875,86.89237213134766
-105.7737045288086,86.86849975585938
-102.2737808227539,86.84463500976562
-98.77386474609375,86.82076263427734
-109.28726196289062,84.89241790771484
-105.78734588623047,84.86854553222656
-102.28742218017578,84.84468078613281
-98.78750610351562,84.82080841064453
--28.72602081298828,28.104219436645508
--30.726320266723633,28.098661422729492
--32.726314544677734,28.09310531616211
--34.979652404785156,27.924379348754883
--37.19096755981445,27.405048370361328
--39.29435348510742,26.54749870300293
--41.23842239379883,25.3726806640625
--42.97569274902344,23.909290313720703
--44.46371841430664,22.193077087402344
--45.660850524902344,20.370302200317383
--46.66980743408203,18.45207405090332
--47.489986419677734,16.44585609436035
--48.11382293701172,14.370176315307617
--48.5355339050293,12.244202613830566
--48.75124740600586,10.087567329406738
--48.78397750854492,8.002671241760254
--48.789608001708984,6.002679347991943
--48.79523468017578,4.002687454223633
--48.80086135864258,2.002695083618164
--48.80649185180664,0.0027035577222704887
--48.686744689941406,42.55527877807617
--52.18673324584961,42.565128326416016
--48.6923713684082,40.5552864074707
--52.192359924316406,40.56513595581055
--48.698001861572266,38.555294036865234
--52.19799041748047,38.56514358520508
--48.70362854003906,36.555301666259766
--52.203617095947266,36.56515121459961
--48.70925521850586,34.5553092956543
--52.20924377441406,34.56515884399414
--48.71488571166992,32.55531692504883
--52.214874267578125,32.56516647338867
--48.72051239013672,30.555326461791992
--52.22050094604492,30.565176010131836
--48.72614288330078,28.555334091186523
--52.226131439208984,28.565183639526367
--48.73176956176758,26.555341720581055
--52.23175811767578,26.5651912689209
--48.737396240234375,24.555349349975586
--52.23738479614258,24.56519889831543
--48.74302673339844,22.55535888671875
--52.24301528930664,22.565208435058594
--48.748653411865234,20.55536651611328
--52.24864196777344,20.565216064453125
--48.75428009033203,18.555374145507812
--52.254268646240234,18.565223693847656
--48.759910583496094,16.555381774902344
--52.2598991394043,16.565231323242188
--48.76553726196289,14.555389404296875
--52.265525817871094,14.565238952636719
--48.77116775512695,12.555397033691406
--52.271156311035156,12.56524658203125
--48.77679443359375,10.555404663085938
--52.27678298950195,10.565254211425781
--48.78242111206055,8.555412292480469
--52.28240966796875,8.565261840820312
--48.78805160522461,6.555419921875
--52.28804016113281,6.5652689933776855
--48.793678283691406,4.555427551269531
--52.29366683959961,4.565276622772217
--48.7993049621582,2.555438995361328
--52.299293518066406,2.5652883052825928
--48.804935455322266,0.5554465055465698
--52.30492401123047,0.5652958750724792
--48.81056213378906,-1.444545865058899
--52.310550689697266,-1.4346965551376343
+X,Y
+-27.017662048339844,66.21400451660156
+-28.86618423461914,66.14916229248047
+-30.66202735900879,65.89645385742188
+-32.42102813720703,65.45503234863281
+-34.12340545654297,64.82988739013672
+-35.75004196166992,64.02803039550781
+-37.282649993896484,63.0584716796875
+-38.63057327270508,61.96412658691406
+-39.74671936035156,60.686317443847656
+-40.627471923828125,59.23619842529297
+-41.24679946899414,57.65663528442383
+-41.58638381958008,55.99433135986328
+-41.653968811035156,54.193668365478516
+-41.65959930419922,52.19367599487305
+-48.57393264770508,82.6451187133789
+-52.07392120361328,82.65496826171875
+-48.579559326171875,80.64512634277344
+-52.07954788208008,80.65497589111328
+-48.58518981933594,78.64513397216797
+-52.08517837524414,78.65498352050781
+-48.590816497802734,76.6451416015625
+-52.09080505371094,76.65499114990234
+-48.59644317626953,74.64514923095703
+-52.096431732177734,74.65499877929688
+-48.602073669433594,72.64515686035156
+-52.1020622253418,72.6550064086914
+-48.60770034790039,70.6451644897461
+-52.107688903808594,70.65501403808594
+-48.61333084106445,68.64517211914062
+-52.113319396972656,68.65502166748047
+-48.61895751953125,66.64517974853516
+-52.11894607543945,66.655029296875
+-48.62458419799805,64.64518737792969
+-52.12457275390625,64.65503692626953
+-48.63021469116211,62.64520263671875
+-52.13020324707031,62.655052185058594
+-48.635841369628906,60.64521026611328
+-52.13582992553711,60.655059814453125
+-48.6414680480957,58.64521789550781
+-52.141456604003906,58.655067443847656
+-48.647098541259766,56.645225524902344
+-52.14708709716797,56.65507507324219
+-48.65272521972656,54.645233154296875
+-52.152713775634766,54.65508270263672
+-48.658355712890625,52.645240783691406
+-52.15834426879883,52.65509033203125
+26.435718536376953,16.757444381713867
+26.44544219970703,13.257457733154297
+28.43570899963379,16.76300048828125
+28.445432662963867,13.26301383972168
+30.435701370239258,16.768558502197266
+30.445425033569336,13.268571853637695
+32.43569564819336,16.77411460876465
+32.44541931152344,13.274127960205078
+34.435691833496094,16.779672622680664
+34.44541549682617,13.279685974121094
+36.43568420410156,16.785228729248047
+36.44540786743164,13.285242080688477
+38.435672760009766,16.790786743164062
+38.445396423339844,13.290800094604492
+40.435665130615234,16.796342849731445
+40.44538879394531,13.296356201171875
+42.4356575012207,16.80190086364746
+42.44538116455078,13.30191421508789
+44.43564987182617,16.807456970214844
+44.44537353515625,13.307470321655273
+46.43564224243164,16.81301498413086
+46.44536590576172,13.313028335571289
+48.43563461303711,16.818571090698242
+48.44535827636719,13.318584442138672
+50.43562698364258,16.82413101196289
+50.445350646972656,13.32414436340332
+52.43561935424805,16.829687118530273
+52.445343017578125,13.329700469970703
+54.435611724853516,16.83524513244629
+54.445335388183594,13.335258483886719
+56.43560028076172,16.84079933166504
+56.4453239440918,13.340812683105469
+26.40376853942871,28.25739860534668
+26.41349220275879,24.75741195678711
+28.403759002685547,28.262954711914062
+28.413482666015625,24.762968063354492
+30.403751373291016,28.268512725830078
+30.413475036621094,24.768526077270508
+32.403743743896484,28.27406883239746
+32.41346740722656,24.77408218383789
+34.40373992919922,28.279626846313477
+34.4134635925293,24.779640197753906
+36.40373229980469,28.28518295288086
+36.413455963134766,24.78519630432129
+38.40372085571289,28.290740966796875
+38.41344451904297,24.790754318237305
+40.40371322631836,28.296297073364258
+40.41343688964844,24.796310424804688
+42.40370559692383,28.301855087280273
+42.413429260253906,24.801868438720703
+44.4036979675293,28.307411193847656
+44.413421630859375,24.807424545288086
+46.403690338134766,28.312969207763672
+46.413414001464844,24.8129825592041
+48.403682708740234,28.318525314331055
+48.41340637207031,24.818538665771484
+50.4036750793457,28.324085235595703
+50.41339874267578,24.824098587036133
+52.40366744995117,28.329641342163086
+52.41339111328125,24.829654693603516
+54.40365982055664,28.3351993560791
+54.41338348388672,24.83521270751953
+56.403648376464844,28.34075355529785
+56.41337203979492,24.84076690673828
+43.88934326171875,41.89961624145508
+43.86312484741211,39.89978790283203
+43.863258361816406,38.02463150024414
+44.10757064819336,36.347923278808594
+44.637516021728516,34.7385139465332
+45.43720245361328,33.24468231201172
+46.482635498046875,31.91122817993164
+47.7593879699707,30.743762969970703
+49.197444915771484,29.782909393310547
+50.765567779541016,29.053367614746094
+52.426841735839844,28.572307586669922
+54.142154693603516,28.351058959960938
+56.04743576049805,28.339763641357422
+-106.7159194946289,-2.2476232051849365
+-106.73834228515625,-0.2477264553308487
+-106.76075744628906,1.7521477937698364
+-106.65607452392578,3.465054750442505
+-106.25785064697266,5.106363773345947
+-105.57762908935547,6.652252674102783
+-104.63652801513672,8.054685592651367
+-103.46380615234375,9.270086288452148
+-102.05567169189453,10.304855346679688
+-100.48445892333984,11.197660446166992
+-98.82495880126953,11.913121223449707
+-97.09711456298828,12.442638397216797
+-95.32169342041016,12.779848098754883
+-93.52003479003906,12.920698165893555
+-91.5557861328125,12.929587364196777
+-89.55579376220703,12.935144424438477
+-88.67606353759766,24.437633514404297
+-90.67620086669922,24.43207550048828
+-92.67619323730469,24.4265193939209
+-94.67618560791016,24.420961380004883
+-96.92293548583984,24.256216049194336
+-99.12898254394531,23.7534236907959
+-101.23404693603516,22.923866271972656
+-103.19002532958984,21.786497116088867
+-104.95222473144531,20.3673038482666
+-106.47366333007812,18.71123504638672
+-107.74635314941406,16.8935546875
+-108.7806396484375,14.930402755737305
+-109.56012725830078,12.85287857055664
+-110.07247161865234,10.693896293640137
+-110.3095474243164,8.487656593322754
+-110.31298065185547,6.391233921051025
+-110.29056549072266,4.391359806060791
+-110.26815032958984,2.3914854526519775
+-110.2457275390625,0.391611248254776
+-110.22331237792969,-1.6080056428909302
+-107.23321533203125,43.899478912353516
+-107.21080017089844,41.89960479736328
+-107.1883773803711,39.89973068237305
+-107.16596221923828,37.89985656738281
+-107.14354705810547,35.89998245239258
+-107.12112426757812,33.900108337402344
+-107.09870910644531,31.900232315063477
+-107.0762939453125,29.900358200073242
+-107.05387115478516,27.900484085083008
+-107.03145599365234,25.900609970092773
+-107.00904083251953,23.90073585510254
+-106.98661804199219,21.900861740112305
+-106.96420288085938,19.900985717773438
+-106.94178771972656,17.901111602783203
+-106.91936492919922,15.901237487792969
+-106.8969497680664,13.901363372802734
+-106.87452697753906,11.9014892578125
+-106.85211181640625,9.901615142822266
+-106.82969665527344,7.9017415046691895
+-106.8072738647461,5.901867389678955
+-106.78485870361328,3.9019930362701416
+-106.76244354248047,1.9021190404891968
+-106.74002075195312,-0.09775511920452118
+-106.71760559082031,-2.0976293087005615
+85.98224639892578,66.35848999023438
+87.98269653320312,66.36105346679688
+89.87236785888672,66.34451293945312
+91.54315185546875,66.09268951416016
+93.14398193359375,65.55207061767578
+94.62535095214844,64.73937225341797
+95.94143676757812,63.67972946166992
+97.05847930908203,62.40235137939453
+97.94198608398438,60.952213287353516
+98.56529998779297,59.372676849365234
+98.91018676757812,57.70998764038086
+98.98468017578125,55.90883255004883
+98.99832153320312,53.90888214111328
+83.04327392578125,24.91476058959961
+85.04326629638672,24.920316696166992
+87.04325866699219,24.925874710083008
+89.04325103759766,24.93143081665039
+91.04324340820312,24.936988830566406
+93.26031494140625,24.802600860595703
+95.44329071044922,24.386388778686523
+97.55535888671875,23.695146560668945
+99.56200408935547,22.74016761779785
+101.43045806884766,21.537046432495117
+103.13019561767578,20.10544204711914
+104.63346099853516,18.468734741210938
+105.91030883789062,16.723594665527344
+107.0205307006836,14.871212005615234
+107.95658111572266,12.925009727478027
+108.71060943603516,10.901317596435547
+109.27629852294922,8.817115783691406
+109.64889526367188,6.689895153045654
+109.82527160644531,4.537504196166992
+109.8492660522461,2.486750364303589
+109.86289978027344,0.4867967665195465
+109.87653350830078,-1.5129233598709106
+109.89017486572266,-3.512876510620117
+106.07840728759766,42.18954086303711
+106.09205627441406,40.18917465209961
+106.1056900024414,38.1892204284668
+106.11933135986328,36.189266204833984
+106.13297271728516,34.18931198120117
+106.14661407470703,32.18935775756836
+106.16024780273438,30.18940544128418
+106.13570404052734,28.065265655517578
+105.82524871826172,25.831296920776367
+105.1906509399414,23.666975021362305
+104.24563598632812,21.61906623840332
+103.0105972290039,19.731821060180664
+101.51223754882812,18.046016693115234
+99.80238342285156,16.60074234008789
+97.91151428222656,15.403153419494629
+95.87468719482422,14.475281715393066
+93.73014831542969,13.834546089172363
+91.51814270019531,13.492974281311035
+89.37653350830078,13.432313919067383
+87.37654113769531,13.426756858825684
+85.37654876708984,13.421199798583984
+83.37641906738281,13.415641784667969
+83.0335464477539,28.41474723815918
+85.0335464477539,28.420303344726562
+87.03353118896484,28.425859451293945
+88.89058685302734,28.472421646118164
+90.62525177001953,28.740413665771484
+92.30603790283203,29.246244430541992
+93.9004898071289,29.980152130126953
+95.37783813476562,30.927968978881836
+96.65447235107422,32.0466194152832
+97.68544006347656,33.3599853515625
+98.4537353515625,34.842403411865234
+98.93246459960938,36.441986083984375
+99.1048812866211,38.10274124145508
+99.0926742553711,40.073665618896484
+99.07903289794922,42.07429885864258
+109.57832336425781,42.213409423828125
+106.07840728759766,42.18954086303711
+109.59196472167969,40.21345520019531
+106.09204864501953,40.1895866394043
+109.60560607910156,38.2135009765625
+106.1056900024414,38.189632415771484
+109.6192398071289,36.21355056762695
+106.11932373046875,36.18968200683594
+109.63288116455078,34.21359634399414
+106.13296508789062,34.189727783203125
+109.64652252197266,32.21364212036133
+106.1466064453125,32.18977355957031
+109.66016387939453,30.213685989379883
+106.16024780273438,30.189817428588867
+109.67379760742188,28.21373176574707
+106.17388153076172,28.189863204956055
+109.68743896484375,26.21377944946289
+106.1875228881836,26.189910888671875
+109.70108032226562,24.213825225830078
+106.20116424560547,24.189956665039062
+109.7147216796875,22.2138729095459
+106.21480560302734,22.190004348754883
+109.72835540771484,20.213918685913086
+106.22843933105469,20.19005012512207
+109.74199676513672,18.213966369628906
+106.24208068847656,18.19009780883789
+109.7556381225586,16.214012145996094
+106.25572204589844,16.190143585205078
+109.76927947998047,14.214058876037598
+106.26936340332031,14.190189361572266
+109.78292083740234,12.214106559753418
+106.28300476074219,12.190237045288086
+109.79655456542969,10.214152336120605
+106.29663848876953,10.190282821655273
+109.81019592285156,8.214198112487793
+106.3102798461914,8.190328598022461
+109.82383728027344,6.2142438888549805
+106.32392120361328,6.190374851226807
+109.83747863769531,4.214293479919434
+106.33756256103516,4.19042444229126
+109.85111236572266,2.214339256286621
+106.3511962890625,2.190469980239868
+109.86475372314453,0.21438491344451904
+106.36483764648438,0.19051580131053925
+109.8783950805664,-1.7855693101882935
+106.37847900390625,-1.8094384670257568
+109.89203643798828,-3.7855234146118164
+106.39212036132812,-3.8093926906585693
+102.57848358154297,42.16566848754883
+99.07856750488281,42.14179992675781
+102.59212493896484,40.165714263916016
+99.09220886230469,40.141845703125
+102.60576629638672,38.1657600402832
+99.10585021972656,38.14189147949219
+102.61940002441406,36.165809631347656
+99.1194839477539,36.14194107055664
+102.63304138183594,34.165855407714844
+99.13312530517578,34.14198684692383
+102.64668273925781,32.16590118408203
+99.14676666259766,32.142032623291016
+102.66032409667969,30.16594886779785
+99.16040802001953,30.142080307006836
+102.67395782470703,28.16599464416504
+99.17404174804688,28.142126083374023
+102.6875991821289,26.16604232788086
+99.18768310546875,26.142173767089844
+102.70124053955078,24.166088104248047
+99.20132446289062,24.14221954345703
+102.71488189697266,22.166135787963867
+99.2149658203125,22.14226722717285
+102.728515625,20.166181564331055
+99.22859954833984,20.14231300354004
+102.74215698242188,18.166229248046875
+99.24224090576172,18.14236068725586
+102.75579833984375,16.166275024414062
+99.2558822631836,16.142406463623047
+102.76943969726562,14.16632080078125
+99.26952362060547,14.142451286315918
+102.7830810546875,12.16636848449707
+99.28316497802734,12.142498970031738
+102.79671478271484,10.166414260864258
+99.29679870605469,10.142544746398926
+102.81035614013672,8.166460037231445
+99.31044006347656,8.142590522766113
+102.8239974975586,6.166505336761475
+99.32408142089844,6.142636299133301
+102.83763885498047,4.166554927825928
+99.33772277832031,4.142685890197754
+102.85127258300781,2.1666009426116943
+99.35135650634766,2.1427316665649414
+102.86491394042969,0.16664667427539825
+99.36499786376953,0.14277756214141846
+102.87855529785156,-1.8333075046539307
+99.3786392211914,-1.857176661491394
+102.89219665527344,-3.833261728286743
+99.39228057861328,-3.857131004333496
+-28.517200469970703,130.03573608398438
+-30.30147361755371,129.92938232421875
+-32.03142166137695,129.5891876220703
+-33.700050354003906,129.0198516845703
+-35.27717971801758,128.23175048828125
+-36.734256744384766,127.23908996582031
+-38.04182052612305,126.0622329711914
+-39.16381072998047,124.72201538085938
+-40.0830192565918,123.23536682128906
+-40.78063201904297,121.63275146484375
+-41.24235153198242,119.94696807861328
+-41.458736419677734,118.2125473022461
+-41.47919845581055,116.2996597290039
+-70.48973083496094,128.9029083251953
+-68.70108795166016,129.21397399902344
+-66.88970184326172,129.33590698242188
+-65.07550048828125,129.26742553710938
+-63.27846145629883,129.00926208496094
+-61.51835632324219,128.5642547607422
+-59.81455993652344,127.93727111816406
+-58.185829162597656,127.13525390625
+-56.70155334472656,126.18061065673828
+-55.390159606933594,125.03644561767578
+-54.2611083984375,123.71202850341797
+-53.33891677856445,122.236083984375
+-52.643585205078125,120.64066314697266
+-52.19021987915039,118.96038818359375
+-51.9886589050293,117.23174285888672
+-51.98202133178711,115.31092834472656
+-71.26968383789062,132.3148956298828
+-69.39166259765625,132.69732666015625
+-67.4975814819336,132.99000549316406
+-65.59546661376953,133.19189453125
+-63.81114959716797,133.224853515625
+-62.03615951538086,133.03965759277344
+-60.29707336425781,132.63906860351562
+-58.619930267333984,132.02906799316406
+-57.02983856201172,131.21884155273438
+-55.55060958862305,130.220458984375
+-54.10551452636719,128.99887084960938
+-52.78818893432617,127.7421875
+-51.633087158203125,126.35982513427734
+-50.64110565185547,124.85610961914062
+-49.82487869262695,123.25019836425781
+-49.19478988647461,121.56254577636719
+-48.758880615234375,119.81464385986328
+-48.5226936340332,118.02875518798828
+-48.47959899902344,116.16610717773438
+-52.142601013183594,-43.38029861450195
+-48.6427001953125,-43.35388946533203
+-45.142799377441406,-43.327484130859375
+-41.64289855957031,-43.30107498168945
+-52.157691955566406,-41.38035583496094
+-48.65779113769531,-41.353946685791016
+-45.15789031982422,-41.32754135131836
+-41.657989501953125,-41.30113220214844
+-52.17278289794922,-39.38041305541992
+-48.672882080078125,-39.35400390625
+-45.17298126220703,-39.327598571777344
+-41.67308044433594,-39.30118942260742
+-52.18787384033203,-37.380470275878906
+-48.68797302246094,-37.354061126708984
+-45.188072204589844,-37.32765579223633
+-41.68817138671875,-37.301246643066406
+-52.202964782714844,-35.38052749633789
+-48.70306396484375,-35.35411834716797
+-45.203163146972656,-35.32771301269531
+-41.70326232910156,-35.30130386352539
+-52.218055725097656,-33.380584716796875
+-48.71815490722656,-33.35417556762695
+-45.21825408935547,-33.3277702331543
+-41.718353271484375,-33.301361083984375
+-52.23314666748047,-31.38064193725586
+-48.733245849609375,-31.354232788085938
+-45.23334503173828,-31.327823638916016
+-41.73344421386719,-31.301414489746094
+-52.24823760986328,-29.380699157714844
+-48.74833679199219,-29.354290008544922
+-45.248435974121094,-29.327880859375
+-41.74853515625,-29.301471710205078
+-52.263328552246094,-27.380756378173828
+-48.763427734375,-27.354347229003906
+-45.263526916503906,-27.327938079833984
+-41.76362609863281,-27.301528930664062
+-52.278419494628906,-25.380813598632812
+-48.77851867675781,-25.35440444946289
+-45.27861785888672,-25.32799530029297
+-41.778717041015625,-25.301586151123047
+-52.29351043701172,-23.380870819091797
+-48.793609619140625,-23.354461669921875
+-45.29370880126953,-23.328052520751953
+-41.79380798339844,-23.30164337158203
+-52.30860137939453,-21.38092613220215
+-48.80870056152344,-21.354516983032227
+-45.308799743652344,-21.328107833862305
+-41.80889892578125,-21.301698684692383
+-52.323692321777344,-19.380983352661133
+-48.82379150390625,-19.35457420349121
+-45.323890686035156,-19.32816505432129
+-41.82398986816406,-19.301755905151367
+-52.338783264160156,-17.381040573120117
+-48.83888244628906,-17.354631423950195
+-45.33898162841797,-17.328222274780273
+-41.839080810546875,-17.30181312561035
+57.403648376464844,28.34353256225586
+57.41337203979492,24.84354591369629
+57.43560028076172,16.843578338623047
+57.44532775878906,13.343591690063477
+59.40364074707031,28.349088668823242
+59.41336441040039,24.849102020263672
+59.43559265136719,16.84913444519043
+59.44532012939453,13.34914779663086
+61.40363311767578,28.354646682739258
+61.41335678100586,24.854660034179688
+61.435585021972656,16.854692459106445
+61.4453125,13.354705810546875
+63.40362548828125,28.36020278930664
+63.41334915161133,24.86021614074707
+63.435577392578125,16.860248565673828
+63.44530487060547,13.360261917114258
+65.40361022949219,28.365760803222656
+65.41333770751953,24.865774154663086
+65.43556213378906,16.865806579589844
+65.4452896118164,13.365819931030273
+67.40360260009766,28.37131690979004
+67.413330078125,24.87133026123047
+67.43555450439453,16.871362686157227
+67.44528198242188,13.371376037597656
+69.40359497070312,28.376874923706055
+69.41332244873047,24.876888275146484
+69.435546875,16.876920700073242
+69.44527435302734,13.376934051513672
+71.4035873413086,28.382431030273438
+71.41331481933594,24.882444381713867
+71.43553924560547,16.882476806640625
+71.44526672363281,13.382490158081055
+73.40357971191406,28.387989044189453
+73.4133071899414,24.888002395629883
+73.43553161621094,16.88803482055664
+73.44525909423828,13.38804817199707
+75.40357208251953,28.393545150756836
+75.41329956054688,24.893558502197266
+75.4355239868164,16.893590927124023
+75.44525146484375,13.393604278564453
+77.40357208251953,28.39910316467285
+77.41329956054688,24.89911651611328
+77.4355239868164,16.89914894104004
+77.44525146484375,13.399162292480469
+79.40355682373047,28.404659271240234
+79.41328430175781,24.904672622680664
+79.43550872802734,16.904705047607422
+79.44523620605469,13.404718399047852
+81.40354919433594,28.41021728515625
+81.41327667236328,24.91023063659668
+81.43550109863281,16.910263061523438
+81.44522857666016,13.410276412963867
+-28.71629524230957,24.604232788085938
+-30.71660614013672,24.598674774169922
+-32.90773010253906,24.49801254272461
+-35.12482833862305,24.075864791870117
+-37.25544738769531,23.331411361694336
+-39.25299835205078,22.280921936035156
+-41.073814392089844,20.947364807128906
+-42.67808151245117,19.35989761352539
+-44.03073501586914,17.55322265625
+-45.10219192504883,15.566841125488281
+-45.859161376953125,13.515207290649414
+-46.47522735595703,11.612456321716309
+-47.09511947631836,9.681135177612305
+-47.653873443603516,7.663947105407715
+-48.10423278808594,5.619825839996338
+-48.444908142089844,3.5545921325683594
+-48.6749382019043,1.474125862121582
+-48.793663024902344,-0.6156484484672546
+-88.685791015625,27.937620162963867
+-90.68607330322266,27.93206024169922
+-92.68606567382812,27.926504135131836
+-94.6860580444336,27.92094612121582
+-96.8669204711914,27.824932098388672
+-99.07166290283203,27.43034553527832
+-101.20113372802734,26.736164093017578
+-103.21484375,25.75558853149414
+-105.07449340820312,24.50726890563965
+-106.76020812988281,22.98198127746582
+-108.18182373046875,21.178382873535156
+-109.27572631835938,19.15913963317871
+-110.00997924804688,16.983177185058594
+-110.36316680908203,14.713991165161133
+-110.3823013305664,12.574618339538574
+-110.35987854003906,10.57474422454834
+-110.33746337890625,8.574869155883789
+-110.31504821777344,6.574995040893555
+-110.2926254272461,4.575120449066162
+-110.27021026611328,2.575246572494507
+-110.24779510498047,0.5753723978996277
+-110.22537231445312,-1.4242451190948486
+109.30042266845703,82.96246337890625
+105.80050659179688,82.93859100341797
+109.31405639648438,80.96250915527344
+105.81414031982422,80.93863677978516
+109.32769775390625,78.96255493164062
+105.8277816772461,78.93868255615234
+109.34133911132812,76.96260070800781
+105.84142303466797,76.93872833251953
+109.35498046875,74.962646484375
+105.85506439208984,74.93877410888672
+109.36862182617188,72.96269226074219
+105.86870574951172,72.9388198852539
+109.38225555419922,70.96273803710938
+105.88233947753906,70.9388656616211
+109.3958969116211,68.9627914428711
+105.89598083496094,68.93891906738281
+109.40953826904297,66.96283721923828
+105.90962219238281,66.93896484375
+109.42317962646484,64.96288299560547
+105.92326354980469,64.93901062011719
+109.43682098388672,62.962928771972656
+105.93690490722656,62.93906021118164
+109.45045471191406,60.962974548339844
+105.9505386352539,60.93910598754883
+109.46409606933594,58.96302032470703
+105.96417999267578,58.939151763916016
+109.47773742675781,56.96306610107422
+105.97782135009766,56.9391975402832
+109.49137115478516,54.963111877441406
+105.991455078125,54.93924331665039
+83.07522583007812,13.41480541229248
+85.03021240234375,13.414726257324219
+86.83293914794922,13.274620056152344
+88.60968780517578,12.939041137695312
+90.33931732177734,12.411982536315918
+92.00128173828125,11.699708938598633
+93.57579803466797,10.810693740844727
+95.04048919677734,9.758234024047852
+96.3056640625,8.567916870117188
+97.37969970703125,7.202645301818848
+98.23870086669922,5.6927995681762695
+98.86356353759766,4.071972846984863
+99.24036407470703,2.3762311935424805
+99.36173248291016,0.622090756893158
+99.37537384033203,-1.3778626918792725
+99.3890151977539,-3.3778162002563477
+-28.72602081298828,28.104219436645508
+-28.71629524230957,24.604232788085938
+-28.694067001342773,16.604265213012695
+-28.684343338012695,13.104278564453125
+-26.726028442382812,28.10977554321289
+-26.7163028717041,24.60978889465332
+-26.694074630737305,16.609821319580078
+-26.684350967407227,13.109834671020508
+-24.726036071777344,28.115333557128906
+-24.716310501098633,24.615346908569336
+-24.694082260131836,16.615379333496094
+-24.684358596801758,13.115392684936523
+-22.726043701171875,28.12088966369629
+-22.716318130493164,24.62090301513672
+-22.694089889526367,16.620935440063477
+-22.68436622619629,13.120948791503906
+-20.726051330566406,28.126447677612305
+-20.716325759887695,24.626461029052734
+-20.6940975189209,16.626493453979492
+-20.68437385559082,13.126506805419922
+-18.726058959960938,28.132003784179688
+-18.716333389282227,24.632017135620117
+-18.69410514831543,16.632049560546875
+-18.68438148498535,13.132062911987305
+-16.7260684967041,28.137561798095703
+-16.71634292602539,24.637575149536133
+-16.694114685058594,16.63760757446289
+-16.684391021728516,13.13762092590332
+-14.726075172424316,28.143117904663086
+-14.716350555419922,24.643131256103516
+-14.694122314453125,16.643163681030273
+-14.684396743774414,13.143177032470703
+-12.726082801818848,28.1486759185791
+-12.716358184814453,24.64868927001953
+-12.694129943847656,16.64872169494629
+-12.684404373168945,13.148735046386719
+-10.726089477539062,28.154232025146484
+-10.716364860534668,24.654245376586914
+-10.694136619567871,16.654277801513672
+-10.68441104888916,13.154291152954102
+-8.726097106933594,28.1597900390625
+-8.7163724899292,24.65980339050293
+-8.694144248962402,16.659835815429688
+-8.684418678283691,13.159849166870117
+-6.726106643676758,28.165346145629883
+-6.716381549835205,24.665359497070312
+-6.694153308868408,16.66539192199707
+-6.684428691864014,13.1654052734375
+-4.726114273071289,28.1709041595459
+-4.716389179229736,24.670917510986328
+-4.6941609382629395,16.670949935913086
+-4.684436321258545,13.170963287353516
+-2.726121664047241,28.17646026611328
+-2.7163968086242676,24.67647361755371
+-2.69416880607605,16.67650604248047
+-2.684443950653076,13.176519393920898
+-0.7261292934417725,28.182018280029297
+-0.7164044976234436,24.682031631469727
+-0.6941763162612915,16.682064056396484
+-0.6844515204429626,13.182077407836914
+1.2738630771636963,28.18757438659668
+1.2835878133773804,24.68758773803711
+1.3058159351348877,16.687620162963867
+1.3155407905578613,13.187633514404297
+3.273855447769165,28.193132400512695
+3.2835803031921387,24.693145751953125
+3.3058083057403564,16.693178176879883
+3.31553316116333,13.193191528320312
+5.2738494873046875,28.198688507080078
+5.28357458114624,24.698701858520508
+5.305802822113037,16.698734283447266
+5.315527439117432,13.198747634887695
+7.273841857910156,28.204246520996094
+7.283566951751709,24.704259872436523
+7.305795192718506,16.70429229736328
+7.3155198097229,13.204305648803711
+9.273834228515625,28.209802627563477
+9.28355884552002,24.709815979003906
+9.305787086486816,16.709848403930664
+9.315512657165527,13.209861755371094
+11.273826599121094,28.215360641479492
+11.283551216125488,24.715373992919922
+11.305779457092285,16.71540641784668
+11.315505027770996,13.21541976928711
+13.273818969726562,28.220916748046875
+13.283543586730957,24.720930099487305
+13.305771827697754,16.720962524414062
+13.315497398376465,13.220975875854492
+15.273807525634766,28.22647476196289
+15.28353214263916,24.72648811340332
+15.305760383605957,16.726520538330078
+15.315485954284668,13.226533889770508
+17.273799896240234,28.232030868530273
+17.283525466918945,24.732044219970703
+17.305753707885742,16.73207664489746
+17.31547737121582,13.23208999633789
+19.273792266845703,28.23758888244629
+19.283517837524414,24.73760223388672
+19.30574607849121,16.737634658813477
+19.31546974182129,13.237648010253906
+21.273784637451172,28.243144989013672
+21.283510208129883,24.7431583404541
+21.30573844909668,16.74319076538086
+21.315462112426758,13.243204116821289
+23.27377700805664,28.248703002929688
+23.28350257873535,24.748716354370117
+23.30573081970215,16.748748779296875
+23.315454483032227,13.248762130737305
+25.27376937866211,28.25425910949707
+25.28349494934082,24.7542724609375
+25.305723190307617,16.754304885864258
+25.315446853637695,13.254318237304688
+-103.21614074707031,-2.2083919048309326
+-103.23856353759766,-0.2086300402879715
+-103.2192153930664,1.6438419818878174
+-102.96272277832031,3.357247829437256
+-102.44989776611328,5.01210880279541
+-101.69257354736328,6.5703125
+-100.70816802978516,7.995970726013184
+-99.51937103271484,9.25624942779541
+-98.13174438476562,10.363348007202148
+-96.61287689208984,11.290770530700684
+-94.99005126953125,12.021167755126953
+-93.28866577148438,12.543092727661133
+-91.5354232788086,12.848367691040039
+-89.72577667236328,12.934672355651855
+-66.8261489868164,24.498342514038086
+-64.82615661621094,24.50389862060547
+-62.80895233154297,24.508527755737305
+-60.624412536621094,24.374526977539062
+-58.46719741821289,24.004953384399414
+-56.362632751464844,23.404142379760742
+-54.335426330566406,22.579153060913086
+-52.40938949584961,21.5396671295166
+-50.60712432861328,20.297895431518555
+-48.94979476928711,18.868408203125
+-47.46052932739258,17.27355194091797
+-46.146366119384766,15.564069747924805
+-44.99060821533203,13.743748664855957
+-44.00253677368164,11.827221870422363
+-43.19010925292969,9.829895973205566
+-42.55984115600586,7.767829895019531
+-42.11681365966797,5.657598495483398
+-41.86457443237305,3.5161664485931396
+-41.80257034301758,1.3860589265823364
+-41.80820083618164,-0.6141355633735657
+-78.07583618164062,27.967100143432617
+-78.06610870361328,24.467113494873047
+-78.04388427734375,16.467145919799805
+-78.0341567993164,12.967159271240234
+-76.07584381103516,27.97265625
+-76.06611633300781,24.47266960144043
+-76.04389190673828,16.472702026367188
+-76.03416442871094,12.972715377807617
+-74.07585144042969,27.978214263916016
+-74.06612396240234,24.478227615356445
+-74.04389953613281,16.478260040283203
+-74.03417205810547,12.978273391723633
+-72.07585906982422,27.9837703704834
+-72.06613159179688,24.483783721923828
+-72.04390716552734,16.483816146850586
+-72.0341796875,12.983829498291016
+-70.07586669921875,27.989328384399414
+-70.0661392211914,24.489341735839844
+-70.04391479492188,16.4893741607666
+-70.03418731689453,12.989387512207031
+-68.07587432861328,27.994884490966797
+-68.06614685058594,24.494897842407227
+-68.0439224243164,16.494930267333984
+-68.03419494628906,12.994943618774414
+-114.23278045654297,43.821014404296875
+-114.21036529541016,41.82114028930664
+-114.18794250488281,39.82085037231445
+-114.16552734375,37.82097625732422
+-114.14310455322266,35.821102142333984
+-114.11214447021484,33.769737243652344
+-113.88878631591797,31.570682525634766
+-113.40167999267578,29.414657592773438
+-112.65792846679688,27.33317756652832
+-111.66839599609375,25.356672286987305
+-110.44757843017578,23.5140380859375
+-109.01329040527344,21.83220672607422
+-107.37828063964844,20.333969116210938
+-105.56774139404297,19.05193519592285
+-103.61077880859375,18.00696563720703
+-101.53826141357422,17.215547561645508
+-99.38288879394531,16.690162658691406
+-97.17865753173828,16.439104080200195
+-95.08568572998047,16.4197940826416
+-93.085693359375,16.425350189208984
+-91.08570098876953,16.430908203125
+-89.0857162475586,16.436464309692383
+-88.685791015625,27.937620162963867
+-88.67606353759766,24.437633514404297
+-88.65383911132812,16.437665939331055
+-88.64411163330078,12.937679290771484
+-86.68579864501953,27.94317626953125
+-86.67607116699219,24.44318962097168
+-86.65384674072266,16.443222045898438
+-86.64411926269531,12.943235397338867
+-84.68580627441406,27.948734283447266
+-84.67607879638672,24.448747634887695
+-84.65385437011719,16.448780059814453
+-84.64412689208984,12.948793411254883
+-82.6858139038086,27.95429039001465
+-82.67608642578125,24.454303741455078
+-82.65386199951172,16.454336166381836
+-82.64413452148438,12.954349517822266
+-80.68582153320312,27.959848403930664
+-80.67609405517578,24.459861755371094
+-80.65386962890625,16.45989418029785
+-80.6441421508789,12.959907531738281
+-78.68582916259766,27.965404510498047
+-78.67610168457031,24.465417861938477
+-78.65387725830078,16.465450286865234
+-78.64414978027344,12.965463638305664
+7.407855033874512,-67.89999389648438
+7.409285068511963,-64.39999389648438
+7.410714626312256,-60.899993896484375
+7.412144660949707,-57.399993896484375
+5.44331169128418,-67.90583801269531
+5.421112537384033,-64.4059066772461
+5.3989129066467285,-60.90597915649414
+5.376713752746582,-57.40605163574219
+3.478853940963745,-67.92493438720703
+3.433025360107422,-64.42523193359375
+3.3871965408325195,-60.925533294677734
+3.3413679599761963,-57.42583465576172
+1.4941807985305786,-67.95541381835938
+1.4382917881011963,-64.45585632324219
+1.3824028968811035,-60.95630645751953
+1.3265138864517212,-57.456748962402344
+-0.5055642127990723,-67.98735046386719
+-0.5614531636238098,-64.48779296875
+-0.6173421740531921,-60.988243103027344
+-0.6732311248779297,-57.488685607910156
+-2.5168769359588623,-68.01824188232422
+-2.565066337585449,-64.51856994628906
+-2.613255500793457,-61.01890182495117
+-2.661444902420044,-57.51923370361328
+-4.5343427658081055,-68.04209899902344
+-4.570794582366943,-64.54228973388672
+-4.607245922088623,-61.04248046875
+-4.643697738647461,-57.54267120361328
+-41.82001876831055,-4.8147735595703125
+-45.32000732421875,-4.804924488067627
+-48.81999206542969,-4.795074939727783
+-52.31998062133789,-4.785225868225098
+-41.825645446777344,-6.814765453338623
+-45.32563400268555,-6.8049163818359375
+-48.825618743896484,-6.795066833496094
+-52.32560729980469,-6.785217761993408
+-41.83384323120117,-8.829364776611328
+-45.33378601074219,-8.809771537780762
+-48.83373260498047,-8.790177345275879
+-52.333675384521484,-8.770584106445312
+-41.84503936767578,-10.829333305358887
+-45.3449821472168,-10.80974006652832
+-48.84492874145508,-10.790145874023438
+-52.344871520996094,-10.770552635192871
+-41.85272979736328,-12.809256553649902
+-45.352725982666016,-12.8030366897583
+-48.852718353271484,-12.7968168258667
+-52.35271453857422,-12.790596961975098
+-41.85203552246094,-14.78698444366455
+-45.35202407836914,-14.795611381530762
+-48.85201644897461,-14.804238319396973
+-52.35200500488281,-14.812865257263184
+-41.84298324584961,-16.764692306518555
+-45.34290313720703,-16.788166046142578
+-48.84282684326172,-16.81163787841797
+-52.34274673461914,-16.835111618041992
+-41.81126403808594,-1.7042442560195923
+-45.31125259399414,-1.6943949460983276
+-48.81123733520508,-1.684545636177063
+-52.31122589111328,-1.6746963262557983
+-41.816890716552734,-3.7042365074157715
+-45.31687927246094,-3.694387197494507
+-48.816864013671875,-3.684537649154663
+-52.31685256958008,-3.6746883392333984
+-41.483009338378906,114.94529724121094
+-44.98299789428711,114.95514678955078
+-48.48298263549805,114.9649887084961
+-51.98297119140625,114.97483825683594
+-41.4886360168457,112.94530487060547
+-44.988624572753906,112.95515441894531
+-48.488609313964844,112.96499633789062
+-51.98859786987305,112.97484588623047
+-41.494266510009766,110.9453125
+-44.99425506591797,110.95516204833984
+-48.494239807128906,110.96500396728516
+-51.99422836303711,110.974853515625
+-41.49989318847656,108.94532012939453
+-44.999881744384766,108.95516967773438
+-48.4998664855957,108.96501159667969
+-51.999855041503906,108.97486114501953
+-41.50551986694336,106.94532775878906
+-45.00550842285156,106.9551773071289
+-48.5054931640625,106.96501922607422
+-52.0054817199707,106.97486877441406
+-41.51115036010742,104.9453353881836
+-45.011138916015625,104.95518493652344
+-48.51112365722656,104.96502685546875
+-52.011112213134766,104.9748764038086
+-41.51677703857422,102.94534301757812
+-45.01676559448242,102.95519256591797
+-48.51675033569336,102.96503448486328
+-52.01673889160156,102.97488403320312
+-41.52240753173828,100.94535064697266
+-45.022396087646484,100.9552001953125
+-48.52238082885742,100.96504211425781
+-52.022369384765625,100.97489166259766
+-41.52803421020508,98.94535827636719
+-45.02802276611328,98.95520782470703
+-48.52800750732422,98.96504974365234
+-52.02799606323242,98.97489929199219
+-41.533660888671875,96.94536590576172
+-45.03364944458008,96.95521545410156
+-48.533634185791016,96.96505737304688
+-52.03362274169922,96.97490692138672
+-41.53929138183594,94.94537353515625
+-45.03927993774414,94.9552230834961
+-48.53926467895508,94.9650650024414
+-52.03925323486328,94.97491455078125
+-41.544918060302734,92.94538879394531
+-45.04490661621094,92.95523834228516
+-48.544891357421875,92.96508026123047
+-52.04487991333008,92.97492980957031
+-41.55054473876953,90.94538879394531
+-45.050533294677734,90.95523834228516
+-48.55051803588867,90.96508026123047
+-52.050506591796875,90.97492980957031
+-41.556175231933594,88.94540405273438
+-45.0561637878418,88.95525360107422
+-48.556148529052734,88.96509552001953
+-52.05613708496094,88.97494506835938
+-41.56180191040039,86.94540405273438
+-45.061790466308594,86.95525360107422
+-48.56177520751953,86.96509552001953
+-52.061763763427734,86.97494506835938
+-41.56743240356445,84.94541931152344
+-45.067420959472656,84.95526885986328
+-48.567405700683594,84.9651107788086
+-52.0673942565918,84.97496032714844
+-41.57305908203125,82.94541931152344
+-45.07304763793945,82.95526885986328
+-48.57303237915039,82.9651107788086
+-52.073020935058594,82.97496032714844
+-66.80392456054688,16.498376846313477
+-66.79419708251953,12.998390197753906
+-64.8039321899414,16.50393295288086
+-64.79420471191406,13.003946304321289
+-62.80393600463867,16.509490966796875
+-62.79420852661133,13.009504318237305
+-60.8039436340332,16.515047073364258
+-60.79421615600586,13.015060424804688
+-58.803951263427734,16.520605087280273
+-58.79422378540039,13.020618438720703
+-56.803958892822266,16.526161193847656
+-56.79423141479492,13.026174545288086
+-54.8039665222168,16.531719207763672
+-54.79423904418945,13.031732559204102
+-52.80397415161133,16.537275314331055
+-52.794246673583984,13.037288665771484
+-50.80398178100586,16.54283332824707
+-50.794254302978516,13.0428466796875
+-48.80398941040039,16.548389434814453
+-48.79426193237305,13.048402786254883
+-46.80399703979492,16.55394744873047
+-46.79426956176758,13.053960800170898
+-44.80400466918945,16.55950355529785
+-44.79427719116211,13.059516906738281
+-42.804012298583984,16.565061569213867
+-42.79428482055664,13.065074920654297
+-40.804019927978516,16.57061767578125
+-40.79429244995117,13.07063102722168
+-38.80402755737305,16.576175689697266
+-38.7943000793457,13.076189041137695
+-36.80403518676758,16.58173179626465
+-36.794307708740234,13.081745147705078
+-34.80404281616211,16.587289810180664
+-34.794315338134766,13.087303161621094
+-32.80405044555664,16.592845916748047
+-32.7943229675293,13.092859268188477
+-30.804058074951172,16.598403930664062
+-30.794334411621094,13.098417282104492
+-28.804065704345703,16.603960037231445
+-28.794342041015625,13.103973388671875
+109.92987823486328,-9.334196090698242
+106.42996215820312,-9.358065605163574
+102.93003845214844,-9.38193416595459
+99.43012237548828,-9.405803680419922
+109.94214630126953,-11.346802711486816
+106.44218444824219,-11.362241744995117
+102.94221496582031,-11.377681732177734
+99.44225311279297,-11.393120765686035
+109.947021484375,-13.367796897888184
+106.447021484375,-13.36923599243164
+102.947021484375,-13.370674133300781
+99.447021484375,-13.372113227844238
+109.94380187988281,-15.38857650756836
+106.4438247680664,-15.376158714294434
+102.94384002685547,-15.363741874694824
+99.44386291503906,-15.351324081420898
+109.93930053710938,-17.36873435974121
+106.43930053710938,-17.36954116821289
+102.93930053710938,-17.370346069335938
+99.43930053710938,-17.371152877807617
+109.94525146484375,-19.339298248291016
+106.4453125,-19.35972023010254
+102.94537353515625,-19.380144119262695
+99.4454345703125,-19.40056610107422
+109.96227264404297,-21.309799194335938
+106.4625015258789,-21.349836349487305
+102.96273040771484,-21.38987159729004
+99.46295928955078,-21.429908752441406
+-66.8261489868164,24.498342514038086
+-64.82615661621094,24.50389862060547
+-62.693565368652344,24.456562042236328
+-60.5024528503418,24.16035270690918
+-58.36332321166992,23.601032257080078
+-56.30764389038086,22.786832809448242
+-54.36567306518555,21.729732513427734
+-52.56597900390625,20.445283889770508
+-50.95553207397461,18.977115631103516
+-49.49954605102539,17.50987434387207
+-48.090599060058594,15.758028984069824
+-46.94546890258789,13.823406219482422
+-46.08749008178711,11.74543285369873
+-45.53415298461914,9.566461563110352
+-45.29673767089844,7.330901145935059
+-45.29166793823242,5.265802383422852
+-45.29729461669922,3.265810012817383
+-45.302921295166016,1.2658182382583618
+-45.30855178833008,-0.7341741323471069
+106.07840728759766,42.18954086303711
+106.09205627441406,40.18917465209961
+106.1056900024414,38.1892204284668
+106.11933135986328,36.189266204833984
+106.07976531982422,34.063968658447266
+105.82299041748047,31.89616584777832
+105.34017181396484,29.767274856567383
+104.63664245605469,27.700794219970703
+103.72016906738281,25.719541549682617
+102.60087585449219,23.845382690429688
+101.26289367675781,22.078367233276367
+99.6535415649414,20.48746681213379
+97.82252502441406,19.157672882080078
+95.81178283691406,18.11945152282715
+93.66738891601562,17.396581649780273
+91.4384536743164,17.005624771118164
+89.27434539794922,16.932044982910156
+87.27435302734375,16.92648696899414
+85.27436065673828,16.920930862426758
+83.27420806884766,16.91537094116211
+-67.15464782714844,-58.193748474121094
+-67.11819458007812,-61.69355773925781
+-65.15475463867188,-58.172916412353516
+-65.11830139160156,-61.672725677490234
+-63.15486526489258,-58.1520881652832
+-63.11841583251953,-61.65189743041992
+-61.154972076416016,-58.13125991821289
+-61.11852264404297,-61.63106918334961
+-59.15507888793945,-58.11042785644531
+-59.118629455566406,-61.61023712158203
+-57.155189514160156,-58.089599609375
+-57.11874008178711,-61.58940887451172
+-55.155296325683594,-58.06877136230469
+-55.11884689331055,-61.568580627441406
+-53.1554069519043,-58.04793930053711
+-53.11895751953125,-61.54774856567383
+-51.155513763427734,-58.0271110534668
+-51.11906433105469,-61.526920318603516
+-49.15562057495117,-58.00627899169922
+-49.119171142578125,-61.50608825683594
+-47.155731201171875,-57.985450744628906
+-47.11928176879883,-61.485260009765625
+-45.15584182739258,-57.964622497558594
+-45.11939239501953,-61.46443176269531
+-43.155948638916016,-57.943790435791016
+-43.11949920654297,-61.443599700927734
+-41.15605545043945,-57.9229621887207
+-41.119606018066406,-61.42277145385742
+-39.15616226196289,-57.90213394165039
+-39.119712829589844,-61.40194320678711
+-37.156272888183594,-57.88130187988281
+-37.11982345581055,-61.38111114501953
+-35.1563835144043,-57.8604736328125
+-35.11993408203125,-61.36028289794922
+-33.156490325927734,-57.83964538574219
+-33.12004089355469,-61.339454650878906
+-31.156599044799805,-57.81881332397461
+-31.120147705078125,-61.31862258911133
+-29.156709671020508,-57.7979850769043
+-29.120258331298828,-61.297794342041016
+83.04327392578125,24.91476058959961
+85.04326629638672,24.920316696166992
+87.04325866699219,24.925872802734375
+89.04325103759766,24.93143081665039
+91.04324340820312,24.936986923217773
+93.22521209716797,24.87339210510254
+95.5011215209961,24.424331665039062
+97.65592193603516,23.565095901489258
+99.61637115478516,22.324880599975586
+101.3158187866211,20.745853424072266
+102.69650268554688,18.881675720214844
+103.71170043945312,16.950847625732422
+104.54739379882812,14.98498821258545
+105.22718048095703,12.959928512573242
+105.7469253540039,10.888010025024414
+106.10345458984375,8.781859397888184
+106.29459381103516,6.65431547164917
+106.33491516113281,4.578386306762695
+106.34855651855469,2.578432559967041
+106.36219787597656,0.5784792304039001
+106.3758316040039,-1.4213203191757202
+106.38947296142578,-3.421273708343506
+-45.18675994873047,42.54542922973633
+-45.192386627197266,40.54543685913086
+-45.19801712036133,38.54544448852539
+-45.25642776489258,36.431758880615234
+-45.4990348815918,34.29103088378906
+-45.93022155761719,32.1801872253418
+-46.54659652709961,30.11580467224121
+-47.34332275390625,28.11410140991211
+-48.31414031982422,26.1907958984375
+-49.45142364501953,24.36099624633789
+-50.76707458496094,22.622722625732422
+-52.311439514160156,21.023685455322266
+-54.047752380371094,19.63545036315918
+-55.94745635986328,18.480846405029297
+-57.979305267333984,17.578861236572266
+-60.10987854003906,16.944332122802734
+-62.304141998291016,16.58769416809082
+-64.46632385253906,16.504871368408203
+-66.46631622314453,16.499313354492188
+109.50276184082031,53.29315185546875
+106.00284576416016,53.269283294677734
+102.50292205810547,53.24541091918945
+99.00300598144531,53.22154235839844
+109.51640319824219,51.29319763183594
+106.01648712158203,51.26932907104492
+102.51656341552734,51.24545669555664
+99.01664733886719,51.221588134765625
+109.53004455566406,49.293243408203125
+106.0301284790039,49.26937484741211
+102.53020477294922,49.24550247192383
+99.03028869628906,49.22163391113281
+109.5436782836914,47.29329299926758
+106.04376220703125,47.26942443847656
+102.54383850097656,47.24555206298828
+99.0439224243164,47.221683502197266
+109.55731964111328,45.293338775634766
+106.05740356445312,45.26947021484375
+102.55747985839844,45.24559783935547
+99.05756378173828,45.22172927856445
+109.57096099853516,43.29338455200195
+106.071044921875,43.26951599121094
+102.57112121582031,43.245643615722656
+99.07120513916016,43.22177505493164
+27.14229393005371,66.28325653076172
+29.14229393005371,66.28581237792969
+31.023746490478516,66.26502990722656
+32.707393646240234,66.00928497314453
+34.32426071166992,65.47466278076172
+35.8285026550293,64.67633819580078
+37.17747116088867,63.636940002441406
+38.338077545166016,62.382720947265625
+39.280731201171875,60.95339584350586
+39.97834396362305,59.38977813720703
+40.41234588623047,57.7335090637207
+40.5711669921875,56.02871322631836
+40.548606872558594,54.07141876220703
+-41.68677520751953,42.535579681396484
+-41.688926696777344,40.57392883300781
+-41.542572021484375,38.80292892456055
+-41.17356491088867,37.06462860107422
+-40.587806701660156,35.386905670166016
+-39.794700622558594,33.796669006347656
+-38.80697250366211,32.319427490234375
+-37.65940475463867,31.02106475830078
+-36.33360290527344,29.9392147064209
+-34.8490104675293,29.088247299194336
+-33.24543762207031,28.490991592407227
+-31.565889358520508,28.163454055786133
+-29.766407012939453,28.101327896118164
+-67.08174133300781,-65.19336700439453
+-67.0452880859375,-68.69317626953125
+-65.08184814453125,-65.17253875732422
+-65.04539489746094,-68.67234802246094
+-63.08196258544922,-65.1517105102539
+-63.04551315307617,-68.65151977539062
+-61.082069396972656,-65.1308822631836
+-61.04561996459961,-68.63069152832031
+-59.082176208496094,-65.11004638671875
+-59.04572677612305,-68.60985565185547
+-57.0822868347168,-65.08921813964844
+-57.04583740234375,-68.58902740478516
+-55.082393646240234,-65.06838989257812
+-55.04594421386719,-68.56819915771484
+-53.08250427246094,-65.04756164550781
+-53.04605484008789,-68.54737091064453
+-51.082611083984375,-65.0267333984375
+-51.04616165161133,-68.52654266357422
+-49.08271789550781,-65.00589752197266
+-49.046268463134766,-68.50570678710938
+-47.082828521728516,-64.98506927490234
+-47.04637908935547,-68.48487854003906
+-45.08293914794922,-64.96424102783203
+-45.04648971557617,-68.46405029296875
+-43.083045959472656,-64.94341278076172
+-43.04659652709961,-68.44322204589844
+-41.083152770996094,-64.9225845336914
+-41.04670333862305,-68.42239379882812
+-39.08325958251953,-64.9017562866211
+-39.046810150146484,-68.40156555175781
+-37.083370208740234,-64.88092041015625
+-37.04692077636719,-68.38072967529297
+-35.08348083496094,-64.86009216308594
+-35.04703140258789,-68.35990142822266
+-33.083587646484375,-64.83926391601562
+-33.04713821411133,-68.33907318115234
+-31.083694458007812,-64.81843566894531
+-31.047243118286133,-68.31824493408203
+-29.083805084228516,-64.797607421875
+-29.047353744506836,-68.29741668701172
+109.89640045166016,-4.425507068634033
+106.396484375,-4.449376106262207
+102.89656066894531,-4.473245620727539
+99.39664459228516,-4.497114658355713
+109.91004180908203,-6.4254608154296875
+106.41012573242188,-6.449329853057861
+102.91020202636719,-6.473199367523193
+99.41028594970703,-6.497068405151367
+109.9236831665039,-8.425414085388184
+106.42376708984375,-8.449283599853516
+102.92384338378906,-8.473152160644531
+99.4239273071289,-8.497021675109863
+-48.6427001953125,-43.3538932800293
+-48.62760925292969,-45.35411834716797
+-48.612518310546875,-47.354061126708984
+-48.481910705566406,-49.532466888427734
+-48.12403869628906,-51.68540573120117
+-47.54281997680664,-53.789066314697266
+-46.7446403503418,-55.820350646972656
+-45.73826599121094,-57.7569465637207
+-44.52067565917969,-59.59299087524414
+-42.97726058959961,-61.29964828491211
+-41.16213607788086,-62.71391296386719
+-39.12992477416992,-63.79323196411133
+-36.9417724609375,-64.505126953125
+-34.663516998291016,-64.82818603515625
+-32.55117416381836,-64.8337173461914
+-30.55128288269043,-64.8128890991211
+-28.5513916015625,-64.79206085205078
+58.05227279663086,66.3227767944336
+56.05227279663086,66.32022094726562
+54.052276611328125,66.31766510009766
+52.052276611328125,66.31510162353516
+50.05228042602539,66.31254577636719
+48.05228042602539,66.30998992919922
+46.05228042602539,66.30743408203125
+44.052284240722656,66.30487823486328
+42.05228805541992,66.30232238769531
+40.05228805541992,66.29975891113281
+38.05228805541992,66.29720306396484
+36.05228805541992,66.29464721679688
+34.05229187011719,66.2920913696289
+32.05229568481445,66.28953552246094
+30.05229377746582,66.28697204589844
+28.052295684814453,66.28441619873047
+-0.14773565530776978,130.2100830078125
+-0.16924521327018738,133.71002197265625
+-0.19075477123260498,137.2099609375
+-0.21226432919502258,140.70989990234375
+-2.147697925567627,130.19778442382812
+-2.1692073345184326,133.69772338867188
+-2.1907169818878174,137.19766235351562
+-2.212226390838623,140.69760131835938
+-4.147660255432129,130.18551635742188
+-4.169169902801514,133.68544006347656
+-4.19067907333374,137.1853790283203
+-4.212188720703125,140.685302734375
+-6.147622108459473,130.1732177734375
+-6.169131755828857,133.6731414794922
+-6.190640926361084,137.17308044433594
+-6.212150573730469,140.67300415039062
+-8.147583961486816,130.16091918945312
+-8.16909408569336,133.66085815429688
+-8.190603256225586,137.16079711914062
+-8.212113380432129,140.66073608398438
+-10.147546768188477,130.14862060546875
+-10.16905689239502,133.6485595703125
+-10.190566062927246,137.14849853515625
+-10.212076187133789,140.6484375
+-12.14750862121582,130.1363525390625
+-12.169018745422363,133.6362762451172
+-12.19052791595459,137.13621520996094
+-12.212038040161133,140.63613891601562
+-14.14747142791748,130.12405395507812
+-14.168981552124023,133.6239776611328
+-14.19049072265625,137.12391662597656
+-14.212000846862793,140.62384033203125
+-16.147432327270508,130.11175537109375
+-16.168941497802734,133.6116943359375
+-16.190452575683594,137.11163330078125
+-16.21196174621582,140.611572265625
+-18.147396087646484,130.09945678710938
+-18.16890525817871,133.59939575195312
+-18.19041633605957,137.09933471679688
+-18.211925506591797,140.59927368164062
+-20.147357940673828,130.08718872070312
+-20.168867111206055,133.5871124267578
+-20.190378189086914,137.08705139160156
+-20.21188735961914,140.58697509765625
+-22.147319793701172,130.07489013671875
+-22.1688289642334,133.57481384277344
+-22.190340042114258,137.0747528076172
+-22.211849212646484,140.57467651367188
+-24.147281646728516,130.06259155273438
+-24.168790817260742,133.56253051757812
+-24.1903018951416,137.06246948242188
+-24.211811065673828,140.56240844726562
+-26.147245407104492,130.05029296875
+-26.16875457763672,133.55023193359375
+-26.190265655517578,137.0501708984375
+-26.211774826049805,140.55010986328125
+-28.147207260131836,130.03802490234375
+-28.168716430664062,133.53794860839844
+-28.190227508544922,137.0378875732422
+-28.21173667907715,140.53781127929688
+-70.48992156982422,128.90286254882812
+-71.26968383789062,132.3148956298828
+-72.0494384765625,135.72694396972656
+-72.8292007446289,139.13897705078125
+-72.18624114990234,128.47250366210938
+-73.12738800048828,131.84359741210938
+-74.06853485107422,135.21469116210938
+-75.00968170166016,138.58578491210938
+-73.86016845703125,127.96195220947266
+-74.96057891845703,131.2844696044922
+-76.06098175048828,134.6069793701172
+-77.16139221191406,137.92950439453125
+-75.5079345703125,127.37236785888672
+-76.76510620117188,130.6387939453125
+-78.02227783203125,133.90521240234375
+-79.27944946289062,137.171630859375
+-77.12578582763672,126.70508575439453
+-78.53688049316406,129.90802001953125
+-79.94798278808594,133.1109619140625
+-81.35907745361328,136.31390380859375
+-78.71007537841797,125.96162414550781
+-80.27189636230469,129.0938262939453
+-81.83372497558594,132.2260284423828
+-83.39554595947266,135.3582305908203
+-80.25720977783203,125.14366149902344
+-81.96623229980469,128.1980438232422
+-83.67524719238281,131.25242614746094
+-85.38426971435547,134.3068084716797
+-81.7636947631836,124.2530288696289
+-83.61604309082031,127.2226791381836
+-85.4683837890625,130.19232177734375
+-87.32073211669922,133.16197204589844
+-83.22611999511719,123.29176330566406
+-85.21759796142578,126.16996002197266
+-87.2090835571289,129.04815673828125
+-89.2005615234375,131.9263458251953
+-84.64117431640625,122.26204681396484
+-86.76728057861328,125.04227447509766
+-88.89339447021484,127.82250213623047
+-91.01950073242188,130.60272216796875
+-86.00565338134766,121.16619110107422
+-88.26158142089844,123.84215545654297
+-90.51750183105469,126.51811981201172
+-92.77342987060547,129.194091796875
+-87.31647491455078,120.00668334960938
+-89.69711303710938,122.57233428955078
+-92.0777587890625,125.13797760009766
+-94.4583969116211,127.70362854003906
+-88.57066345214844,118.78614044189453
+-91.07062530517578,121.23567199707031
+-93.57059478759766,123.68519592285156
+-96.070556640625,126.13472747802734
+-89.76539611816406,117.50733947753906
+-92.37902069091797,119.83519744873047
+-94.9926528930664,122.1630630493164
+-97.60627746582031,124.49092102050781
+-90.89795684814453,116.17316436767578
+-93.61933898925781,118.37409210205078
+-96.34071350097656,120.57501983642578
+-99.06209564208984,122.77594757080078
+-91.96578216552734,114.78662872314453
+-94.78875732421875,116.85564422607422
+-97.61172485351562,118.9246597290039
+-100.43470001220703,120.9936752319336
+-92.97467041015625,113.33920288085938
+-95.88758087158203,115.27954864501953
+-98.80049896240234,117.21988677978516
+-101.71340942382812,119.16023254394531
+-93.98038482666016,111.78266143798828
+-96.94639587402344,113.64083099365234
+-99.91239929199219,115.4990005493164
+-102.87841033935547,117.35717010498047
+-94.94220733642578,110.19862365722656
+-97.95899200439453,111.9731674194336
+-100.97577667236328,113.7477035522461
+-103.99256134033203,115.52224731445312
+-95.859375,108.58831024169922
+-98.9245834350586,110.27783966064453
+-101.98978424072266,111.96736907958984
+-105.05499267578125,113.65689849853516
+-96.7311782836914,106.9530029296875
+-99.8424072265625,108.55620574951172
+-102.95364379882812,110.1594009399414
+-106.06487274169922,111.76260375976562
+-97.55693054199219,105.29396057128906
+-100.71175384521484,106.80957794189453
+-103.86658477783203,108.32518768310547
+-107.02140808105469,109.84080505371094
+-98.33599853515625,103.61248779296875
+-101.53195190429688,105.0393295288086
+-104.7279052734375,106.46617889404297
+-107.92385864257812,107.89302062988281
+-99.06775665283203,101.90989685058594
+-102.30233764648438,103.24685668945312
+-105.53692626953125,104.58381652832031
+-108.7715072631836,105.9207763671875
+-99.75164031982422,100.1875228881836
+-103.02233123779297,101.43354797363281
+-106.29302215576172,102.67958068847656
+-109.56371307373047,103.92560577392578
+-100.38712310791016,98.44670867919922
+-103.69136047363281,99.600830078125
+-106.99560546875,100.75495910644531
+-110.29984283447266,101.9090805053711
+-100.97370147705078,96.68880462646484
+-104.30890655517578,97.7501220703125
+-107.64411163330078,98.81144714355469
+-110.97931671142578,99.87276458740234
+-101.51091766357422,94.91519927978516
+-104.87448120117188,95.88288879394531
+-108.23805236816406,96.85057067871094
+-111.60161590576172,97.8182601928711
+-101.99834442138672,93.12726593017578
+-105.38764190673828,94.00056457519531
+-108.77693939208984,94.87385559082031
+-112.1662368774414,95.74715423583984
+-102.43561553955078,91.32640075683594
+-105.8479995727539,92.10462951660156
+-109.26038360595703,92.88285827636719
+-112.67276763916016,93.66108703613281
+-102.82238006591797,89.51403045654297
+-106.25518035888672,90.19657897949219
+-109.68798065185547,90.87911987304688
+-113.12078094482422,91.5616683959961
+-103.1583251953125,87.69155883789062
+-106.60887145996094,88.27788543701172
+-110.05940246582031,88.86421966552734
+-113.50994873046875,89.45054626464844
+-103.44322204589844,85.86040496826172
+-106.90879821777344,86.35006713867188
+-110.37437438964844,86.8397216796875
+-113.83995056152344,87.32938385009766
+-103.67681121826172,84.02200317382812
+-107.15472412109375,84.41460418701172
+-110.63262939453125,84.80721282958984
+-114.11054229736328,85.19981384277344
+-103.85893249511719,82.17778778076172
+-107.3464584350586,82.47303009033203
+-110.83397674560547,82.76827239990234
+-114.32150268554688,83.06351470947266
+-103.98943328857422,80.32920837402344
+-107.48384857177734,80.52686309814453
+-110.97826385498047,80.7245101928711
+-114.4726791381836,80.92216491699219
+-104.0682144165039,78.47769927978516
+-107.56678771972656,78.57760620117188
+-111.06536865234375,78.67750549316406
+-114.5639419555664,78.77741241455078
+-104.09522247314453,76.62471771240234
+-107.59522247314453,76.62680053710938
+-111.09522247314453,76.62887573242188
+-114.59522247314453,76.6309585571289
+-104.0781021118164,74.68677520751953
+-107.577880859375,74.64754486083984
+-111.07766723632812,74.60831451416016
+-114.57744598388672,74.56908416748047
+-104.0556869506836,72.68689727783203
+-107.55546569824219,72.64766693115234
+-111.05525207519531,72.60843658447266
+-114.5550308227539,72.56920623779297
+-104.03327178955078,70.68702697753906
+-107.53305053710938,70.64779663085938
+-111.0328369140625,70.60856628417969
+-114.5326156616211,70.5693359375
+-104.01084899902344,68.68714904785156
+-107.51062774658203,68.64791870117188
+-111.01041412353516,68.60868835449219
+-114.51019287109375,68.5694580078125
+-103.98843383789062,66.6872787475586
+-107.48821258544922,66.6480484008789
+-110.98799896240234,66.60881805419922
+-114.48777770996094,66.56958770751953
+-103.96601867675781,64.6874008178711
+-107.4657974243164,64.6481704711914
+-110.96558380126953,64.60894012451172
+-114.46536254882812,64.56970977783203
+-103.94359588623047,62.687530517578125
+-107.44337463378906,62.64830017089844
+-110.94316101074219,62.60906982421875
+-114.44293975830078,62.56983947753906
+-103.92118072509766,60.687652587890625
+-107.42095947265625,60.64842224121094
+-110.92074584960938,60.60919189453125
+-114.42052459716797,60.56996154785156
+-103.89876556396484,58.687782287597656
+-107.39854431152344,58.64855194091797
+-110.89833068847656,58.60932159423828
+-114.39810943603516,58.570091247558594
+-103.8763427734375,56.687904357910156
+-107.3761215209961,56.64867401123047
+-110.87590789794922,56.60944366455078
+-114.37568664550781,56.570213317871094
+-103.85392761230469,54.68803405761719
+-107.35370635986328,54.6488037109375
+-110.8534927368164,54.60957336425781
+-114.353271484375,54.570343017578125
+-103.83151245117188,52.68815612792969
+-107.33129119873047,52.64892578125
+-110.8310775756836,52.60969543457031
+-114.33085632324219,52.570465087890625
+-103.80908966064453,50.68828201293945
+-107.30886840820312,50.649051666259766
+-110.80865478515625,50.60982131958008
+-114.30843353271484,50.57059097290039
+-103.78667449951172,48.68840789794922
+-107.28645324707031,48.64917755126953
+-110.78623962402344,48.609947204589844
+-114.28601837158203,48.570716857910156
+-103.7642593383789,46.688533782958984
+-107.2640380859375,46.6493034362793
+-110.76382446289062,46.61007308959961
+-114.26360321044922,46.57084274291992
+-103.74183654785156,44.68865966796875
+-107.24161529541016,44.64942932128906
+-110.74140167236328,44.610198974609375
+-114.24118041992188,44.57096862792969
+-103.21614074707031,-2.2083921432495117
+-106.7159194946289,-2.2476232051849365
+-110.21570587158203,-2.2868540287017822
+-113.71548461914062,-2.326085090637207
+-103.1937255859375,-4.208266258239746
+-106.6935043334961,-4.247497081756592
+-110.19329071044922,-4.286728382110596
+-113.69306945800781,-4.325959205627441
+-103.17130279541016,-6.208140850067139
+-106.67108154296875,-6.247371673583984
+-110.17086791992188,-6.286602973937988
+-113.67064666748047,-6.325833797454834
+-103.14888763427734,-8.208015441894531
+-106.64866638183594,-8.247246742248535
+-110.14845275878906,-8.286477088928223
+-113.64823150634766,-8.325708389282227
+-103.12647247314453,-10.207889556884766
+-106.62625122070312,-10.24712085723877
+-110.12603759765625,-10.286351203918457
+-113.62581634521484,-10.325582504272461
+-103.10404968261719,-12.207763671875
+-106.60382843017578,-12.246994972229004
+-110.1036148071289,-12.286225318908691
+-113.6033935546875,-12.325456619262695
+-103.08163452148438,-14.20763874053955
+-106.58141326904297,-14.246870040893555
+-110.0811996459961,-14.286100387573242
+-113.58097839355469,-14.325331687927246
+-103.05921936035156,-16.20751190185547
+-106.55899810791016,-16.24674415588379
+-110.05878448486328,-16.285974502563477
+-113.55856323242188,-16.325206756591797
+-103.03679656982422,-18.207386016845703
+-106.53657531738281,-18.246618270874023
+-110.03636169433594,-18.28584861755371
+-113.53614044189453,-18.32508087158203
+-103.0143814086914,-20.207260131835938
+-106.51416015625,-20.246492385864258
+-110.01394653320312,-20.285722732543945
+-113.51372528076172,-20.324954986572266
+-102.99175262451172,-22.180795669555664
+-106.49128723144531,-22.23758316040039
+-109.99082946777344,-22.294368743896484
+-113.49036407470703,-22.35115623474121
+-102.92448425292969,-23.950885772705078
+-106.4182357788086,-24.15987777709961
+-109.91199493408203,-24.36886978149414
+-113.40574645996094,-24.577861785888672
+-102.78025817871094,-25.71637535095215
+-106.26161193847656,-26.077177047729492
+-109.74296569824219,-26.437978744506836
+-113.22431945800781,-26.79878044128418
+-102.55935668945312,-27.473915100097656
+-106.02172088623047,-27.985843658447266
+-109.48407745361328,-28.497772216796875
+-112.94644165039062,-29.009700775146484
+-102.26219940185547,-29.220182418823242
+-105.69900512695312,-29.882266998291016
+-109.13581848144531,-30.544353485107422
+-112.57262420654297,-31.206438064575195
+-101.88935089111328,-30.951866149902344
+-105.29409790039062,-31.762855529785156
+-108.69883728027344,-32.57384490966797
+-112.10358428955078,-33.38483428955078
+-101.4415054321289,-32.66568374633789
+-104.8077392578125,-33.62403869628906
+-108.17398071289062,-34.5823974609375
+-111.54021453857422,-35.54075241088867
+-100.91951751708984,-34.358402252197266
+-104.24087524414062,-35.462310791015625
+-107.56222534179688,-36.56621551513672
+-110.88358306884766,-37.67012405395508
+-100.32437896728516,-36.026798248291016
+-103.59455871582031,-37.274169921875
+-106.86473083496094,-38.52153778076172
+-110.1349105834961,-39.7689094543457
+-99.65721893310547,-37.667724609375
+-102.87002563476562,-39.05619430541992
+-106.08283996582031,-40.44466018676758
+-109.29564666748047,-41.8331298828125
+-98.9192886352539,-39.278072357177734
+-102.06864929199219,-40.80501174926758
+-105.21800231933594,-42.33195114135742
+-108.36736297607422,-43.858890533447266
+-98.11199951171875,-40.85478591918945
+-101.19194030761719,-42.517303466796875
+-104.27188110351562,-44.17981719970703
+-107.35182189941406,-45.84233474731445
+-97.23687744140625,-42.3948860168457
+-100.24156951904297,-44.1898307800293
+-103.24625396728516,-45.98477554321289
+-106.25094604492188,-47.779720306396484
+-96.29557037353516,-43.89544677734375
+-99.21932220458984,-45.81942367553711
+-102.14307403564453,-47.7433967590332
+-105.06682586669922,-49.66737365722656
+-95.28986358642578,-45.3536376953125
+-98.12713623046875,-47.40299606323242
+-100.96441650390625,-49.45235824584961
+-103.80168914794922,-51.50171661376953
+-94.22167205810547,-46.766685485839844
+-96.96709442138672,-48.93754959106445
+-99.71251678466797,-51.10841751098633
+-102.45793914794922,-53.27928161621094
+-93.1077880859375,-48.112548828125
+-95.74552917480469,-50.413055419921875
+-98.38327026367188,-52.71356201171875
+-101.02101135253906,-55.014068603515625
+-91.95550537109375,-49.359474182128906
+-94.4566421508789,-51.807804107666016
+-96.9577865600586,-54.25613021850586
+-99.45892333984375,-56.70446014404297
+-90.73345184326172,-50.5380973815918
+-93.0897216796875,-53.12615203857422
+-95.44598388671875,-55.714202880859375
+-97.80225372314453,-58.3022575378418
+-89.44567108154297,-51.64453125
+-91.6492691040039,-54.36375045776367
+-93.85286712646484,-57.08296585083008
+-96.05646514892578,-59.80218505859375
+-88.0964126586914,-52.675106048583984
+-90.14006042480469,-55.51649475097656
+-92.1837158203125,-58.357887268066406
+-94.22736358642578,-61.199275970458984
+-86.69014739990234,-53.62641525268555
+-88.56708526611328,-56.58058166503906
+-90.44402313232422,-59.534751892089844
+-92.32096099853516,-62.48891830444336
+-85.23152160644531,-54.49531555175781
+-86.93553924560547,-57.552490234375
+-88.63956451416016,-60.60966491699219
+-90.34358215332031,-63.666839599609375
+-83.7253646850586,-55.278934478759766
+-85.2508316040039,-58.42900848388672
+-86.77629852294922,-61.579078674316406
+-88.30176544189453,-64.7291488647461
+-82.1766586303711,-55.97468185424805
+-83.51852416992188,-59.20723342895508
+-84.86039733886719,-62.43978500366211
+-86.20226287841797,-65.67233276367188
+-80.59050750732422,-56.58024978637695
+-81.74433898925781,-59.88459014892578
+-82.89817810058594,-63.188934326171875
+-84.05200958251953,-66.49327087402344
+-78.97217559814453,-57.09364318847656
+-79.93415832519531,-60.45884704589844
+-80.89614868164062,-63.82405090332031
+-81.8581314086914,-67.18925476074219
+-77.3270034790039,-57.51316452026367
+-78.09395599365234,-60.9281005859375
+-78.86090850830078,-64.34303283691406
+-79.62786102294922,-67.75797271728516
+-75.66044616699219,-57.83741760253906
+-76.22982788085938,-61.290794372558594
+-76.79920959472656,-64.74417114257812
+-77.36859130859375,-68.19754791259766
+-73.9780044555664,-58.065338134765625
+-74.34793090820312,-61.54573440551758
+-74.71786499023438,-65.02613067626953
+-75.0877914428711,-68.50652313232422
+-72.28523254394531,-58.1961669921875
+-72.4544906616211,-61.692073822021484
+-72.62374114990234,-65.18798065185547
+-72.79299926757812,-68.68388366699219
+-70.5877456665039,-58.22947692871094
+-70.55577087402344,-61.729331970214844
+-70.52378845214844,-65.22918701171875
+-70.49181365966797,-68.72904205322266
+-68.59456634521484,-58.208744049072266
+-68.55811309814453,-61.708553314208984
+-68.52165985107422,-65.20836639404297
+-68.4852066040039,-68.70817565917969
+-28.517202377319336,130.03573608398438
+-28.538711547851562,133.53567504882812
+-30.51716423034668,130.02346801757812
+-30.538673400878906,133.5233917236328
+-32.51712417602539,130.01116943359375
+-32.53863525390625,133.51109313964844
+-34.517086029052734,129.99887084960938
+-34.538597106933594,133.49880981445312
+-36.51704788208008,129.986572265625
+-36.53855895996094,133.48651123046875
+-38.51700973510742,129.97427368164062
+-38.53852081298828,133.47421264648438
+-40.516971588134766,129.96200561523438
+-40.538482666015625,133.46192932128906
+-42.51693344116211,129.94970703125
+-42.53844451904297,133.4496307373047
+-44.51689529418945,129.93740844726562
+-44.53840637207031,133.43734741210938
+-46.5168571472168,129.92510986328125
+-46.538368225097656,133.425048828125
+-48.516822814941406,129.912841796875
+-48.538333892822266,133.4127655029297
+-50.51678466796875,129.90054321289062
+-50.53829574584961,133.4004669189453
+-52.516746520996094,129.88824462890625
+-52.53825759887695,133.38818359375
+-54.51670837402344,129.87594604492188
+-54.5382194519043,133.37588500976562
+-56.51667022705078,129.86367797851562
+-56.53818130493164,133.3636016845703
+-58.516632080078125,129.85137939453125
+-58.538143157958984,133.35130310058594
+-60.51659393310547,129.83908081054688
+-60.53810501098633,133.33901977539062
+-62.51655960083008,129.8267822265625
+-62.53807067871094,133.32672119140625
+-64.26628112792969,129.77456665039062
+-64.45392608642578,133.26953125
+-66.01110076904297,129.63919067382812
+-66.36474609375,133.12127685546875
+-67.74750518798828,129.42098999023438
+-68.26634979248047,132.88232421875
+-69.47157287597656,129.12046813964844
+-70.1544418334961,132.55320739746094
+-27.836780548095703,-57.784236907958984
+-27.800329208374023,-61.2840461730957
+-27.76387596130371,-64.78385925292969
+-27.72742462158203,-68.2836685180664
+-25.836889266967773,-57.76340866088867
+-25.800437927246094,-61.26321792602539
+-25.76398468017578,-64.76303100585938
+-25.7275333404541,-68.2628402709961
+-23.836997985839844,-57.742576599121094
+-23.800546646118164,-61.24238586425781
+-23.76409339904785,-64.74219512939453
+-23.727642059326172,-68.24200439453125
+-21.837106704711914,-57.72174835205078
+-21.800655364990234,-61.2215576171875
+-21.764202117919922,-64.72136688232422
+-21.727750778198242,-68.22117614746094
+-19.83721351623535,-57.70092010498047
+-19.800762176513672,-61.20072937011719
+-19.76430892944336,-64.7005386352539
+-19.72785758972168,-68.20034790039062
+-17.837324142456055,-57.68008804321289
+-17.800872802734375,-61.17989730834961
+-17.764419555664062,-64.6797103881836
+-17.727968215942383,-68.17951965332031
+-15.837430953979492,-57.65925979614258
+-15.800978660583496,-61.1590690612793
+-15.764527320861816,-64.65888214111328
+-15.72807502746582,-68.15869140625
+-13.837539672851562,-57.638427734375
+-13.801087379455566,-61.13823699951172
+-13.764636039733887,-64.63804626464844
+-13.72818374633789,-68.13785552978516
+-11.837648391723633,-57.61759948730469
+-11.801196098327637,-61.117408752441406
+-11.764744758605957,-64.61721801757812
+-11.728292465209961,-68.11702728271484
+-9.837757110595703,-57.596771240234375
+-9.801304817199707,-61.096580505371094
+-9.764853477478027,-64.59638977050781
+-9.728401184082031,-68.09619903564453
+-7.837865829467773,-57.5759391784668
+-7.8014140129089355,-61.075748443603516
+-7.7649617195129395,-64.5755615234375
+-7.728509902954102,-68.07537078857422
+-5.837974548339844,-57.555110931396484
+-5.801522731781006,-61.0549201965332
+-5.76507043838501,-64.55473327636719
+-5.728618621826172,-68.0545425415039
+-67.15464782714844,-58.19374465942383
+-65.15410614013672,-58.172908782958984
+-63.24685287475586,-58.13529586791992
+-61.503944396972656,-57.9042854309082
+-59.809104919433594,-57.43671798706055
+-58.19428634643555,-56.74140167236328
+-56.6899299621582,-55.83144760131836
+-55.3316535949707,-54.729557037353516
+-54.19142150878906,-53.46065139770508
+-53.27783966064453,-52.019962310791016
+-52.61628723144531,-50.447509765625
+-52.225162506103516,-48.787017822265625
+-52.114803314208984,-47.06452560424805
+-52.1298942565918,-45.06428909301758
+-28.560218811035156,137.03561401367188
+-28.581727981567383,140.53555297851562
+-30.5601806640625,137.02333068847656
+-30.581689834594727,140.52325439453125
+-32.560142517089844,137.0110321044922
+-32.5816535949707,140.51095581054688
+-34.56010437011719,136.99874877929688
+-34.58161544799805,140.49868774414062
+-36.56006622314453,136.9864501953125
+-36.58157730102539,140.48638916015625
+-38.560028076171875,136.97415161132812
+-38.581539154052734,140.47409057617188
+-40.55998992919922,136.9618682861328
+-40.58150100708008,140.4617919921875
+-42.55995178222656,136.94956970214844
+-42.58146286010742,140.44949340820312
+-44.559913635253906,136.93728637695312
+-44.581424713134766,140.43722534179688
+-46.55987548828125,136.92498779296875
+-46.58138656616211,140.4249267578125
+-48.55984115600586,136.91270446777344
+-48.58135223388672,140.41262817382812
+-50.5598030090332,136.90040588378906
+-50.58131408691406,140.40032958984375
+-52.55976486206055,136.88812255859375
+-52.581275939941406,140.3880615234375
+-54.55972671508789,136.87582397460938
+-54.58123779296875,140.37576293945312
+-56.559688568115234,136.86354064941406
+-56.581199645996094,140.36346435546875
+-58.55965042114258,136.8512420654297
+-58.58116149902344,140.35116577148438
+-60.55961227416992,136.83895874023438
+-60.58112335205078,140.33889770507812
+-62.55957794189453,136.82666015625
+-62.58108901977539,140.32659912109375
+-64.64156341552734,136.76449584960938
+-64.82920837402344,140.25946044921875
+-66.7183837890625,136.60336303710938
+-67.07202911376953,140.08544921875
+-68.78519439697266,136.34365844726562
+-69.30403900146484,139.80499267578125
+-70.83731842041016,135.98594665527344
+-71.52018737792969,139.41868591308594
+-0.21226438879966736,140.70989990234375
+-0.19075478613376617,137.2099609375
+-0.16924519836902618,133.71002197265625
+-0.147735595703125,130.2100830078125
+1.7829740047454834,140.7223663330078
+1.8076318502426147,137.2224578857422
+1.8322898149490356,133.72254943847656
+1.856947660446167,130.22264099121094
+3.7618916034698486,140.74024963378906
+3.800549030303955,137.24046325683594
+3.8392062187194824,133.7406768798828
+3.877863645553589,130.2408905029297
+5.740721702575684,140.7660675048828
+5.793377876281738,137.26646423339844
+5.846034049987793,133.76686096191406
+5.898690223693848,130.2672576904297
+7.719432830810547,140.7998046875
+7.7860870361328125,137.30043029785156
+7.852741241455078,133.8010711669922
+7.919395446777344,130.30169677734375
+9.711109161376953,140.8401641845703
+9.783038139343262,137.34091186523438
+9.854968070983887,133.84164428710938
+9.926897048950195,130.34239196777344
+11.725129127502441,140.87965393066406
+11.787455558776855,137.38021850585938
+11.84978199005127,133.88076782226562
+11.912108421325684,130.38133239746094
+13.745875358581543,140.91160583496094
+13.79420280456543,137.4119415283203
+13.842531204223633,133.9122772216797
+13.89085865020752,130.41261291503906
+15.766733169555664,140.9354705810547
+15.80106258392334,137.43563842773438
+15.8353910446167,133.93582153320312
+15.869720458984375,130.4359893798828
+17.787670135498047,140.95126342773438
+17.808000564575195,137.45132446289062
+17.82832908630371,133.95138549804688
+17.84865951538086,130.45144653320312
+44.02894973754883,52.548702239990234
+40.52924728393555,52.59458541870117
+44.00273132324219,50.54887390136719
+40.503028869628906,50.594757080078125
+43.97651672363281,48.54904556274414
+40.47681427001953,48.59492874145508
+43.95029830932617,46.549217224121094
+40.45059585571289,46.59510040283203
+43.92407989501953,44.54938888549805
+40.42437744140625,44.595272064208984
+43.89786148071289,42.549560546875
+40.39815902709961,42.59544372558594
+109.97942352294922,-22.602590560913086
+106.47980499267578,-22.654197692871094
+102.98018646240234,-22.70580291748047
+99.4805679321289,-22.757410049438477
+109.9553451538086,-24.868633270263672
+106.45761108398438,-24.742660522460938
+102.95988464355469,-24.616687774658203
+99.46215057373047,-24.49071502685547
+109.81635284423828,-27.130535125732422
+106.32951354980469,-26.827306747436523
+102.84266662597656,-26.524080276489258
+99.35582733154297,-26.22085189819336
+109.56280517578125,-29.382476806640625
+106.09583282470703,-28.902774810791016
+102.62886810302734,-28.423072814941406
+99.16189575195312,-27.943370819091797
+109.19536590576172,-31.6186580657959
+105.75718688964844,-30.963716506958008
+102.31901550292969,-30.308774948120117
+98.8808364868164,-29.653833389282227
+108.71495819091797,-33.83332061767578
+105.3144302368164,-33.00482940673828
+101.91390228271484,-32.17633056640625
+98.51337432861328,-31.347837448120117
+108.12284088134766,-36.02077102661133
+104.76871490478516,-35.02085494995117
+101.41458892822266,-34.020938873291016
+98.06046295166016,-33.02102279663086
+107.4205322265625,-38.17536926269531
+104.1214370727539,-37.00660705566406
+100.82234954833984,-35.83784484863281
+97.52325439453125,-34.66908264160156
+106.6098403930664,-40.29156494140625
+103.37428283691406,-38.956966400146484
+100.13871765136719,-37.622371673583984
+96.90316009521484,-36.28777313232422
+105.6928482055664,-42.36391830444336
+102.52914428710938,-40.866920471191406
+99.36544799804688,-39.36991882324219
+96.20174407958984,-37.872920989990234
+104.67192077636719,-44.387088775634766
+101.58822631835938,-42.731544494628906
+98.50453186035156,-41.07599639892578
+95.42083740234375,-39.42045211791992
+103.5496826171875,-46.355873107910156
+100.5539321899414,-44.546043395996094
+97.55818939208984,-42.73621368408203
+94.56243896484375,-40.92638397216797
+102.32901763916016,-48.265201568603516
+99.42892456054688,-46.305747985839844
+96.52883911132812,-44.346290588378906
+93.62874603271484,-42.386837005615234
+101.01309204101562,-50.11015319824219
+98.21612548828125,-48.0061149597168
+95.41915893554688,-45.90208053588867
+92.6221923828125,-43.79804229736328
+99.60527038574219,-51.88597869873047
+96.91862487792969,-49.64278030395508
+94.23197937011719,-47.39957809448242
+91.54533386230469,-45.15637969970703
+98.10918426513672,-53.58811569213867
+95.53977966308594,-51.211524963378906
+92.97038269042969,-48.834938049316406
+90.4009780883789,-46.45834732055664
+96.5286865234375,-55.21216583251953
+94.08313751220703,-52.708309173583984
+91.6375961303711,-50.20444869995117
+89.19204711914062,-47.700592041015625
+94.86785125732422,-56.753963470458984
+92.55245971679688,-54.12928009033203
+90.237060546875,-51.504600524902344
+87.92166900634766,-48.87991714477539
+93.13094329833984,-58.20953369140625
+90.95166015625,-55.47078323364258
+88.77238464355469,-52.73203659057617
+86.59310150146484,-49.9932861328125
+91.32244110107422,-59.57512283325195
+89.28488159179688,-56.7293586730957
+87.24732971191406,-53.88359451293945
+85.20977020263672,-51.0378303527832
+89.44699096679688,-60.84722137451172
+87.55640411376953,-57.90176773071289
+85.66582489013672,-54.95631790161133
+83.77523803710938,-52.0108642578125
+87.50944519042969,-62.022552490234375
+85.77069854736328,-58.9849967956543
+84.03194427490234,-55.94743728637695
+82.29319763183594,-52.909881591796875
+85.51476287841797,-63.09809875488281
+83.93232727050781,-59.976253509521484
+82.34989929199219,-56.85441207885742
+80.76746368408203,-53.732566833496094
+83.46810150146484,-64.07107543945312
+82.04605102539062,-60.872982025146484
+80.62400817871094,-57.67489242553711
+79.20195770263672,-54.47679901123047
+81.37471008300781,-64.9389877319336
+80.11671447753906,-61.672882080078125
+78.85871887207031,-58.406776428222656
+77.60072326660156,-55.14067077636719
+79.24000549316406,-65.69960021972656
+78.14929962158203,-62.3738899230957
+77.05858612060547,-59.04817581176758
+75.96788024902344,-55.72246551513672
+77.0694580078125,-66.3509521484375
+76.14884185791016,-62.97419738769531
+75.22823333740234,-59.597442626953125
+74.3076171875,-56.22068786621094
+74.86866760253906,-66.89136505126953
+74.12052154541016,-63.47226333618164
+73.37236785888672,-60.053157806396484
+72.62422180175781,-56.63405227661133
+72.64330291748047,-67.3194580078125
+72.06954956054688,-63.86680603027344
+71.49578857421875,-60.414154052734375
+70.92203521728516,-56.96150207519531
+70.39908599853516,-67.63411712646484
+70.0011978149414,-64.15680694580078
+69.60330963134766,-60.67949676513672
+69.2054214477539,-57.202186584472656
+68.14179229736328,-67.83453369140625
+67.9207992553711,-64.34152221679688
+67.6998062133789,-60.84850311279297
+67.47881317138672,-57.35548782348633
+65.87725067138672,-67.92019653320312
+65.8337173461914,-64.42047119140625
+65.7901840209961,-60.920738220214844
+65.74665069580078,-57.42101287841797
+63.809814453125,-67.92304229736328
+63.81124496459961,-64.42304229736328
+63.81267166137695,-60.92304229736328
+63.81410217285156,-57.42304229736328
+61.809814453125,-67.92222595214844
+61.81124496459961,-64.42222595214844
+61.81267166137695,-60.92222595214844
+61.81410217285156,-57.42222595214844
+59.809814453125,-67.9214096069336
+59.81124496459961,-64.4214096069336
+59.81267166137695,-60.921409606933594
+59.81410217285156,-57.421409606933594
+57.809814453125,-67.92058563232422
+57.81124496459961,-64.42058563232422
+57.81267166137695,-60.920589447021484
+57.81410217285156,-57.420589447021484
+55.809814453125,-67.91976928710938
+55.81124496459961,-64.41976928710938
+55.81267166137695,-60.91977310180664
+55.81410217285156,-57.41977310180664
+53.809814453125,-67.91895294189453
+53.81124496459961,-64.41895294189453
+53.81267166137695,-60.9189567565918
+53.81410217285156,-57.4189567565918
+51.809814453125,-67.91813659667969
+51.81124496459961,-64.41813659667969
+51.81267166137695,-60.91814041137695
+51.81410217285156,-57.41814041137695
+49.809814453125,-67.91732025146484
+49.81124496459961,-64.41732025146484
+49.81267166137695,-60.91732406616211
+49.81410217285156,-57.41732406616211
+47.809814453125,-67.91650390625
+47.81124496459961,-64.41650390625
+47.81267166137695,-60.91650390625
+47.81410217285156,-57.41650390625
+45.809814453125,-67.91568756103516
+45.81124496459961,-64.41568756103516
+45.81267166137695,-60.915687561035156
+45.81410217285156,-57.415687561035156
+43.809814453125,-67.91487121582031
+43.81124496459961,-64.41487121582031
+43.81267166137695,-60.91487121582031
+43.81410217285156,-57.41487121582031
+41.809814453125,-67.91405487060547
+41.81124496459961,-64.41405487060547
+41.81267166137695,-60.91405487060547
+41.81410217285156,-57.41405487060547
+39.809814453125,-67.91323852539062
+39.81124496459961,-64.41323852539062
+39.81267166137695,-60.913238525390625
+39.81410217285156,-57.413238525390625
+37.809814453125,-67.91241455078125
+37.81124496459961,-64.41241455078125
+37.81267166137695,-60.912418365478516
+37.81410217285156,-57.412418365478516
+35.809814453125,-67.9115982055664
+35.81124496459961,-64.4115982055664
+35.81267166137695,-60.91160202026367
+35.81410217285156,-57.41160202026367
+33.809814453125,-67.91078186035156
+33.81124496459961,-64.41078186035156
+33.81267166137695,-60.91078567504883
+33.81410217285156,-57.41078567504883
+31.809812545776367,-67.90996551513672
+31.811243057250977,-64.40996551513672
+31.812673568725586,-60.909969329833984
+31.814104080200195,-57.409969329833984
+29.809812545776367,-67.90914916992188
+29.811243057250977,-64.40914916992188
+29.812673568725586,-60.90915298461914
+29.814104080200195,-57.40915298461914
+27.809812545776367,-67.90833282470703
+27.811243057250977,-64.40833282470703
+27.812673568725586,-60.90833282470703
+27.814104080200195,-57.40833282470703
+25.809816360473633,-67.90751647949219
+25.811246871948242,-64.40751647949219
+25.81267738342285,-60.90751647949219
+25.81410789489746,-57.40751647949219
+23.809816360473633,-67.90670013427734
+23.811246871948242,-64.40670013427734
+23.81267738342285,-60.906700134277344
+23.81410789489746,-57.406700134277344
+21.809816360473633,-67.9058837890625
+21.811246871948242,-64.4058837890625
+21.81267738342285,-60.9058837890625
+21.81410789489746,-57.4058837890625
+19.809816360473633,-67.90506744384766
+19.811246871948242,-64.40506744384766
+19.81267738342285,-60.905067443847656
+19.81410789489746,-57.405067443847656
+17.809816360473633,-67.90425109863281
+17.811246871948242,-64.40425109863281
+17.81267738342285,-60.90425109863281
+17.81410789489746,-57.40425109863281
+15.80981731414795,-67.90342712402344
+15.811246871948242,-64.40342712402344
+15.812677383422852,-60.9034309387207
+15.814106941223145,-57.4034309387207
+13.80981731414795,-67.9026107788086
+13.811246871948242,-64.4026107788086
+13.812677383422852,-60.90261459350586
+13.814106941223145,-57.40261459350586
+11.80981731414795,-67.90179443359375
+11.811246871948242,-64.40179443359375
+11.812677383422852,-60.901798248291016
+11.814106941223145,-57.401798248291016
+9.80981731414795,-67.9009780883789
+9.811246871948242,-64.4009780883789
+9.812677383422852,-60.90098190307617
+9.814106941223145,-57.40098190307617
+7.809817314147949,-67.90016174316406
+7.8112473487854,-64.40016174316406
+7.812676906585693,-60.90016555786133
+7.8141069412231445,-57.40016555786133
+-41.57395935058594,82.62542724609375
+-41.579586029052734,80.62543487548828
+-41.525909423828125,78.82386016845703
+-41.19239807128906,77.17517852783203
+-40.568546295166016,75.61306762695312
+-39.67458724975586,74.18819427490234
+-38.53953170776367,72.94681549072266
+-37.16744613647461,71.88114166259766
+-35.64335250854492,71.00440979003906
+-34.013580322265625,70.34459686279297
+-32.30881881713867,69.91413116455078
+-30.56117820739746,69.72110748291016
+-28.63589096069336,69.71194458007812
+85.98224639892578,66.35848999023438
+85.97777557373047,69.85848999023438
+83.98224639892578,66.3559341430664
+83.97777557373047,69.8559341430664
+81.98224639892578,66.35337829589844
+81.97777557373047,69.85337829589844
+79.98225402832031,66.35081481933594
+79.977783203125,69.85081481933594
+77.98225402832031,66.34825897216797
+77.977783203125,69.84825897216797
+75.98225402832031,66.345703125
+75.977783203125,69.845703125
+73.98225402832031,66.34314727783203
+73.977783203125,69.84314727783203
+71.98226165771484,66.34059143066406
+71.97779083251953,69.84059143066406
+69.98226165771484,66.3380355834961
+69.97779083251953,69.8380355834961
+67.98226165771484,66.3354721069336
+67.97779083251953,69.8354721069336
+65.98226165771484,66.33291625976562
+65.97779083251953,69.83291625976562
+63.98226547241211,66.33036041259766
+63.977787017822266,69.83036041259766
+61.982269287109375,66.32780456542969
+61.97779083251953,69.82780456542969
+59.98227310180664,66.32524871826172
+59.9777946472168,69.82524871826172
+102.30058288574219,82.91472625732422
+98.80066680908203,82.89085388183594
+102.31421661376953,80.9147720336914
+98.81430053710938,80.89089965820312
+102.3278579711914,78.9148178100586
+98.82794189453125,78.89094543457031
+102.34149932861328,76.91486358642578
+98.84158325195312,76.8909912109375
+102.35514068603516,74.91490936279297
+98.855224609375,74.89103698730469
+102.36878204345703,72.91495513916016
+98.86886596679688,72.89108276367188
+102.38241577148438,70.91500091552734
+98.88249969482422,70.89112854003906
+102.39605712890625,68.91505432128906
+98.8961410522461,68.89118194580078
+102.40969848632812,66.91510009765625
+98.90978240966797,66.89122772216797
+102.42333984375,64.91514587402344
+98.92342376708984,64.89127349853516
+102.43698120117188,62.91518783569336
+98.93706512451172,62.891319274902344
+102.45061492919922,60.91523361206055
+98.95069885253906,60.89136505126953
+102.4642562866211,58.915279388427734
+98.96434020996094,58.89141082763672
+102.47789764404297,56.91532516479492
+98.97798156738281,56.891456604003906
+102.49153137207031,54.91537094116211
+98.99161529541016,54.891502380371094
+-27.836780548095703,-57.784236907958984
+-29.6750545501709,-57.75445556640625
+-31.392126083374023,-57.48530960083008
+-33.05033493041992,-56.96461868286133
+-34.613040924072266,-56.20388412475586
+-36.04573059082031,-55.21992111206055
+-37.316734313964844,-54.03445816040039
+-38.4940299987793,-52.63148880004883
+-39.49547576904297,-51.1412353515625
+-40.31724548339844,-49.54485321044922
+-40.948238372802734,-47.86389923095703
+-41.37992858886719,-46.121089935302734
+-41.60648727416992,-44.339962005615234
+-110.73300170898438,43.86024856567383
+-114.23278045654297,43.82101821899414
+-110.71058654785156,41.860374450683594
+-114.21036529541016,41.821144104003906
+-110.68816375732422,39.86050033569336
+-114.18794250488281,39.82126998901367
+-110.6657485961914,37.860626220703125
+-114.16552734375,37.82139587402344
+-110.6433334350586,35.86075210571289
+-114.14311218261719,35.8215217590332
+-110.62091064453125,33.860877990722656
+-114.12068939208984,33.82164764404297
+-110.59849548339844,31.86100196838379
+-114.09827423095703,31.82176971435547
+-110.57608032226562,29.861127853393555
+-114.07585906982422,29.821895599365234
+-110.55365753173828,27.86125373840332
+-114.05343627929688,27.822021484375
+-110.53124237060547,25.861379623413086
+-114.03102111816406,25.822147369384766
+-110.50882720947266,23.86150550842285
+-114.00860595703125,23.82227325439453
+-110.48640441894531,21.861631393432617
+-113.9861831665039,21.822399139404297
+-110.4639892578125,19.86175537109375
+-113.9637680053711,19.822525024414062
+-110.44157409667969,17.861881256103516
+-113.94135284423828,17.822650909423828
+-110.41915130615234,15.862007141113281
+-113.91893005371094,15.822775840759277
+-110.39673614501953,13.862133026123047
+-113.89651489257812,13.822901725769043
+-110.37431335449219,11.862258911132812
+-113.87409210205078,11.823027610778809
+-110.35189819335938,9.862384796142578
+-113.85167694091797,9.823153495788574
+-110.32948303222656,7.8625102043151855
+-113.82926177978516,7.82327938079834
+-110.30706024169922,5.862636089324951
+-113.80683898925781,5.8234052658081055
+-110.2846450805664,3.862762212753296
+-113.784423828125,3.823531150817871
+-110.2622299194336,1.862887978553772
+-113.76200866699219,1.8236570358276367
+-110.23980712890625,-0.13698609173297882
+-113.73958587646484,-0.17621707916259766
+-110.21739196777344,-2.1368601322174072
+-113.71717071533203,-2.176091194152832
+83.0335464477539,28.41474723815918
+85.0335464477539,28.420303344726562
+86.99187469482422,28.431671142578125
+88.83265686035156,28.561765670776367
+90.65487670898438,28.85317039489746
+92.44442749023438,29.303630828857422
+94.18744659423828,29.909656524658203
+95.87045288085938,30.666555404663086
+97.48040008544922,31.568470001220703
+98.89628601074219,32.58076095581055
+100.10743713378906,33.788692474365234
+101.10472106933594,35.17844772338867
+101.86125183105469,36.712608337402344
+102.35667419433594,38.34984588623047
+102.57763671875,40.04606628417969
+102.57994842529297,41.95169448852539
+-67.0452880859375,-68.69317626953125
+-65.04474639892578,-68.6723403930664
+-63.04485321044922,-68.6515121459961
+-61.004295349121094,-68.62614440917969
+-58.7590446472168,-68.38240814208984
+-56.57477951049805,-67.80834197998047
+-54.49982452392578,-66.91664123535156
+-52.580078125,-65.72703552246094
+-50.8580207824707,-64.2658462524414
+-49.3718376159668,-62.56550979614258
+-48.1550178527832,-60.7596435546875
+-47.12841796875,-58.83924865722656
+-46.30270767211914,-56.824302673339844
+-45.68648147583008,-54.73574447631836
+-45.286136627197266,-52.59528732299805
+-45.10584259033203,-50.42519760131836
+-45.104854583740234,-48.35634231567383
+-45.11994552612305,-46.35639953613281
+-45.13503646850586,-44.3564567565918
+27.14229393005371,66.28325653076172
+27.137819290161133,69.78325653076172
+25.142295837402344,66.28070068359375
+25.137821197509766,69.78070068359375
+23.142297744750977,66.27814483642578
+23.1378231048584,69.77814483642578
+21.142297744750977,66.27558135986328
+21.1378231048584,69.77558135986328
+19.142301559448242,66.27302551269531
+19.137826919555664,69.77302551269531
+17.142301559448242,66.27046966552734
+17.137826919555664,69.77046966552734
+15.142303466796875,66.26791381835938
+15.137828826904297,69.76791381835938
+13.142305374145508,66.2653579711914
+13.13783073425293,69.7653579711914
+11.14230728149414,66.26280212402344
+11.137832641601562,69.76280212402344
+9.142309188842773,66.26023864746094
+9.137834548950195,69.76023864746094
+7.142311096191406,66.25768280029297
+7.137836456298828,69.75768280029297
+5.142311096191406,66.255126953125
+5.137836456298828,69.755126953125
+3.142313241958618,66.25257110595703
+3.137838125228882,69.75257110595703
+1.1423150300979614,66.25001525878906
+1.1378401517868042,69.75001525878906
+-0.8576830625534058,66.24745178222656
+-0.862157940864563,69.74745178222656
+-2.8576810359954834,66.2448959350586
+-2.8621561527252197,69.7448959350586
+-4.85767936706543,66.24234008789062
+-4.862154006958008,69.74234008789062
+-6.85767936706543,66.23978424072266
+-6.862154006958008,69.73978424072266
+-8.857675552368164,66.23722839355469
+-8.862150192260742,69.73722839355469
+-10.857675552368164,66.23467254638672
+-10.862150192260742,69.73467254638672
+-12.857671737670898,66.23210906982422
+-12.862146377563477,69.73210906982422
+-14.857671737670898,66.22955322265625
+-14.862146377563477,69.72955322265625
+-16.8576717376709,66.22699737548828
+-16.862146377563477,69.72699737548828
+-18.857667922973633,66.22444152832031
+-18.86214256286621,69.72444152832031
+-20.857667922973633,66.22188568115234
+-20.86214256286621,69.72188568115234
+-22.857664108276367,66.21932220458984
+-22.862138748168945,69.71932220458984
+-24.857664108276367,66.21676635742188
+-24.862138748168945,69.71676635742188
+-26.8576602935791,66.2142105102539
+-26.86213493347168,69.7142105102539
+-28.517200469970703,130.03573608398438
+-30.479185104370117,130.01951599121094
+-32.290748596191406,129.8743896484375
+-34.077491760253906,129.5421600341797
+-35.82014083862305,129.0264434814453
+-37.49991226196289,128.332763671875
+-39.098690032958984,127.46863555908203
+-40.59678268432617,126.44512939453125
+-41.8831901550293,125.2926254272461
+-42.97636795043945,123.95542907714844
+-43.85012435913086,122.465576171875
+-44.483543395996094,120.85874938964844
+-44.861446380615234,119.17343139648438
+-44.97604751586914,117.42443084716797
+-44.98167419433594,115.42443084716797
+-67.08174133300781,-65.19336700439453
+-65.08104705810547,-65.17253112792969
+-63.08115768432617,-65.15169525146484
+-61.04294204711914,-65.12653350830078
+-58.815914154052734,-64.90087127685547
+-56.64070510864258,-64.37262725830078
+-54.5582275390625,-63.55173110961914
+-52.60764694213867,-62.45363235473633
+-50.82565689086914,-61.098976135253906
+-49.24726104736328,-59.515892028808594
+-47.89688491821289,-57.74089431762695
+-46.79288864135742,-55.80302429199219
+-45.95462417602539,-53.73627853393555
+-45.396793365478516,-51.5768928527832
+-45.12916946411133,-49.36273193359375
+-45.1131591796875,-47.255462646484375
+-45.12825012207031,-45.25551986694336
+58.047794342041016,69.8227767944336
+56.047794342041016,69.82022094726562
+54.04779815673828,69.81766510009766
+52.04779815673828,69.81510162353516
+50.04780197143555,69.81254577636719
+48.04780197143555,69.80998992919922
+46.04780197143555,69.80743408203125
+44.04780578613281,69.80487823486328
+42.04780960083008,69.80232238769531
+40.04780960083008,69.79975891113281
+38.04780960083008,69.79720306396484
+36.04780960083008,69.79464721679688
+34.047813415527344,69.7920913696289
+32.04781723022461,69.78953552246094
+30.047819137573242,69.78697204589844
+28.047821044921875,69.78441619873047
+-41.66096878051758,51.705543518066406
+-45.16095733642578,51.71539306640625
+-48.66094207763672,51.725242614746094
+-52.16093063354492,51.73509216308594
+-41.666595458984375,49.70555114746094
+-45.16658401489258,49.71540069580078
+-48.666568756103516,49.725250244140625
+-52.16655731201172,49.73509979248047
+-41.67222595214844,47.70555877685547
+-45.17221450805664,47.71540832519531
+-48.67219924926758,47.725257873535156
+-52.17218780517578,47.735107421875
+-41.677852630615234,45.70556640625
+-45.17784118652344,45.715415954589844
+-48.677825927734375,45.72526550292969
+-52.17781448364258,45.73511505126953
+-41.68347930908203,43.70557403564453
+-45.183467864990234,43.715423583984375
+-48.68345260620117,43.72527313232422
+-52.183441162109375,43.73512268066406
+-41.8112678527832,-1.7042436599731445
+-41.805641174316406,0.29588666558265686
+-41.69941329956055,2.0741705894470215
+-41.35930252075195,3.804919719696045
+-40.79069519042969,5.474608421325684
+-40.00382995605469,7.053216934204102
+-39.012840270996094,8.51236629486084
+-37.84077453613281,9.818121910095215
+-36.50387954711914,10.92912483215332
+-35.017189025878906,11.829895973205566
+-33.41349792480469,12.500568389892578
+-31.72817039489746,12.926355361938477
+-29.998367309570312,13.097864151000977
+-66.83586883544922,27.998329162597656
+-64.83587646484375,28.00388526916504
+-62.83588790893555,28.009443283081055
+-60.96198272705078,28.037200927734375
+-59.320926666259766,28.318063735961914
+-57.762474060058594,28.903867721557617
+-56.34273910522461,29.77351951599121
+-55.11284255981445,30.895706176757812
+-54.06452560424805,32.26249694824219
+-53.229007720947266,33.781429290771484
+-52.631980895996094,35.40894317626953
+-52.28708267211914,37.10784912109375
+-52.19707107543945,38.89096450805664
+-52.19144058227539,40.891414642333984
+-110.73300170898438,43.86024856567383
+-110.71058654785156,41.860374450683594
+-110.68816375732422,39.86050033569336
+-110.6657485961914,37.860626220703125
+-110.6433334350586,35.86075210571289
+-110.61959838867188,33.841243743896484
+-110.43726348876953,31.63846206665039
+-109.99047088623047,29.473773956298828
+-109.2857666015625,27.378807067871094
+-108.33344268798828,25.384170532226562
+-107.14742279052734,23.51900863647461
+-105.80815887451172,21.844375610351562
+-104.22147369384766,20.24699592590332
+-102.42084503173828,18.895343780517578
+-100.4439926147461,17.817724227905273
+-98.33230590820312,17.036706924438477
+-96.1300048828125,16.568639755249023
+-93.89205169677734,16.423110961914062
+-91.89205932617188,16.428667068481445
+-89.8920669555664,16.43422508239746
+58.047794342041016,69.8227767944336
+56.04737854003906,69.82022094726562
+54.04738235473633,69.81766510009766
+51.988121032714844,69.80863189697266
+49.6430778503418,69.47372436523438
+47.42210006713867,68.64990234375
+45.42589569091797,67.37451934814453
+43.748924255371094,65.71070861816406
+42.45146560668945,63.83143997192383
+41.4772834777832,61.766014099121094
+40.85236740112305,59.56953430175781
+40.59340286254883,57.300621032714844
+40.56429672241211,55.268001556396484
+40.53807830810547,53.26817321777344
+-107.23320770263672,43.89921951293945
+-107.2107925415039,41.89934539794922
+-107.18836975097656,39.899471282958984
+-107.16299438476562,37.936710357666016
+-106.99881744384766,36.15324020385742
+-106.6243896484375,34.40181350708008
+-106.04498291015625,32.707115173339844
+-105.26876068115234,31.093053817749023
+-104.30668640136719,29.58238410949707
+-103.17849731445312,28.205001831054688
+-101.89923858642578,27.02199935913086
+-100.461181640625,26.038129806518555
+-98.89506530761719,25.2744140625
+-97.23432922363281,24.747173309326172
+-95.51448059082031,24.467668533325195
+-93.67462158203125,24.423744201660156
+-91.67462921142578,24.42930030822754
+-89.67448425292969,24.434858322143555
+-27.800329208374023,-61.2840461730957
+-29.64684295654297,-61.25670623779297
+-31.37819480895996,-60.99969482421875
+-33.05583190917969,-60.500526428222656
+-34.64606475830078,-59.769222259521484
+-36.11695098876953,-58.820472717285156
+-37.4389533996582,-57.6733283996582
+-38.60688018798828,-56.338409423828125
+-39.60588836669922,-54.86180877685547
+-40.41543197631836,-53.273414611816406
+-41.023193359375,-51.597415924072266
+-41.41991424560547,-49.85932540893555
+-41.59955596923828,-48.085601806640625
+-41.6214714050293,-46.14118957519531
+-41.63656234741211,-44.1412467956543
+58.05227279663086,66.3227767944336
+56.067020416259766,66.31979370117188
+54.31907272338867,66.1801528930664
+52.60772705078125,65.79791259765625
+50.96648406982422,65.18055725097656
+49.42747116088867,64.34015655517578
+48.02082061767578,63.2932014465332
+46.79072570800781,62.068260192871094
+45.765785217285156,60.67502212524414
+44.9659538269043,59.14142608642578
+44.41005325317383,57.503562927246094
+44.11115646362305,55.79995346069336
+44.047298431396484,53.948402404785156
+-41.57395935058594,82.62542724609375
+-45.07394790649414,82.6352767944336
+-41.579586029052734,80.62543487548828
+-45.07957458496094,80.63528442382812
+-41.5852165222168,78.62544250488281
+-45.085205078125,78.63529205322266
+-41.590843200683594,76.62545013427734
+-45.0908317565918,76.63529968261719
+-41.59646987915039,74.62545776367188
+-45.096458435058594,74.63530731201172
+-41.60210037231445,72.6254653930664
+-45.102088928222656,72.63531494140625
+-41.60772705078125,70.62547302246094
+-45.10771560668945,70.63532257080078
+-41.61335754394531,68.62548065185547
+-45.113346099853516,68.63533020019531
+-41.61898422241211,66.62548828125
+-45.11897277832031,66.63533782958984
+-41.624610900878906,64.62549591064453
+-45.12459945678711,64.63534545898438
+-41.63024139404297,62.62550354003906
+-45.13022994995117,62.635353088378906
+-41.635868072509766,60.625511169433594
+-45.13585662841797,60.63536071777344
+-41.64149475097656,58.625518798828125
+-45.141483306884766,58.63536834716797
+-41.647125244140625,56.625526428222656
+-45.14711380004883,56.6353759765625
+-41.65275192260742,54.62553405761719
+-45.152740478515625,54.63538360595703
+-41.658382415771484,52.62554168701172
+-45.15837097167969,52.63539123535156
+44.02894973754883,52.548702239990234
+44.055171966552734,54.54882049560547
+44.01411819458008,56.72224426269531
+43.62957000732422,58.97473907470703
+42.88161087036133,61.133949279785156
+41.790401458740234,63.141658782958984
+40.38536071777344,64.94373321533203
+38.77177810668945,66.47734069824219
+36.912357330322266,67.79409790039062
+34.866397857666016,68.79676818847656
+32.68648910522461,69.45955657958984
+30.42867088317871,69.76544189453125
+28.331613540649414,69.78478240966797
+26.403766632080078,28.25739860534668
+28.388469696044922,28.263391494750977
+30.135652542114258,28.406394958496094
+31.845666885375977,28.792335510253906
+33.48490524291992,29.413618087768555
+35.02115249633789,30.258039474487305
+36.42421340942383,31.308998107910156
+37.650108337402344,32.537899017333984
+38.67073059082031,33.93463897705078
+39.46599197387695,35.47091293334961
+40.017215728759766,37.11064147949219
+40.311466217041016,38.815330505371094
+40.37294387817383,40.67201232910156
+-41.686771392822266,42.535579681396484
+-45.18675994873047,42.54542922973633
+-41.69239807128906,40.535587310791016
+-45.192386627197266,40.54543685913086
+-41.698028564453125,38.53559494018555
+-45.19801712036133,38.54544448852539
+-41.70365524291992,36.53560256958008
+-45.203643798828125,36.54545211791992
+-41.70928192138672,34.53561019897461
+-45.20927047729492,34.54545974731445
+-41.71491241455078,32.53561782836914
+-45.214900970458984,32.545467376708984
+-41.72053909301758,30.535627365112305
+-45.22052764892578,30.54547691345215
+-41.72616958618164,28.535634994506836
+-45.226158142089844,28.54548454284668
+-41.73179626464844,26.535642623901367
+-45.23178482055664,26.54549217224121
+-41.737422943115234,24.5356502532959
+-45.23741149902344,24.545499801635742
+-41.7430534362793,22.535659790039062
+-45.2430419921875,22.545509338378906
+-41.748680114746094,20.535667419433594
+-45.2486686706543,20.545516967773438
+-41.75430679321289,18.535675048828125
+-45.254295349121094,18.54552459716797
+-41.75993728637695,16.535682678222656
+-45.259925842285156,16.5455322265625
+-41.76556396484375,14.535690307617188
+-45.26555252075195,14.545539855957031
+-41.77119445800781,12.535697937011719
+-45.271183013916016,12.545547485351562
+-41.77682113647461,10.53570556640625
+-45.27680969238281,10.545555114746094
+-41.782447814941406,8.535713195800781
+-45.28243637084961,8.545562744140625
+-41.78807830810547,6.535721302032471
+-45.28806686401367,6.545570373535156
+-41.793704986572266,4.535728931427002
+-45.29369354248047,4.5455780029296875
+-41.79933166503906,2.5357401371002197
+-45.299320220947266,2.5455894470214844
+-41.804962158203125,0.5357478260993958
+-45.30495071411133,0.5455971956253052
+-41.81058883666992,-1.4642444849014282
+-45.310577392578125,-1.4543951749801636
+-66.79419708251953,12.998388290405273
+-64.79407501220703,13.003945350646973
+-62.95246505737305,12.963264465332031
+-61.24401092529297,12.681835174560547
+-59.598121643066406,12.14417552947998
+-58.0529899597168,11.362762451171875
+-56.644474029541016,10.355727195739746
+-55.40166091918945,9.143378257751465
+-54.33807373046875,7.753330230712891
+-53.48170471191406,6.226869106292725
+-52.84976577758789,4.594662189483643
+-52.45494842529297,2.8895034790039062
+-52.3051872253418,1.1456518173217773
+-52.30883026123047,-0.8236172795295715
+98.8006591796875,82.89085388183594
+98.8143081665039,80.89006805419922
+98.82794952392578,78.8901138305664
+98.72276306152344,77.18574523925781
+98.30300903320312,75.58283233642578
+97.5813217163086,74.0912857055664
+96.58493041992188,72.76737976074219
+95.34532165527344,71.65087890625
+93.9169692993164,70.78024291992188
+92.35247802734375,70.18814849853516
+90.7055892944336,69.89494323730469
+88.85015106201172,69.8621597290039
+86.85015869140625,69.85960388183594
+-48.686744689941406,42.55527877807617
+-48.69237518310547,40.55512237548828
+-48.69800567626953,38.55513000488281
+-48.70363235473633,36.555137634277344
+-48.66004943847656,34.438323974609375
+-48.41246032714844,32.279457092285156
+-47.951908111572266,30.155811309814453
+-47.282928466796875,28.088333129882812
+-46.41213607788086,26.097429275512695
+-45.348106384277344,24.20273780822754
+-44.09283447265625,22.413785934448242
+-42.56835174560547,20.750102996826172
+-40.81555938720703,19.328977584838867
+-38.87264633178711,18.18138313293457
+-36.78195571899414,17.33232879638672
+-34.589054107666016,16.80031394958496
+-32.341712951660156,16.596933364868164
+-30.308218002319336,16.599781036376953
+-103.73343658447266,43.9387092590332
+-103.71101379394531,41.938575744628906
+-103.61397552490234,40.124244689941406
+-103.29901123046875,38.373069763183594
+-102.76738739013672,36.675071716308594
+-102.0274658203125,35.05694580078125
+-101.09088897705078,33.54412078857422
+-99.97235870361328,32.1603889465332
+-98.69608306884766,30.942018508911133
+-97.26941680908203,29.90922737121582
+-95.7161865234375,29.078859329223633
+-94.06493377685547,28.466171264648438
+-92.34599304199219,28.082420349121094
+-90.59093475341797,27.93465805053711
+-66.83587646484375,27.99833106994629
+-66.8261489868164,24.49834442138672
+-64.83588409423828,28.003887176513672
+-64.82615661621094,24.5039005279541
+-62.83588790893555,28.009445190429688
+-62.82616424560547,24.509458541870117
+-60.83589553833008,28.01500129699707
+-60.826171875,24.5150146484375
+-58.83590316772461,28.020559310913086
+-58.82617950439453,24.520572662353516
+-56.83591079711914,28.02611541748047
+-56.82618713378906,24.5261287689209
+-54.83591842651367,28.031673431396484
+-54.826194763183594,24.531686782836914
+-52.8359260559082,28.037229537963867
+-52.826202392578125,24.537242889404297
+-50.835933685302734,28.042787551879883
+-50.826210021972656,24.542800903320312
+-48.835941314697266,28.048343658447266
+-48.82621765136719,24.548357009887695
+-46.8359489440918,28.05390167236328
+-46.82622528076172,24.55391502380371
+-44.83595657348633,28.059457778930664
+-44.82623291015625,24.559471130371094
+-42.83596420288086,28.06501579284668
+-42.82624053955078,24.56502914428711
+-40.83597183227539,28.070571899414062
+-40.82624816894531,24.570585250854492
+-38.83597946166992,28.076129913330078
+-38.826255798339844,24.576143264770508
+-36.83598709106445,28.08168601989746
+-36.826263427734375,24.58169937133789
+-34.835994720458984,28.087244033813477
+-34.826271057128906,24.587257385253906
+-32.836002349853516,28.09280014038086
+-32.82627868652344,24.59281349182129
+-30.83601188659668,28.098358154296875
+-30.82628631591797,24.598371505737305
+-28.83601951599121,28.103914260864258
+-28.8262939453125,24.603927612304688
+19.330636978149414,140.9599151611328
+19.35021209716797,137.4599609375
+19.36978530883789,133.96002197265625
+19.389360427856445,130.46006774902344
+21.33060646057129,140.97109985351562
+21.350181579589844,137.4711456298828
+21.369754791259766,133.97120666503906
+21.38932991027832,130.47125244140625
+23.33057403564453,140.98228454589844
+23.350149154663086,137.48233032226562
+23.369722366333008,133.98239135742188
+23.389297485351562,130.48243713378906
+25.330543518066406,140.99346923828125
+25.35011863708496,137.49351501464844
+25.369691848754883,133.9935760498047
+25.389266967773438,130.49362182617188
+27.33051300048828,141.00465393066406
+27.350088119506836,137.50469970703125
+27.369661331176758,134.0047607421875
+27.389236450195312,130.5048065185547
+29.330480575561523,141.01583862304688
+29.350055694580078,137.51588439941406
+29.36962890625,134.0159454345703
+29.389204025268555,130.5159912109375
+31.330448150634766,141.0270233154297
+31.35002326965332,137.52706909179688
+31.369596481323242,134.02713012695312
+31.389171600341797,130.5271759033203
+33.33041763305664,141.0382080078125
+33.34999084472656,137.5382537841797
+33.36956787109375,134.03831481933594
+33.38914108276367,130.53836059570312
+35.330387115478516,141.04940795898438
+35.34996032714844,137.54945373535156
+35.369537353515625,134.0495147705078
+35.38911056518555,130.549560546875
+37.33035659790039,141.0605926513672
+37.34992980957031,137.56063842773438
+37.3695068359375,134.06069946289062
+37.38908004760742,130.5607452392578
+39.330326080322266,141.07177734375
+39.34989929199219,137.5718231201172
+39.369476318359375,134.07188415527344
+39.3890495300293,130.57192993164062
+41.33029556274414,141.0829620361328
+41.34986877441406,137.5830078125
+41.36944580078125,134.08306884765625
+41.38901901245117,130.58311462402344
+43.33026123046875,141.09414672851562
+43.34983444213867,137.5941925048828
+43.36941146850586,134.09425354003906
+43.38898468017578,130.59429931640625
+45.330230712890625,141.10533142089844
+45.34980392456055,137.60537719726562
+45.369380950927734,134.10543823242188
+45.388954162597656,130.60548400878906
+47.330196380615234,141.11651611328125
+47.349769592285156,137.61656188964844
+47.369346618652344,134.1166229248047
+47.388919830322266,130.61666870117188
+49.33016586303711,141.12770080566406
+49.34973907470703,137.62774658203125
+49.36931610107422,134.1278076171875
+49.38888931274414,130.6278533935547
+51.330135345458984,141.13888549804688
+51.349708557128906,137.63893127441406
+51.369285583496094,134.1389923095703
+51.388858795166016,130.6390380859375
+53.33010482788086,141.1500701904297
+53.34967803955078,137.65011596679688
+53.36925506591797,134.15017700195312
+53.38882827758789,130.6502227783203
+55.330074310302734,141.1612548828125
+55.349647521972656,137.6613006591797
+55.369224548339844,134.16136169433594
+55.388797760009766,130.66140747070312
+57.33004379272461,141.1724395751953
+57.34961700439453,137.6724853515625
+57.36919403076172,134.17254638671875
+57.38876724243164,130.67259216308594
+59.330013275146484,141.18362426757812
+59.349586486816406,137.6836700439453
+59.369163513183594,134.18373107910156
+59.388736724853516,130.68377685546875
+61.32998275756836,141.19480895996094
+61.34955596923828,137.69485473632812
+61.36913299560547,134.19491577148438
+61.38870620727539,130.69496154785156
+63.329952239990234,141.20599365234375
+63.349525451660156,137.70603942871094
+63.369102478027344,134.2061004638672
+63.388675689697266,130.70614624023438
+65.42821502685547,141.21044921875
+65.38225555419922,137.71075439453125
+65.33629608154297,134.2110595703125
+65.29033660888672,130.71136474609375
+67.71540832519531,141.11734008789062
+67.47671508789062,137.62548828125
+67.23802185058594,134.13363647460938
+66.99932861328125,130.64178466796875
+69.99400329589844,140.8983612060547
+69.56330108642578,137.42495727539062
+69.1325912475586,133.95156860351562
+68.70188903808594,130.47816467285156
+72.25706481933594,140.55416870117188
+71.63565826416016,137.10977172851562
+71.0142593383789,133.66537475585938
+70.39285278320312,130.22097778320312
+74.49773406982422,140.08583068847656
+73.68751525878906,136.680908203125
+72.87728881835938,133.27597045898438
+72.06707000732422,129.8710479736328
+76.70919799804688,139.49476623535156
+75.7126235961914,136.1396484375
+74.7160415649414,132.78451538085938
+73.71946716308594,129.4293975830078
+78.88473510742188,138.7827606201172
+77.704833984375,135.48764038085938
+76.52493286132812,132.1925048828125
+75.34503173828125,128.8973846435547
+81.01774597167969,137.9519805908203
+79.6581039428711,134.72686767578125
+78.29845428466797,131.50173950195312
+76.93881225585938,128.27662658691406
+83.10175323486328,137.0049591064453
+81.56649780273438,133.85964965820312
+80.03123474121094,130.71432495117188
+78.49597930908203,127.56902313232422
+85.13041687011719,135.94454956054688
+83.42420959472656,132.88858032226562
+81.71800231933594,129.8326416015625
+80.01179504394531,126.77667999267578
+87.09757232666016,134.77398681640625
+85.22560119628906,131.81666564941406
+83.35362243652344,128.85935974121094
+81.48165130615234,125.90203857421875
+88.99726867675781,133.496826171875
+86.9652099609375,130.6471405029297
+84.93315124511719,127.79744720458984
+82.90109252929688,124.94775390625
+90.82369995117188,132.11697387695312
+88.63773345947266,129.38356018066406
+86.45177459716797,126.65013885498047
+84.26580810546875,123.9167251586914
+92.57135772705078,130.63856506347656
+90.23812103271484,128.02972412109375
+87.9048843383789,125.42089080810547
+85.57164764404297,122.81205749511719
+94.23490142822266,129.06613159179688
+91.76148223876953,126.58980560302734
+89.2880630493164,124.11347198486328
+86.81464385986328,121.63714599609375
+95.80928802490234,127.40443420410156
+93.20320129394531,125.06813049316406
+90.59710693359375,122.73182678222656
+87.99102020263672,120.39552307128906
+97.27974700927734,125.672119140625
+94.55594635009766,123.47418212890625
+91.83214569091797,121.2762451171875
+89.10834503173828,119.07830810546875
+98.63536834716797,123.91968536376953
+95.8235855102539,121.83549499511719
+93.01180267333984,119.75129699707031
+90.20001983642578,117.66710662841797
+99.91785430908203,122.11304473876953
+97.0228271484375,120.14611053466797
+94.1278076171875,118.1791763305664
+91.23278045654297,116.21224212646484
+101.12505340576172,120.25525665283203
+98.15167236328125,118.40890502929688
+95.17829895019531,116.56254577636719
+92.20491790771484,114.71619415283203
+102.25491333007812,118.34944915771484
+99.20819854736328,116.62678527832031
+96.16149139404297,114.90412902832031
+93.11477661132812,113.18146514892578
+103.30553436279297,116.3988265991211
+100.19063568115234,114.80277252197266
+97.07573699951172,113.20671844482422
+93.9608383178711,111.61066436767578
+104.27513885498047,114.40670776367188
+101.09730529785156,112.93994903564453
+97.91947937011719,111.47319793701172
+94.74164581298828,110.00643920898438
+105.162109375,112.37643432617188
+101.92670440673828,111.04145050048828
+98.6913070678711,109.70647430419922
+95.45590209960938,108.37149047851562
+105.96492004394531,110.31144714355469
+102.67741394042969,109.11048889160156
+99.38990783691406,107.90953063964844
+96.10240173339844,106.70857238769531
+106.68224334716797,108.21521759033203
+103.34817504882812,107.15031433105469
+100.01411437988281,106.08541870117188
+96.68004608154297,105.02051544189453
+107.3128433227539,106.09129333496094
+103.93785095214844,105.16424560546875
+100.56285095214844,104.23719787597656
+97.18785858154297,103.31015014648438
+107.85566711425781,103.94326782226562
+104.44544219970703,103.15563201904297
+101.03520965576172,102.36800384521484
+97.62498474121094,101.58036804199219
+108.30980682373047,101.77474975585938
+104.87010192871094,101.12786102294922
+101.43040466308594,100.4809799194336
+97.9906997680664,99.83409118652344
+108.67446899414062,99.58940887451172
+105.21109771728516,99.08436584472656
+101.74773406982422,98.57931518554688
+98.28436279296875,98.07427215576172
+108.94906616210938,97.39093017578125
+105.4678726196289,97.02857208251953
+101.98668670654297,96.66622161865234
+98.5054931640625,96.30386352539062
+109.13312530517578,95.18302917480469
+105.63998413085938,94.96398162841797
+102.1468505859375,94.74492645263672
+98.6537094116211,94.52587890625
+109.22633361816406,92.96942901611328
+105.7271499633789,92.89405059814453
+102.22795867919922,92.81867218017578
+98.72877502441406,92.74329376220703
+109.246337890625,90.89227294921875
+105.74642181396484,90.86840057373047
+102.24649810791016,90.84453582763672
+98.74658203125,90.82066345214844
+109.25997924804688,88.89232635498047
+105.76006317138672,88.86845397949219
+102.26013946533203,88.84458923339844
+98.76022338867188,88.82071685791016
+109.27362060546875,86.89237213134766
+105.7737045288086,86.86849975585938
+102.2737808227539,86.84463500976562
+98.77386474609375,86.82076263427734
+109.28726196289062,84.89241790771484
+105.78734588623047,84.86854553222656
+102.28742218017578,84.84468078613281
+98.78750610351562,84.82080841064453
+-28.72602081298828,28.104219436645508
+-30.726320266723633,28.098661422729492
+-32.726314544677734,28.09310531616211
+-34.979652404785156,27.924379348754883
+-37.19096755981445,27.405048370361328
+-39.29435348510742,26.54749870300293
+-41.23842239379883,25.3726806640625
+-42.97569274902344,23.909290313720703
+-44.46371841430664,22.193077087402344
+-45.660850524902344,20.370302200317383
+-46.66980743408203,18.45207405090332
+-47.489986419677734,16.44585609436035
+-48.11382293701172,14.370176315307617
+-48.5355339050293,12.244202613830566
+-48.75124740600586,10.087567329406738
+-48.78397750854492,8.002671241760254
+-48.789608001708984,6.002679347991943
+-48.79523468017578,4.002687454223633
+-48.80086135864258,2.002695083618164
+-48.80649185180664,0.0027035577222704887
+-48.686744689941406,42.55527877807617
+-52.18673324584961,42.565128326416016
+-48.6923713684082,40.5552864074707
+-52.192359924316406,40.56513595581055
+-48.698001861572266,38.555294036865234
+-52.19799041748047,38.56514358520508
+-48.70362854003906,36.555301666259766
+-52.203617095947266,36.56515121459961
+-48.70925521850586,34.5553092956543
+-52.20924377441406,34.56515884399414
+-48.71488571166992,32.55531692504883
+-52.214874267578125,32.56516647338867
+-48.72051239013672,30.555326461791992
+-52.22050094604492,30.565176010131836
+-48.72614288330078,28.555334091186523
+-52.226131439208984,28.565183639526367
+-48.73176956176758,26.555341720581055
+-52.23175811767578,26.5651912689209
+-48.737396240234375,24.555349349975586
+-52.23738479614258,24.56519889831543
+-48.74302673339844,22.55535888671875
+-52.24301528930664,22.565208435058594
+-48.748653411865234,20.55536651611328
+-52.24864196777344,20.565216064453125
+-48.75428009033203,18.555374145507812
+-52.254268646240234,18.565223693847656
+-48.759910583496094,16.555381774902344
+-52.2598991394043,16.565231323242188
+-48.76553726196289,14.555389404296875
+-52.265525817871094,14.565238952636719
+-48.77116775512695,12.555397033691406
+-52.271156311035156,12.56524658203125
+-48.77679443359375,10.555404663085938
+-52.27678298950195,10.565254211425781
+-48.78242111206055,8.555412292480469
+-52.28240966796875,8.565261840820312
+-48.78805160522461,6.555419921875
+-52.28804016113281,6.5652689933776855
+-48.793678283691406,4.555427551269531
+-52.29366683959961,4.565276622772217
+-48.7993049621582,2.555438995361328
+-52.299293518066406,2.5652883052825928
+-48.804935455322266,0.5554465055465698
+-52.30492401123047,0.5652958750724792
+-48.81056213378906,-1.444545865058899
+-52.310550689697266,-1.4346965551376343
diff --git a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/main_car.json b/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/main_car.json
deleted file mode 100644
index d687d1c9..00000000
--- a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/main_car.json
+++ /dev/null
@@ -1,161 +0,0 @@
-{
- "objects":
- [
- {
- "type": "sensor.pseudo.traffic_lights",
- "id": "traffic_lights"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.actor_list",
- "id": "actor_list"
- },
- {
- "type": "sensor.pseudo.markers",
- "id": "markers"
- },
- {
- "type": "sensor.pseudo.opendrive_map",
- "id": "map"
- },
- {
- "type": "vehicle.tesla.model3",
- "id": "ego_vehicle",
- "sensors":
- [
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_front",
- "spawn_point": {"x": 2.5, "y": 0.0, "z": 0.8, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "image_size_x": 640,
- "image_size_y": 480
- },
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_view",
- "spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0,
- "attached_objects":
- [
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "sensor.lidar.ray_cast",
- "id": "lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20,
- "noise_stddev": 0.0
- },
- {
- "type": "sensor.lidar.ray_cast_semantic",
- "id": "semantic_lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20
- },
- {
- "type": "sensor.other.radar",
- "id": "radar_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "horizontal_fov": 30.0,
- "vertical_fov": 10.0,
- "points_per_second": 1500,
- "range": 100.0
- },
- {
- "type": "sensor.camera.semantic_segmentation",
- "id": "semantic_segmentation_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.depth",
- "id": "depth_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.dvs",
- "id": "dvs_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70,
- "positive_threshold": 0.3,
- "negative_threshold": 0.3,
- "sigma_positive_threshold": 0.0,
- "sigma_negative_threshold": 0.0,
- "use_log": true,
- "log_eps": 0.001
- },
- {
- "type": "sensor.other.gnss",
- "id": "gnss",
- "spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0},
- "noise_alt_stddev": 0.0, "noise_lat_stddev": 0.0, "noise_lon_stddev": 0.0,
- "noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0
- },
- {
- "type": "sensor.other.imu",
- "id": "imu",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "noise_accel_stddev_x": 0.0, "noise_accel_stddev_y": 0.0, "noise_accel_stddev_z": 0.0,
- "noise_gyro_stddev_x": 0.0, "noise_gyro_stddev_y": 0.0, "noise_gyro_stddev_z": 0.0,
- "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0
- },
- {
- "type": "sensor.other.collision",
- "id": "collision",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.other.lane_invasion",
- "id": "lane_invasion",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.pseudo.tf",
- "id": "tf"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.odom",
- "id": "odometry"
- },
- {
- "type": "sensor.pseudo.speedometer",
- "id": "speedometer"
- },
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- }
- ]
-}
diff --git a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/main_car_custom_camera.json b/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/main_car_custom_camera.json
deleted file mode 100644
index 5054f0fd..00000000
--- a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/main_car_custom_camera.json
+++ /dev/null
@@ -1,163 +0,0 @@
-{
- "objects":
- [
- {
- "type": "sensor.pseudo.traffic_lights",
- "id": "traffic_lights"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.actor_list",
- "id": "actor_list"
- },
- {
- "type": "sensor.pseudo.markers",
- "id": "markers"
- },
- {
- "type": "sensor.pseudo.opendrive_map",
- "id": "map"
- },
- {
- "type": "vehicle.tesla.model3",
- "id": "ego_vehicle",
- "sensors":
- [
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_front",
- "spawn_point": {"x": 1.5, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 15.0, "yaw": 0.0},
- "image_size_x": 288,
- "image_size_y": 200,
- "fov": 90.0
- },
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_view",
- "spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0,
- "attached_objects":
- [
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "sensor.lidar.ray_cast",
- "id": "lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20,
- "noise_stddev": 0.0
- },
- {
- "type": "sensor.lidar.ray_cast_semantic",
- "id": "semantic_lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20
- },
- {
- "type": "sensor.other.radar",
- "id": "radar_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "horizontal_fov": 30.0,
- "vertical_fov": 10.0,
- "points_per_second": 1500,
- "range": 100.0
- },
- {
- "type": "sensor.camera.semantic_segmentation",
- "id": "semantic_segmentation_front",
- "spawn_point": {"x": 1.5, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 15.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 288,
- "image_size_y": 200
- },
- {
- "type": "sensor.camera.depth",
- "id": "depth_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.dvs",
- "id": "dvs_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70,
- "positive_threshold": 0.3,
- "negative_threshold": 0.3,
- "sigma_positive_threshold": 0.0,
- "sigma_negative_threshold": 0.0,
- "use_log": true,
- "log_eps": 0.001
- },
- {
- "type": "sensor.other.gnss",
- "id": "gnss",
- "spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0},
- "noise_alt_stddev": 0.0, "noise_lat_stddev": 0.0, "noise_lon_stddev": 0.0,
- "noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0
- },
- {
- "type": "sensor.other.imu",
- "id": "imu",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "noise_accel_stddev_x": 0.0, "noise_accel_stddev_y": 0.0, "noise_accel_stddev_z": 0.0,
- "noise_gyro_stddev_x": 0.0, "noise_gyro_stddev_y": 0.0, "noise_gyro_stddev_z": 0.0,
- "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0
- },
- {
- "type": "sensor.other.collision",
- "id": "collision",
- "spawn_point": {"x": 2.5, "y": 0.0, "z": 0.7}
- },
- {
- "type": "sensor.other.lane_invasion",
- "id": "lane_invasion",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.pseudo.tf",
- "id": "tf"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.odom",
- "id": "odometry"
- },
- {
- "type": "sensor.pseudo.speedometer",
- "id": "speedometer"
- },
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- }
- ]
-}
-
diff --git a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/parked_bike_car_objects.json b/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/parked_bike_car_objects.json
deleted file mode 100644
index 70124e1f..00000000
--- a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/parked_bike_car_objects.json
+++ /dev/null
@@ -1,170 +0,0 @@
-{
- "objects":
- [
- {
- "type": "sensor.pseudo.traffic_lights",
- "id": "traffic_lights"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.actor_list",
- "id": "actor_list"
- },
- {
- "type": "sensor.pseudo.markers",
- "id": "markers"
- },
- {
- "type": "sensor.pseudo.opendrive_map",
- "id": "map"
- },
- {
- "type": "vehicle.tesla.model3",
- "id": "ego_vehicle",
- "sensors":
- [
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0
- },
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_view",
- "spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0,
- "attached_objects":
- [
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "sensor.lidar.ray_cast",
- "id": "lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20,
- "noise_stddev": 0.0
- },
- {
- "type": "sensor.lidar.ray_cast_semantic",
- "id": "semantic_lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20
- },
- {
- "type": "sensor.other.radar",
- "id": "radar_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "horizontal_fov": 30.0,
- "vertical_fov": 10.0,
- "points_per_second": 1500,
- "range": 100.0
- },
- {
- "type": "sensor.camera.semantic_segmentation",
- "id": "semantic_segmentation_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.depth",
- "id": "depth_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.dvs",
- "id": "dvs_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70,
- "positive_threshold": 0.3,
- "negative_threshold": 0.3,
- "sigma_positive_threshold": 0.0,
- "sigma_negative_threshold": 0.0,
- "use_log": true,
- "log_eps": 0.001
- },
- {
- "type": "sensor.other.gnss",
- "id": "gnss",
- "spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0},
- "noise_alt_stddev": 0.0, "noise_lat_stddev": 0.0, "noise_lon_stddev": 0.0,
- "noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0
- },
- {
- "type": "sensor.other.imu",
- "id": "imu",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "noise_accel_stddev_x": 0.0, "noise_accel_stddev_y": 0.0, "noise_accel_stddev_z": 0.0,
- "noise_gyro_stddev_x": 0.0, "noise_gyro_stddev_y": 0.0, "noise_gyro_stddev_z": 0.0,
- "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0
- },
- {
- "type": "sensor.other.collision",
- "id": "collision",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.other.lane_invasion",
- "id": "lane_invasion",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.pseudo.tf",
- "id": "tf"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.odom",
- "id": "odometry"
- },
- {
- "type": "sensor.pseudo.speedometer",
- "id": "speedometer"
- },
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "vehicle.yamaha.yzf",
- "id": "parked_bike"
- },
- {
- "type": "vehicle.audi.a2",
- "id": "parked_car"
- }
- ]
-}
\ No newline at end of file
diff --git a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/parked_bike_objects.json b/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/parked_bike_objects.json
deleted file mode 100644
index 816ebda5..00000000
--- a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/parked_bike_objects.json
+++ /dev/null
@@ -1,166 +0,0 @@
-{
- "objects":
- [
- {
- "type": "sensor.pseudo.traffic_lights",
- "id": "traffic_lights"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.actor_list",
- "id": "actor_list"
- },
- {
- "type": "sensor.pseudo.markers",
- "id": "markers"
- },
- {
- "type": "sensor.pseudo.opendrive_map",
- "id": "map"
- },
- {
- "type": "vehicle.tesla.model3",
- "id": "ego_vehicle",
- "sensors":
- [
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0
- },
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_view",
- "spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0,
- "attached_objects":
- [
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "sensor.lidar.ray_cast",
- "id": "lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20,
- "noise_stddev": 0.0
- },
- {
- "type": "sensor.lidar.ray_cast_semantic",
- "id": "semantic_lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20
- },
- {
- "type": "sensor.other.radar",
- "id": "radar_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "horizontal_fov": 30.0,
- "vertical_fov": 10.0,
- "points_per_second": 1500,
- "range": 100.0
- },
- {
- "type": "sensor.camera.semantic_segmentation",
- "id": "semantic_segmentation_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.depth",
- "id": "depth_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.dvs",
- "id": "dvs_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70,
- "positive_threshold": 0.3,
- "negative_threshold": 0.3,
- "sigma_positive_threshold": 0.0,
- "sigma_negative_threshold": 0.0,
- "use_log": true,
- "log_eps": 0.001
- },
- {
- "type": "sensor.other.gnss",
- "id": "gnss",
- "spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0},
- "noise_alt_stddev": 0.0, "noise_lat_stddev": 0.0, "noise_lon_stddev": 0.0,
- "noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0
- },
- {
- "type": "sensor.other.imu",
- "id": "imu",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "noise_accel_stddev_x": 0.0, "noise_accel_stddev_y": 0.0, "noise_accel_stddev_z": 0.0,
- "noise_gyro_stddev_x": 0.0, "noise_gyro_stddev_y": 0.0, "noise_gyro_stddev_z": 0.0,
- "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0
- },
- {
- "type": "sensor.other.collision",
- "id": "collision",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.other.lane_invasion",
- "id": "lane_invasion",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.pseudo.tf",
- "id": "tf"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.odom",
- "id": "odometry"
- },
- {
- "type": "sensor.pseudo.speedometer",
- "id": "speedometer"
- },
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "vehicle.yamaha.yzf",
- "id": "parked_bike"
- }
- ]
-}
\ No newline at end of file
diff --git a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/parked_car_objects.json b/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/parked_car_objects.json
deleted file mode 100644
index 017dfb0e..00000000
--- a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/parked_car_objects.json
+++ /dev/null
@@ -1,166 +0,0 @@
-{
- "objects":
- [
- {
- "type": "sensor.pseudo.traffic_lights",
- "id": "traffic_lights"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.actor_list",
- "id": "actor_list"
- },
- {
- "type": "sensor.pseudo.markers",
- "id": "markers"
- },
- {
- "type": "sensor.pseudo.opendrive_map",
- "id": "map"
- },
- {
- "type": "vehicle.tesla.model3",
- "id": "ego_vehicle",
- "sensors":
- [
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0
- },
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_view",
- "spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0,
- "attached_objects":
- [
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "sensor.lidar.ray_cast",
- "id": "lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20,
- "noise_stddev": 0.0
- },
- {
- "type": "sensor.lidar.ray_cast_semantic",
- "id": "semantic_lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20
- },
- {
- "type": "sensor.other.radar",
- "id": "radar_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "horizontal_fov": 30.0,
- "vertical_fov": 10.0,
- "points_per_second": 1500,
- "range": 100.0
- },
- {
- "type": "sensor.camera.semantic_segmentation",
- "id": "semantic_segmentation_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.depth",
- "id": "depth_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.dvs",
- "id": "dvs_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70,
- "positive_threshold": 0.3,
- "negative_threshold": 0.3,
- "sigma_positive_threshold": 0.0,
- "sigma_negative_threshold": 0.0,
- "use_log": true,
- "log_eps": 0.001
- },
- {
- "type": "sensor.other.gnss",
- "id": "gnss",
- "spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0},
- "noise_alt_stddev": 0.0, "noise_lat_stddev": 0.0, "noise_lon_stddev": 0.0,
- "noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0
- },
- {
- "type": "sensor.other.imu",
- "id": "imu",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "noise_accel_stddev_x": 0.0, "noise_accel_stddev_y": 0.0, "noise_accel_stddev_z": 0.0,
- "noise_gyro_stddev_x": 0.0, "noise_gyro_stddev_y": 0.0, "noise_gyro_stddev_z": 0.0,
- "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0
- },
- {
- "type": "sensor.other.collision",
- "id": "collision",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.other.lane_invasion",
- "id": "lane_invasion",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.pseudo.tf",
- "id": "tf"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.odom",
- "id": "odometry"
- },
- {
- "type": "sensor.pseudo.speedometer",
- "id": "speedometer"
- },
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "vehicle.audi.a2",
- "id": "parked_vehicle"
- }
- ]
-}
\ No newline at end of file
diff --git a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/pedestrian_objects.json b/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/pedestrian_objects.json
deleted file mode 100644
index 19e2556f..00000000
--- a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/pedestrian_objects.json
+++ /dev/null
@@ -1,166 +0,0 @@
-{
- "objects":
- [
- {
- "type": "sensor.pseudo.traffic_lights",
- "id": "traffic_lights"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.actor_list",
- "id": "actor_list"
- },
- {
- "type": "sensor.pseudo.markers",
- "id": "markers"
- },
- {
- "type": "sensor.pseudo.opendrive_map",
- "id": "map"
- },
- {
- "type": "vehicle.tesla.model3",
- "id": "ego_vehicle",
- "sensors":
- [
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0
- },
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_view",
- "spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0,
- "attached_objects":
- [
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "sensor.lidar.ray_cast",
- "id": "lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20,
- "noise_stddev": 0.0
- },
- {
- "type": "sensor.lidar.ray_cast_semantic",
- "id": "semantic_lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20
- },
- {
- "type": "sensor.other.radar",
- "id": "radar_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "horizontal_fov": 30.0,
- "vertical_fov": 10.0,
- "points_per_second": 1500,
- "range": 100.0
- },
- {
- "type": "sensor.camera.semantic_segmentation",
- "id": "semantic_segmentation_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.depth",
- "id": "depth_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.dvs",
- "id": "dvs_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70,
- "positive_threshold": 0.3,
- "negative_threshold": 0.3,
- "sigma_positive_threshold": 0.0,
- "sigma_negative_threshold": 0.0,
- "use_log": true,
- "log_eps": 0.001
- },
- {
- "type": "sensor.other.gnss",
- "id": "gnss",
- "spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0},
- "noise_alt_stddev": 0.0, "noise_lat_stddev": 0.0, "noise_lon_stddev": 0.0,
- "noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0
- },
- {
- "type": "sensor.other.imu",
- "id": "imu",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "noise_accel_stddev_x": 0.0, "noise_accel_stddev_y": 0.0, "noise_accel_stddev_z": 0.0,
- "noise_gyro_stddev_x": 0.0, "noise_gyro_stddev_y": 0.0, "noise_gyro_stddev_z": 0.0,
- "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0
- },
- {
- "type": "sensor.other.collision",
- "id": "collision",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.other.lane_invasion",
- "id": "lane_invasion",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.pseudo.tf",
- "id": "tf"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.odom",
- "id": "odometry"
- },
- {
- "type": "sensor.pseudo.speedometer",
- "id": "speedometer"
- },
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "walker.pedestrian.0001",
- "id": "pedestrian"
- }
- ]
-}
\ No newline at end of file
diff --git a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/pedestrian_parked_bike_car_objects.json b/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/pedestrian_parked_bike_car_objects.json
deleted file mode 100644
index f4079106..00000000
--- a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/pedestrian_parked_bike_car_objects.json
+++ /dev/null
@@ -1,174 +0,0 @@
-{
- "objects":
- [
- {
- "type": "sensor.pseudo.traffic_lights",
- "id": "traffic_lights"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.actor_list",
- "id": "actor_list"
- },
- {
- "type": "sensor.pseudo.markers",
- "id": "markers"
- },
- {
- "type": "sensor.pseudo.opendrive_map",
- "id": "map"
- },
- {
- "type": "vehicle.tesla.model3",
- "id": "ego_vehicle",
- "sensors":
- [
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0
- },
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_view",
- "spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0,
- "attached_objects":
- [
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "sensor.lidar.ray_cast",
- "id": "lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20,
- "noise_stddev": 0.0
- },
- {
- "type": "sensor.lidar.ray_cast_semantic",
- "id": "semantic_lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20
- },
- {
- "type": "sensor.other.radar",
- "id": "radar_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "horizontal_fov": 30.0,
- "vertical_fov": 10.0,
- "points_per_second": 1500,
- "range": 100.0
- },
- {
- "type": "sensor.camera.semantic_segmentation",
- "id": "semantic_segmentation_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.depth",
- "id": "depth_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.dvs",
- "id": "dvs_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70,
- "positive_threshold": 0.3,
- "negative_threshold": 0.3,
- "sigma_positive_threshold": 0.0,
- "sigma_negative_threshold": 0.0,
- "use_log": true,
- "log_eps": 0.001
- },
- {
- "type": "sensor.other.gnss",
- "id": "gnss",
- "spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0},
- "noise_alt_stddev": 0.0, "noise_lat_stddev": 0.0, "noise_lon_stddev": 0.0,
- "noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0
- },
- {
- "type": "sensor.other.imu",
- "id": "imu",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "noise_accel_stddev_x": 0.0, "noise_accel_stddev_y": 0.0, "noise_accel_stddev_z": 0.0,
- "noise_gyro_stddev_x": 0.0, "noise_gyro_stddev_y": 0.0, "noise_gyro_stddev_z": 0.0,
- "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0
- },
- {
- "type": "sensor.other.collision",
- "id": "collision",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.other.lane_invasion",
- "id": "lane_invasion",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.pseudo.tf",
- "id": "tf"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.odom",
- "id": "odometry"
- },
- {
- "type": "sensor.pseudo.speedometer",
- "id": "speedometer"
- },
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "vehicle.yamaha.yzf",
- "id": "parked_bike"
- },
- {
- "type": "vehicle.audi.a2",
- "id": "parked_car"
- },
- {
- "type": "walker.pedestrian.0001",
- "id": "pedestrian"
- }
- ]
-}
\ No newline at end of file
diff --git a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/single_ad_car.json b/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/single_ad_car.json
deleted file mode 100644
index 46758eb4..00000000
--- a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/single_ad_car.json
+++ /dev/null
@@ -1,178 +0,0 @@
-{
- "objects":
- [
- {
- "type": "sensor.pseudo.traffic_lights",
- "id": "traffic_lights"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.actor_list",
- "id": "actor_list"
- },
- {
- "type": "sensor.pseudo.markers",
- "id": "markers"
- },
- {
- "type": "sensor.pseudo.opendrive_map",
- "id": "map"
- },
- {
- "type": "vehicle.tesla.model3",
- "id": "ego_vehicle",
- "sensors":
- [
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0
- },
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_view",
- "spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0,
- "attached_objects":
- [
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "sensor.lidar.ray_cast",
- "id": "lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20,
- "noise_stddev": 0.0
- },
- {
- "type": "sensor.lidar.ray_cast_semantic",
- "id": "semantic_lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20
- },
- {
- "type": "sensor.other.radar",
- "id": "radar_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "horizontal_fov": 30.0,
- "vertical_fov": 10.0,
- "points_per_second": 1500,
- "range": 100.0
- },
- {
- "type": "sensor.camera.semantic_segmentation",
- "id": "semantic_segmentation_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.depth",
- "id": "depth_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.dvs",
- "id": "dvs_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70,
- "positive_threshold": 0.3,
- "negative_threshold": 0.3,
- "sigma_positive_threshold": 0.0,
- "sigma_negative_threshold": 0.0,
- "use_log": true,
- "log_eps": 0.001
- },
- {
- "type": "sensor.other.gnss",
- "id": "gnss",
- "spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0},
- "noise_alt_stddev": 0.0, "noise_lat_stddev": 0.0, "noise_lon_stddev": 0.0,
- "noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0
- },
- {
- "type": "sensor.other.imu",
- "id": "imu",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "noise_accel_stddev_x": 0.0, "noise_accel_stddev_y": 0.0, "noise_accel_stddev_z": 0.0,
- "noise_gyro_stddev_x": 0.0, "noise_gyro_stddev_y": 0.0, "noise_gyro_stddev_z": 0.0,
- "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0
- },
- {
- "type": "sensor.other.collision",
- "id": "collision",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.other.lane_invasion",
- "id": "lane_invasion",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.pseudo.tf",
- "id": "tf"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.odom",
- "id": "odometry"
- },
- {
- "type": "sensor.pseudo.speedometer",
- "id": "speedometer"
- },
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "vehicle.audi.a2",
- "id": "npc_vehicle_1",
- "spawn_point": {"x": 60.0, "y": 2.0, "z": 1.37, "roll": 0.0, "pitch": 0.0, "yaw": 180.0},
- "sensors":
- [
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.odom",
- "id": "odometry"
- }
- ]
- }
- ]
-}
\ No newline at end of file
diff --git a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/single_ad_car_subjective_vision.json b/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/single_ad_car_subjective_vision.json
deleted file mode 100644
index 0a9d8fce..00000000
--- a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/single_ad_car_subjective_vision.json
+++ /dev/null
@@ -1,177 +0,0 @@
-{
- "objects":
- [
- {
- "type": "sensor.pseudo.traffic_lights",
- "id": "traffic_lights"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.actor_list",
- "id": "actor_list"
- },
- {
- "type": "sensor.pseudo.markers",
- "id": "markers"
- },
- {
- "type": "sensor.pseudo.opendrive_map",
- "id": "map"
- },
- {
- "type": "vehicle.tesla.model3",
- "id": "ego_vehicle",
- "sensors":
- [
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_front",
- "spawn_point": {"x": 2.5, "y": 0.0, "z": 0.8, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "image_size_x": 640,
- "image_size_y": 480
- },
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_view",
- "spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0,
- "attached_objects":
- [
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "sensor.lidar.ray_cast",
- "id": "lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20,
- "noise_stddev": 0.0
- },
- {
- "type": "sensor.lidar.ray_cast_semantic",
- "id": "semantic_lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20
- },
- {
- "type": "sensor.other.radar",
- "id": "radar_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "horizontal_fov": 30.0,
- "vertical_fov": 10.0,
- "points_per_second": 1500,
- "range": 100.0
- },
- {
- "type": "sensor.camera.semantic_segmentation",
- "id": "semantic_segmentation_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.depth",
- "id": "depth_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.dvs",
- "id": "dvs_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70,
- "positive_threshold": 0.3,
- "negative_threshold": 0.3,
- "sigma_positive_threshold": 0.0,
- "sigma_negative_threshold": 0.0,
- "use_log": true,
- "log_eps": 0.001
- },
- {
- "type": "sensor.other.gnss",
- "id": "gnss",
- "spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0},
- "noise_alt_stddev": 0.0, "noise_lat_stddev": 0.0, "noise_lon_stddev": 0.0,
- "noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0
- },
- {
- "type": "sensor.other.imu",
- "id": "imu",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "noise_accel_stddev_x": 0.0, "noise_accel_stddev_y": 0.0, "noise_accel_stddev_z": 0.0,
- "noise_gyro_stddev_x": 0.0, "noise_gyro_stddev_y": 0.0, "noise_gyro_stddev_z": 0.0,
- "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0
- },
- {
- "type": "sensor.other.collision",
- "id": "collision",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.other.lane_invasion",
- "id": "lane_invasion",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.pseudo.tf",
- "id": "tf"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.odom",
- "id": "odometry"
- },
- {
- "type": "sensor.pseudo.speedometer",
- "id": "speedometer"
- },
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "vehicle.audi.a2",
- "id": "npc_vehicle_1",
- "spawn_point": {"x": 60.0, "y": 2.0, "z": 1.37, "roll": 0.0, "pitch": 0.0, "yaw": 180.0},
- "sensors":
- [
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.odom",
- "id": "odometry"
- }
- ]
- }
- ]
-}
diff --git a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/single_ad_car_town02.json b/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/single_ad_car_town02.json
deleted file mode 100644
index 3438109a..00000000
--- a/behavior_metrics/configs/CARLA/CARLA_launch_files/CARLA_object_files/single_ad_car_town02.json
+++ /dev/null
@@ -1,178 +0,0 @@
-{
- "objects":
- [
- {
- "type": "sensor.pseudo.traffic_lights",
- "id": "traffic_lights"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.actor_list",
- "id": "actor_list"
- },
- {
- "type": "sensor.pseudo.markers",
- "id": "markers"
- },
- {
- "type": "sensor.pseudo.opendrive_map",
- "id": "map"
- },
- {
- "type": "vehicle.tesla.model3",
- "id": "ego_vehicle",
- "sensors":
- [
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0
- },
- {
- "type": "sensor.camera.rgb",
- "id": "rgb_view",
- "spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0},
- "image_size_x": 800,
- "image_size_y": 600,
- "fov": 90.0,
- "attached_objects":
- [
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "sensor.lidar.ray_cast",
- "id": "lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20,
- "noise_stddev": 0.0
- },
- {
- "type": "sensor.lidar.ray_cast_semantic",
- "id": "semantic_lidar",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "range": 50,
- "channels": 32,
- "points_per_second": 320000,
- "upper_fov": 2.0,
- "lower_fov": -26.8,
- "rotation_frequency": 20
- },
- {
- "type": "sensor.other.radar",
- "id": "radar_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "horizontal_fov": 30.0,
- "vertical_fov": 10.0,
- "points_per_second": 1500,
- "range": 100.0
- },
- {
- "type": "sensor.camera.semantic_segmentation",
- "id": "semantic_segmentation_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.depth",
- "id": "depth_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70
- },
- {
- "type": "sensor.camera.dvs",
- "id": "dvs_front",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "fov": 90.0,
- "image_size_x": 400,
- "image_size_y": 70,
- "positive_threshold": 0.3,
- "negative_threshold": 0.3,
- "sigma_positive_threshold": 0.0,
- "sigma_negative_threshold": 0.0,
- "use_log": true,
- "log_eps": 0.001
- },
- {
- "type": "sensor.other.gnss",
- "id": "gnss",
- "spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0},
- "noise_alt_stddev": 0.0, "noise_lat_stddev": 0.0, "noise_lon_stddev": 0.0,
- "noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0
- },
- {
- "type": "sensor.other.imu",
- "id": "imu",
- "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
- "noise_accel_stddev_x": 0.0, "noise_accel_stddev_y": 0.0, "noise_accel_stddev_z": 0.0,
- "noise_gyro_stddev_x": 0.0, "noise_gyro_stddev_y": 0.0, "noise_gyro_stddev_z": 0.0,
- "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0
- },
- {
- "type": "sensor.other.collision",
- "id": "collision",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.other.lane_invasion",
- "id": "lane_invasion",
- "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
- },
- {
- "type": "sensor.pseudo.tf",
- "id": "tf"
- },
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.odom",
- "id": "odometry"
- },
- {
- "type": "sensor.pseudo.speedometer",
- "id": "speedometer"
- },
- {
- "type": "actor.pseudo.control",
- "id": "control"
- }
- ]
- },
- {
- "type": "vehicle.audi.a2",
- "id": "npc_vehicle_1",
- "spawn_point": {"x": 194.0, "y": -250, "z": 1.37, "roll": 0.0, "pitch": 0.0, "yaw": 90.0},
- "sensors":
- [
- {
- "type": "sensor.pseudo.objects",
- "id": "objects"
- },
- {
- "type": "sensor.pseudo.odom",
- "id": "odometry"
- }
- ]
- }
- ]
-}
\ No newline at end of file
diff --git a/behavior_metrics/configs/CARLA/CARLA_launch_files/test_suite_template.launch.py b/behavior_metrics/configs/CARLA/CARLA_launch_files/test_suite_template.launch.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/configs/CARLA/CARLA_launch_files/town_01_anticlockwise.launch.py b/behavior_metrics/configs/CARLA/CARLA_launch_files/town_01_anticlockwise.launch.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/configs/gazebo/gazebo_launch_files/simple_circuit.launch.py b/behavior_metrics/configs/gazebo/gazebo_launch_files/simple_circuit.launch.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/driver_gazebo.py b/behavior_metrics/driver_gazebo.py
index c0a170d8..0ad10b4e 100644
--- a/behavior_metrics/driver_gazebo.py
+++ b/behavior_metrics/driver_gazebo.py
@@ -1,255 +1,255 @@
-#!/usr/bin/env python
-""" Main module of the BehaviorMetrics application.
-
-This module is the responsible for initializing and destroying all the elements of the application when it is launched.
-
-This program is free software: you can redistribute it and/or modify it under
-the terms of the GNU General Public License as published by the Free Software
-Foundation, either version 3 of the License, or (at your option) any later
-version.
-This program is distributed in the hope that it will be useful, but WITHOUT
-ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
-FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
-You should have received a copy of the GNU General Public License along with
-this program. If not, see .
-"""
-
-import argparse
-import os
-import sys
-import threading
-
-from pilot_gazebo import PilotGazebo
-from ui.tui.main_view import TUI
-from utils import environment, script_manager_gazebo
-from utils.colors import Colors
-from utils.configuration import Config
-from utils.controller_gazebo import ControllerGazebo
-from utils.logger import logger
-from utils.tmp_world_generator import tmp_world_generator
-
-__author__ = 'fqez'
-__contributors__ = []
-__license__ = 'GPLv3'
-
-
-def check_args(argv):
- """Function that handles argument checking and parsing.
-
- Arguments:
- argv {list} -- list of arguments from command line.
-
- Returns:
- dict -- dictionary with the detected configuration.
- """
- parser = argparse.ArgumentParser(description='Neural Behaviors Suite',
- epilog='Enjoy the program! :)')
-
- parser.add_argument('-c',
- '--config',
- type=str,
- action='append',
- required=True,
- help='{}Path to the configuration file in YML format.{}'.format(
- Colors.OKBLUE, Colors.ENDC))
-
- group = parser.add_mutually_exclusive_group(required=True)
- group.add_argument('-g',
- '--gui',
- action='store_true',
- help='{}Load the GUI (Graphic User Interface). Requires PyQt5 installed{}'.format(
- Colors.OKBLUE, Colors.ENDC))
-
- group.add_argument('-t',
- '--tui',
- action='store_true',
- help='{}Load the TUI (Terminal User Interface). Requires npyscreen installed{}'.format(
- Colors.OKBLUE, Colors.ENDC))
-
- group.add_argument('-s',
- '--script',
- action='store_true',
- help='{}Run Behavior Metrics as script{}'.format(
- Colors.OKBLUE, Colors.ENDC))
-
- parser.add_argument('-r',
- '--random',
- action='store_true',
- help='{}Run Behavior Metrics F1 with random spawning{}'.format(
- Colors.OKBLUE, Colors.ENDC))
-
- args = parser.parse_args()
- # get ROS version from environment variable
- ros_version = os.environ.get('ROS_VERSION', '2') # Default is ROS 2
- if ros_version not in ['1', '2']:
- logger.error('Invalid ROS_VERSION environment variable. Must be "1" or "2". Killing program...')
- sys.exit(-1)
-
- config_data = {'config': None, 'gui': None, 'tui': None, 'script': None, 'random': False, 'ros_version': int(ros_version)}
- if args.config:
- config_data['config'] = []
- for config_file in args.config:
- if not os.path.isfile(config_file):
- parser.error('{}No such file {} {}'.format(Colors.FAIL, config_file, Colors.ENDC))
-
- config_data['config'] = args.config
-
- if args.gui:
- config_data['gui'] = args.gui
-
- if args.tui:
- config_data['tui'] = args.tui
-
- if args.script:
- config_data['script'] = args.script
-
- if args.random:
- config_data['random'] = args.random
-
- return config_data
-
-
-def init_node(ros_version):
- """
- Initializes the ROS node based on the selected version.
-
- Arguments:
- ros_version (str): The ROS version ("ros1" or "ros2").
-
- Returns:
- For ROS1: returns None (as rospy manages the node globally).
- For ROS2: returns the created node.
- """
- if ros_version == 1:
- import rospy
- rospy.init_node('my_ros1_node')
- return None # rospy maneja la instancia globalmente
- elif ros_version == 2:
- import rclpy
- rclpy.init()
- node = rclpy.create_node('my_ros2_node')
- logger.info('ROS2 node initialized')
- return node
- else:
- logger.error(f"Unsupported ROS version: {ros_version}")
- sys.exit(-1)
-
-def conf_window(configuration):
- """Gui windows for configuring the app. If not configuration file specified when launched, this windows appears,
- otherwise, main_win is called.
-
- Arguments:
- configuration {Config} -- configuration instance for the application
-
- Keyword Arguments:
- controller {ControllerGazebo} -- controller part of the MVC of the application (default: {None})
- """
- try:
-
- from PyQt5.QtWidgets import QApplication
- from ui.gui.views_controller import ParentWindow, ViewsController
-
- app = QApplication(sys.argv)
- main_window = ParentWindow()
-
- views_controller = ViewsController(main_window, configuration)
- views_controller.show_title()
-
- main_window.show()
-
- app.exec_()
- except Exception:
- pass
-
-
-def main_win(configuration, controller, node):
- """shows the Qt main window of the application
-
- Arguments:
- configuration {Config} -- configuration instance for the application
- controller {ControllerGazebo} -- controller part of the MVC model of the application
- """
- try:
- from PyQt5.QtWidgets import QApplication
- from ui.gui.views_controller import ParentWindow, ViewsController
-
- app = QApplication(sys.argv)
- main_window = ParentWindow()
-
- views_controller = ViewsController(main_window, configuration, controller, node)
- views_controller.show_main_view(True)
-
- main_window.show()
-
- app.exec_()
- except Exception as e:
- logger.error(e)
-
-
-def main():
- """Main function for the app. Handles creation and destruction of every element of the application."""
-
- # Check and generate configuration
- config_data = check_args(sys.argv)
- node = init_node(config_data['ros_version']) # Initialize the ROS node shared by all the application
-
- for config in config_data['config']:
- app_configuration = Config(config)
-
- # Create controller of model-view
- controller = ControllerGazebo(node)
-
- # If there's no config, configure the app through the GUI
- if app_configuration.empty and config_data['gui']:
- conf_window(app_configuration)
-
- # Launch the simulation
- if app_configuration.current_world and not config_data['script']:
- logger.debug('Launching Simulation... please wait...')
- if config_data['random']:
- tmp_world_generator(app_configuration.current_world, app_configuration.stats_perfect_lap,
- app_configuration.real_time_update_rate, randomize=True,
- gui=True, launch=False)
- app_configuration.current_world = 'tmp_circuit.launch'
- environment.launch_env(app_configuration.current_world)
-
- if config_data['tui']:
- rows, columns = os.popen('stty size', 'r').read().split()
- if int(rows) < 34 and int(columns) < 115:
- logger.error(
- "Terminal window too small: {}x{}, please resize it to at least 35x115".format(rows, columns))
- sys.exit(1)
- else:
- t = TUI(controller)
- ttui = threading.Thread(target=t.run)
- ttui.start()
-
- if not config_data['script']:
- # Launch control
-
- pilot = PilotGazebo(node, app_configuration, controller, app_configuration.brain_path)
- pilot.daemon = True
- pilot.start()
- logger.info('Executing app')
-
- # If GUI specified, launch it. Otherwise don't
- if config_data['gui']:
- main_win(app_configuration, controller,node)
- else:
- pilot.join()
-
- # When window is closed or keypress for quit is detected, quit gracefully.
- logger.info('closing all processes...')
- pilot.kill_event.set()
- environment.close_ros_and_simulators()
- else:
- script_manager_gazebo.run_brains_worlds(app_configuration, controller, randomize=config_data['random'])
- logger.info('closing all processes...')
- environment.close_ros_and_simulators()
-
- logger.info('DONE! Bye, bye :)')
-
-
-if __name__ == '__main__':
- main()
- sys.exit(0)
+#!/usr/bin/env python
+""" Main module of the BehaviorMetrics application.
+
+This module is the responsible for initializing and destroying all the elements of the application when it is launched.
+
+This program is free software: you can redistribute it and/or modify it under
+the terms of the GNU General Public License as published by the Free Software
+Foundation, either version 3 of the License, or (at your option) any later
+version.
+This program is distributed in the hope that it will be useful, but WITHOUT
+ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
+You should have received a copy of the GNU General Public License along with
+this program. If not, see .
+"""
+
+import argparse
+import os
+import sys
+import threading
+
+from pilot_gazebo import PilotGazebo
+from ui.tui.main_view import TUI
+from utils import environment, script_manager_gazebo
+from utils.colors import Colors
+from utils.configuration import Config
+from utils.controller_gazebo import ControllerGazebo
+from utils.logger import logger
+from utils.tmp_world_generator import tmp_world_generator
+
+__author__ = 'fqez'
+__contributors__ = []
+__license__ = 'GPLv3'
+
+
+def check_args(argv):
+ """Function that handles argument checking and parsing.
+
+ Arguments:
+ argv {list} -- list of arguments from command line.
+
+ Returns:
+ dict -- dictionary with the detected configuration.
+ """
+ parser = argparse.ArgumentParser(description='Neural Behaviors Suite',
+ epilog='Enjoy the program! :)')
+
+ parser.add_argument('-c',
+ '--config',
+ type=str,
+ action='append',
+ required=True,
+ help='{}Path to the configuration file in YML format.{}'.format(
+ Colors.OKBLUE, Colors.ENDC))
+
+ group = parser.add_mutually_exclusive_group(required=True)
+ group.add_argument('-g',
+ '--gui',
+ action='store_true',
+ help='{}Load the GUI (Graphic User Interface). Requires PyQt5 installed{}'.format(
+ Colors.OKBLUE, Colors.ENDC))
+
+ group.add_argument('-t',
+ '--tui',
+ action='store_true',
+ help='{}Load the TUI (Terminal User Interface). Requires npyscreen installed{}'.format(
+ Colors.OKBLUE, Colors.ENDC))
+
+ group.add_argument('-s',
+ '--script',
+ action='store_true',
+ help='{}Run Behavior Metrics as script{}'.format(
+ Colors.OKBLUE, Colors.ENDC))
+
+ parser.add_argument('-r',
+ '--random',
+ action='store_true',
+ help='{}Run Behavior Metrics F1 with random spawning{}'.format(
+ Colors.OKBLUE, Colors.ENDC))
+
+ args = parser.parse_args()
+ # get ROS version from environment variable
+ ros_version = os.environ.get('ROS_VERSION', '2') # Default is ROS 2
+ if ros_version not in ['1', '2']:
+ logger.error('Invalid ROS_VERSION environment variable. Must be "1" or "2". Killing program...')
+ sys.exit(-1)
+
+ config_data = {'config': None, 'gui': None, 'tui': None, 'script': None, 'random': False, 'ros_version': int(ros_version)}
+ if args.config:
+ config_data['config'] = []
+ for config_file in args.config:
+ if not os.path.isfile(config_file):
+ parser.error('{}No such file {} {}'.format(Colors.FAIL, config_file, Colors.ENDC))
+
+ config_data['config'] = args.config
+
+ if args.gui:
+ config_data['gui'] = args.gui
+
+ if args.tui:
+ config_data['tui'] = args.tui
+
+ if args.script:
+ config_data['script'] = args.script
+
+ if args.random:
+ config_data['random'] = args.random
+
+ return config_data
+
+
+def init_node(ros_version):
+ """
+ Initializes the ROS node based on the selected version.
+
+ Arguments:
+ ros_version (str): The ROS version ("ros1" or "ros2").
+
+ Returns:
+ For ROS1: returns None (as rospy manages the node globally).
+ For ROS2: returns the created node.
+ """
+ if ros_version == 1:
+ import rospy
+ rospy.init_node('my_ros1_node')
+ return None # rospy maneja la instancia globalmente
+ elif ros_version == 2:
+ import rclpy
+ rclpy.init()
+ node = rclpy.create_node('my_ros2_node')
+ logger.info('ROS2 node initialized')
+ return node
+ else:
+ logger.error(f"Unsupported ROS version: {ros_version}")
+ sys.exit(-1)
+
+def conf_window(configuration):
+ """Gui windows for configuring the app. If not configuration file specified when launched, this windows appears,
+ otherwise, main_win is called.
+
+ Arguments:
+ configuration {Config} -- configuration instance for the application
+
+ Keyword Arguments:
+ controller {ControllerGazebo} -- controller part of the MVC of the application (default: {None})
+ """
+ try:
+
+ from PyQt5.QtWidgets import QApplication
+ from ui.gui.views_controller import ParentWindow, ViewsController
+
+ app = QApplication(sys.argv)
+ main_window = ParentWindow()
+
+ views_controller = ViewsController(main_window, configuration)
+ views_controller.show_title()
+
+ main_window.show()
+
+ app.exec_()
+ except Exception:
+ pass
+
+
+def main_win(configuration, controller, node):
+ """shows the Qt main window of the application
+
+ Arguments:
+ configuration {Config} -- configuration instance for the application
+ controller {ControllerGazebo} -- controller part of the MVC model of the application
+ """
+ try:
+ from PyQt5.QtWidgets import QApplication
+ from ui.gui.views_controller import ParentWindow, ViewsController
+
+ app = QApplication(sys.argv)
+ main_window = ParentWindow()
+
+ views_controller = ViewsController(main_window, configuration, controller, node)
+ views_controller.show_main_view(True)
+
+ main_window.show()
+
+ app.exec_()
+ except Exception as e:
+ logger.error(e)
+
+
+def main():
+ """Main function for the app. Handles creation and destruction of every element of the application."""
+
+ # Check and generate configuration
+ config_data = check_args(sys.argv)
+ node = init_node(config_data['ros_version']) # Initialize the ROS node shared by all the application
+
+ for config in config_data['config']:
+ app_configuration = Config(config)
+
+ # Create controller of model-view
+ controller = ControllerGazebo(node)
+
+ # If there's no config, configure the app through the GUI
+ if app_configuration.empty and config_data['gui']:
+ conf_window(app_configuration)
+
+ # Launch the simulation
+ if app_configuration.current_world and not config_data['script']:
+ logger.debug('Launching Simulation... please wait...')
+ if config_data['random']:
+ tmp_world_generator(app_configuration.current_world, app_configuration.stats_perfect_lap,
+ app_configuration.real_time_update_rate, randomize=True,
+ gui=True, launch=False)
+ app_configuration.current_world = 'tmp_circuit.launch'
+ environment.launch_env(app_configuration.current_world)
+
+ if config_data['tui']:
+ rows, columns = os.popen('stty size', 'r').read().split()
+ if int(rows) < 34 and int(columns) < 115:
+ logger.error(
+ "Terminal window too small: {}x{}, please resize it to at least 35x115".format(rows, columns))
+ sys.exit(1)
+ else:
+ t = TUI(controller)
+ ttui = threading.Thread(target=t.run)
+ ttui.start()
+
+ if not config_data['script']:
+ # Launch control
+
+ pilot = PilotGazebo(node, app_configuration, controller, app_configuration.brain_path)
+ pilot.daemon = True
+ pilot.start()
+ logger.info('Executing app')
+
+ # If GUI specified, launch it. Otherwise don't
+ if config_data['gui']:
+ main_win(app_configuration, controller,node)
+ else:
+ pilot.join()
+
+ # When window is closed or keypress for quit is detected, quit gracefully.
+ logger.info('closing all processes...')
+ pilot.kill_event.set()
+ environment.close_ros_and_simulators()
+ else:
+ script_manager_gazebo.run_brains_worlds(app_configuration, controller, randomize=config_data['random'])
+ logger.info('closing all processes...')
+ environment.close_ros_and_simulators()
+
+ logger.info('DONE! Bye, bye :)')
+
+
+if __name__ == '__main__':
+ main()
+ sys.exit(0)
diff --git a/behavior_metrics/models/CARLA/20221214-102705_deepestLSTMTinyPilotNet_CARLA_14_12_dataset_bird_eye_300_epochs_no_flip_3_output_both_directions_all_towns_PAPER_cp.h5 b/behavior_metrics/models/CARLA/20221214-102705_deepestLSTMTinyPilotNet_CARLA_14_12_dataset_bird_eye_300_epochs_no_flip_3_output_both_directions_all_towns_PAPER_cp.h5
deleted file mode 100644
index 8d73f5ee..00000000
Binary files a/behavior_metrics/models/CARLA/20221214-102705_deepestLSTMTinyPilotNet_CARLA_14_12_dataset_bird_eye_300_epochs_no_flip_3_output_both_directions_all_towns_PAPER_cp.h5 and /dev/null differ
diff --git a/behavior_metrics/models/CARLA/20230126-183457_deepestLSTMTinyPilotNet_CARLA_14_12_dataset_bird_eye_400_epochs_no_flip_3_output_both_directions_all_towns__less_learning_rate_PAPER_cp.h5 b/behavior_metrics/models/CARLA/20230126-183457_deepestLSTMTinyPilotNet_CARLA_14_12_dataset_bird_eye_400_epochs_no_flip_3_output_both_directions_all_towns__less_learning_rate_PAPER_cp.h5
deleted file mode 100644
index 1987eaf4..00000000
Binary files a/behavior_metrics/models/CARLA/20230126-183457_deepestLSTMTinyPilotNet_CARLA_14_12_dataset_bird_eye_400_epochs_no_flip_3_output_both_directions_all_towns__less_learning_rate_PAPER_cp.h5 and /dev/null differ
diff --git a/behavior_metrics/models/CARLA/pilotnet.h5 b/behavior_metrics/models/CARLA/pilotnet.h5
deleted file mode 100644
index 9cd17687..00000000
Binary files a/behavior_metrics/models/CARLA/pilotnet.h5 and /dev/null differ
diff --git a/behavior_metrics/models/CARLA/pilotnet_combined_control.pth b/behavior_metrics/models/CARLA/pilotnet_combined_control.pth
deleted file mode 100644
index d3ff6bd6..00000000
Binary files a/behavior_metrics/models/CARLA/pilotnet_combined_control.pth and /dev/null differ
diff --git a/behavior_metrics/models/CARLA/pilotnet_model.pth b/behavior_metrics/models/CARLA/pilotnet_model.pth
deleted file mode 100644
index 0fa3fd2e..00000000
Binary files a/behavior_metrics/models/CARLA/pilotnet_model.pth and /dev/null differ
diff --git a/behavior_metrics/models/CARLA/pilotnet_v8.0.pth b/behavior_metrics/models/CARLA/pilotnet_v8.0.pth
deleted file mode 100644
index 9149d3ad..00000000
Binary files a/behavior_metrics/models/CARLA/pilotnet_v8.0.pth and /dev/null differ
diff --git a/behavior_metrics/models/dir1 b/behavior_metrics/models/dir1
deleted file mode 120000
index 2d7a08bd..00000000
--- a/behavior_metrics/models/dir1
+++ /dev/null
@@ -1 +0,0 @@
-/dir1
\ No newline at end of file
diff --git a/behavior_metrics/models/dir1 b/behavior_metrics/models/dir1
new file mode 100644
index 00000000..2d7a08bd
--- /dev/null
+++ b/behavior_metrics/models/dir1
@@ -0,0 +1 @@
+/dir1
\ No newline at end of file
diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/variables/variables.data-00000-of-00001 b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/variables/variables.data-00000-of-00001
deleted file mode 100644
index 9ea5fd6c..00000000
Binary files a/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/ACTOR/variables/variables.data-00000-of-00001 and /dev/null differ
diff --git a/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/variables/variables.data-00000-of-00001 b/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/variables/variables.data-00000-of-00001
deleted file mode 100644
index 077d76f9..00000000
Binary files a/behavior_metrics/models/gazebo/rl_models/ddpg/20231104-003119_LAPCOMPLETEDCircuit-simple_States-sp5_Actions-continuous_BATCH_Rewards-followline_center_MaxReward-3096_Epoch-277/CRITIC/variables/variables.data-00000-of-00001 and /dev/null differ
diff --git a/behavior_metrics/perfect_bags/lap-many-curves.bag b/behavior_metrics/perfect_bags/lap-many-curves.bag
deleted file mode 100644
index dcfc47c7..00000000
Binary files a/behavior_metrics/perfect_bags/lap-many-curves.bag and /dev/null differ
diff --git a/behavior_metrics/perfect_bags/lap-montmelo.bag b/behavior_metrics/perfect_bags/lap-montmelo.bag
deleted file mode 100644
index b0e81045..00000000
Binary files a/behavior_metrics/perfect_bags/lap-montmelo.bag and /dev/null differ
diff --git a/behavior_metrics/perfect_bags/lap-montreal.bag b/behavior_metrics/perfect_bags/lap-montreal.bag
deleted file mode 100644
index b65ae25f..00000000
Binary files a/behavior_metrics/perfect_bags/lap-montreal.bag and /dev/null differ
diff --git a/behavior_metrics/perfect_bags/lap-nurburgring.bag b/behavior_metrics/perfect_bags/lap-nurburgring.bag
deleted file mode 100644
index abd2f11a..00000000
Binary files a/behavior_metrics/perfect_bags/lap-nurburgring.bag and /dev/null differ
diff --git a/behavior_metrics/perfect_bags/lap-simple-circuit.bag b/behavior_metrics/perfect_bags/lap-simple-circuit.bag
deleted file mode 100644
index e98e27f7..00000000
Binary files a/behavior_metrics/perfect_bags/lap-simple-circuit.bag and /dev/null differ
diff --git a/behavior_metrics/pilot_carla.py b/behavior_metrics/pilot_carla.py
index f33bbf7d..c5d85bb1 100644
--- a/behavior_metrics/pilot_carla.py
+++ b/behavior_metrics/pilot_carla.py
@@ -1,257 +1,257 @@
-#!/usr/bin/env python
-""" This module is responsible for handling the logic of the robot and its current brain.
-
-This program is free software: you can redistribute it and/or modify it under
-the terms of the GNU General Public License as published by the Free Software
-Foundation, either version 3 of the License, or (at your option) any later
-version.
-This program is distributed in the hope that it will be useful, but WITHOUT
-ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
-FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
-You should have received a copy of the GNU General Public License along with
-this program. If not, see .
-"""
-
-import threading
-import time
-# import rospy
-import subprocess
-import os
-
-from datetime import datetime
-from brains.brains_handler import Brains
-from robot.actuators import Actuators
-from robot.sensors import Sensors
-from utils.logger import logger
-from utils.constants import MIN_EXPERIMENT_PERCENTAGE_COMPLETED, ROOT_PATH
-
-ros_version = os.environ.get('ROS_VERSION', '2')
-if ros_version == '2':
- import rclpy
- from rclpy.node import Node
-else:
- import rospy
-
-from rosgraph_msgs.msg import Clock
-from carla_msgs.msg import CarlaControl
-
-import numpy as np
-
-__author__ = 'fqez'
-__contributors__ = []
-__license__ = 'GPLv3'
-
-
-class PilotCarla(threading.Thread):
- """This class handles the robot and its brain.
-
- This class called PilotCarla that handles the initialization of the robot sensors and actuators and the
- brain that will control the robot. The main logic consists of an infinite loop called every 60 milliseconds that
- invoke an action from the brain.
-
- Attributes:
- controller {utils.controller.Controller} -- Controller instance of the MVC of the application
- configuration {utils.configuration.Config} -- Configuration instance of the application
- sensors {robot.sensors.Sensors} -- Sensors instance of the robot
- actuators {robot.actuators.Actuators} -- Actuators instance of the robot
- brains {brains.brains_handler.Brains} -- Brains controller instance
- """
-
- def __init__(self, node: Node, configuration, controller, brain_path, experiment_model=None):
- """Constructor of the pilot class
-
- Arguments:
- configuration {utils.configuration.Config} -- Configuration instance of the application
- controller {utils.controller.Controller} -- Controller instance of the MVC of the application
- """
- self.node = node
- self.stop_event = threading.Event()
- self.kill_event = threading.Event()
- threading.Thread.__init__(self, args=self.stop_event)
-
- self.controller = controller
- self.controller.set_pilot(self)
- self.configuration = configuration
- # self.stop_event = threading.Event()
- # self.kill_event = threading.Event()
- # threading.Thread.__init__(self, args=self.stop_event)
- self.brain_path = brain_path
- self.robot_type = self.brain_path.split("/")[-2]
- self.sensors = None
- self.actuators = None
- self.brains = None
- self.experiment_model = experiment_model
- self.initialize_robot()
- self.pose3d = self.sensors.get_pose3d('pose3d_0')
- self.start_pose = np.array([self.pose3d.getPose3d().x, self.pose3d.getPose3d().y])
- self.previous = datetime.now()
- self.checkpoints = []
- self.metrics = {}
- self.checkpoint_save = False
- self.max_distance = 0.5
- self.execution_completed = False
- self.stats_thread = threading.Thread(target=self.track_stats)
- self.stats_thread.start()
- self.ros_clock_time = 0
- self.real_time_factor = 0
- self.brain_iterations_real_time = []
- self.brain_iterations_simulated_time = []
- self.real_time_factors = []
- self.real_time_update_rate = 1000
- self.pilot_start_time = 0
- self.time_cycle = self.configuration.pilot_time_cycle
- self.async_mode = self.configuration.async_mode
- self.waypoint_publisher_path = self.configuration.waypoint_publisher_path
-
- def __wait_carla(self):
- """Wait for simulator to be initialized"""
-
- self.stop_event.set()
-
- def initialize_robot(self):
- """Initialize robot interfaces (sensors and actuators) and its brain from configuration"""
- self.stop_interfaces()
- self.actuators = Actuators(self.configuration.actuators, self.node)
- self.sensors = Sensors(self.configuration.sensors, self.node)
- if self.experiment_model:
- self.brains = Brains(self.sensors, self.actuators, self.brain_path, self.controller,
- self.experiment_model, self.configuration.brain_kwargs)
- else:
- self.brains = Brains(self.sensors, self.actuators, self.brain_path, self.controller,
- config=self.configuration.brain_kwargs)
- self.__wait_carla()
-
- def stop_interfaces(self):
- """Function that kill the current interfaces of the robot. For reloading purposes."""
- if self.sensors:
- self.sensors.kill()
- if self.actuators:
- self.actuators.kill()
- pass
-
- def run(self):
- """Main loop of the class. Calls a brain action every self.time_cycle"""
- "TODO: cleanup measure of ips"
- self.brain_iterations_simulated_time = []
- self.real_time_factors = []
- self.sensors.get_camera('camera_0').total_frames = 0
- self.pilot_start_time = time.time()
-
- if ros_version == '2':
- control_pub = self.node.create_publisher(CarlaControl, '/carla/control', 1)
- else:
- control_pub = rospy.Publisher('/carla/control', CarlaControl, queue_size=1)
-
- control_command = CarlaControl()
- control_command.command = 1 # PAUSE
- control_pub.publish(control_command)
-
- self.waypoint_publisher = None
- while not self.kill_event.is_set():
- if not self.stop_event.is_set():
- if self.waypoint_publisher is None and self.waypoint_publisher_path is not None:
- if ros_version == '2':
- self.waypoint_publisher = subprocess.Popen(["ros2", "launch", ROOT_PATH + '/' + self.waypoint_publisher_path])
- else:
- self.waypoint_publisher = subprocess.Popen(["roslaunch", ROOT_PATH + '/' + self.waypoint_publisher_path])
-
- if ros_version == '2':
- if not hasattr(self, 'control_pub'):
- # control_pub = self.controller.create_publisher(CarlaControl, '/carla/control', 1)
- self.control_pub = self.node.create_publisher(CarlaControl, '/carla/control', 1)
- control_command = CarlaControl()
- if self.async_mode:
- control_command.command = 0 # PLAY
- else:
- control_command.command = 2 # STEP_ONCE
- self.control_pub.publish(control_command)
- else:
- # self.control_pub = rospy.Publisher('/carla/control', CarlaControl, queue_size=1)
- control_command = CarlaControl()
-
- if self.async_mode:
- control_command.command = 0 # PLAY
- else:
- control_command.command = 2 # STEP_ONCE
- self.control_pub.publish(control_command)
-
- start_time = datetime.now()
- start_time_ros = self.ros_clock_time
- self.execution_completed = False
- try:
- self.brains.active_brain.execute()
- except AttributeError as e:
- logger.warning('No Brain selected')
- logger.error(e)
- except Exception as ex:
- logger.warning(type(ex).__name__)
- logger.warning(ex)
- logger.warning('ERROR Pilot Carla!')
- self.stop()
- self.kill()
- os._exit(-1)
-
- dt = datetime.now() - start_time
- ms = (dt.days * 24 * 60 * 60 + dt.seconds) * 1000 + dt.microseconds / 1000.0
- self.brain_iterations_real_time.append(ms / 1000)
- if ms < self.time_cycle:
- time.sleep((self.time_cycle - ms) / 1000.0)
- self.real_time_factors.append(self.real_time_factor)
- self.brain_iterations_simulated_time.append(self.ros_clock_time - start_time_ros)
- if not self.async_mode:
- self.controller.world.tick()
- self.execution_completed = True
- self.kill()
- logger.info('Pilot: pilot killed.')
-
- def stop(self):
- """Pause the main loop"""
-
- self.stop_event.set()
-
- def play(self):
- """Resume the main loop."""
-
- if self.is_alive():
- self.stop_event.clear()
- else:
- self.start()
-
- def kill(self):
- """Destroy the main loop. For exiting"""
- self.stop_interfaces()
- self.actuators.kill()
- self.kill_event.set()
-
- def reload_brain(self, brain_path, model=None):
- """Reload a brain specified by brain_path
-
- This function is useful if one wants to change the environment of the robot (simulated world).
-
- Arguments:
- brain_path {str} -- Path to the brain module to load.
- """
- self.brains.load_brain(brain_path, model=model)
-
- def finish_line(self):
- pose = self.pose3d.getPose3d()
- current_point = np.array([pose.x, pose.y])
-
- dist = (self.start_pose - current_point) ** 2
- dist = np.sum(dist, axis=0)
- dist = np.sqrt(dist)
- if dist < self.max_distance:
- return True
- return False
-
- def clock_callback(self, clock_data):
- if ros_version == '2':
- self.ros_clock_time = clock_data.clock.sec + clock_data.clock.nanosec * 1e-9
- else:
- self.ros_clock_time = clock_data.clock.to_sec()
-
- def track_stats(self):
- if ros_version == '2':
- self.clock_subscriber = self.node.create_subscription(Clock, '/clock', self.clock_callback, 1)
- else:
- self.clock_subscriber = rospy.Subscriber("/clock", Clock, self.clock_callback)
+#!/usr/bin/env python
+""" This module is responsible for handling the logic of the robot and its current brain.
+
+This program is free software: you can redistribute it and/or modify it under
+the terms of the GNU General Public License as published by the Free Software
+Foundation, either version 3 of the License, or (at your option) any later
+version.
+This program is distributed in the hope that it will be useful, but WITHOUT
+ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
+You should have received a copy of the GNU General Public License along with
+this program. If not, see .
+"""
+
+import threading
+import time
+# import rospy
+import subprocess
+import os
+
+from datetime import datetime
+from brains.brains_handler import Brains
+from robot.actuators import Actuators
+from robot.sensors import Sensors
+from utils.logger import logger
+from utils.constants import MIN_EXPERIMENT_PERCENTAGE_COMPLETED, ROOT_PATH
+
+ros_version = os.environ.get('ROS_VERSION', '2')
+if ros_version == '2':
+ import rclpy
+ from rclpy.node import Node
+else:
+ import rospy
+
+from rosgraph_msgs.msg import Clock
+from carla_msgs.msg import CarlaControl
+
+import numpy as np
+
+__author__ = 'fqez'
+__contributors__ = []
+__license__ = 'GPLv3'
+
+
+class PilotCarla(threading.Thread):
+ """This class handles the robot and its brain.
+
+ This class called PilotCarla that handles the initialization of the robot sensors and actuators and the
+ brain that will control the robot. The main logic consists of an infinite loop called every 60 milliseconds that
+ invoke an action from the brain.
+
+ Attributes:
+ controller {utils.controller.Controller} -- Controller instance of the MVC of the application
+ configuration {utils.configuration.Config} -- Configuration instance of the application
+ sensors {robot.sensors.Sensors} -- Sensors instance of the robot
+ actuators {robot.actuators.Actuators} -- Actuators instance of the robot
+ brains {brains.brains_handler.Brains} -- Brains controller instance
+ """
+
+ def __init__(self, node: Node, configuration, controller, brain_path, experiment_model=None):
+ """Constructor of the pilot class
+
+ Arguments:
+ configuration {utils.configuration.Config} -- Configuration instance of the application
+ controller {utils.controller.Controller} -- Controller instance of the MVC of the application
+ """
+ self.node = node
+ self.stop_event = threading.Event()
+ self.kill_event = threading.Event()
+ threading.Thread.__init__(self, args=self.stop_event)
+
+ self.controller = controller
+ self.controller.set_pilot(self)
+ self.configuration = configuration
+ # self.stop_event = threading.Event()
+ # self.kill_event = threading.Event()
+ # threading.Thread.__init__(self, args=self.stop_event)
+ self.brain_path = brain_path
+ self.robot_type = self.brain_path.split("/")[-2]
+ self.sensors = None
+ self.actuators = None
+ self.brains = None
+ self.experiment_model = experiment_model
+ self.initialize_robot()
+ self.pose3d = self.sensors.get_pose3d('pose3d_0')
+ self.start_pose = np.array([self.pose3d.getPose3d().x, self.pose3d.getPose3d().y])
+ self.previous = datetime.now()
+ self.checkpoints = []
+ self.metrics = {}
+ self.checkpoint_save = False
+ self.max_distance = 0.5
+ self.execution_completed = False
+ self.stats_thread = threading.Thread(target=self.track_stats)
+ self.stats_thread.start()
+ self.ros_clock_time = 0
+ self.real_time_factor = 0
+ self.brain_iterations_real_time = []
+ self.brain_iterations_simulated_time = []
+ self.real_time_factors = []
+ self.real_time_update_rate = 1000
+ self.pilot_start_time = 0
+ self.time_cycle = self.configuration.pilot_time_cycle
+ self.async_mode = self.configuration.async_mode
+ self.waypoint_publisher_path = self.configuration.waypoint_publisher_path
+
+ def __wait_carla(self):
+ """Wait for simulator to be initialized"""
+
+ self.stop_event.set()
+
+ def initialize_robot(self):
+ """Initialize robot interfaces (sensors and actuators) and its brain from configuration"""
+ self.stop_interfaces()
+ self.actuators = Actuators(self.configuration.actuators, self.node)
+ self.sensors = Sensors(self.configuration.sensors, self.node)
+ if self.experiment_model:
+ self.brains = Brains(self.sensors, self.actuators, self.brain_path, self.controller,
+ self.experiment_model, self.configuration.brain_kwargs)
+ else:
+ self.brains = Brains(self.sensors, self.actuators, self.brain_path, self.controller,
+ config=self.configuration.brain_kwargs)
+ self.__wait_carla()
+
+ def stop_interfaces(self):
+ """Function that kill the current interfaces of the robot. For reloading purposes."""
+ if self.sensors:
+ self.sensors.kill()
+ if self.actuators:
+ self.actuators.kill()
+ pass
+
+ def run(self):
+ """Main loop of the class. Calls a brain action every self.time_cycle"""
+ "TODO: cleanup measure of ips"
+ self.brain_iterations_simulated_time = []
+ self.real_time_factors = []
+ self.sensors.get_camera('camera_0').total_frames = 0
+ self.pilot_start_time = time.time()
+
+ if ros_version == '2':
+ control_pub = self.node.create_publisher(CarlaControl, '/carla/control', 1)
+ else:
+ control_pub = rospy.Publisher('/carla/control', CarlaControl, queue_size=1)
+
+ control_command = CarlaControl()
+ control_command.command = 1 # PAUSE
+ control_pub.publish(control_command)
+
+ self.waypoint_publisher = None
+ while not self.kill_event.is_set():
+ if not self.stop_event.is_set():
+ if self.waypoint_publisher is None and self.waypoint_publisher_path is not None:
+ if ros_version == '2':
+ self.waypoint_publisher = subprocess.Popen(["ros2", "launch", ROOT_PATH + '/' + self.waypoint_publisher_path])
+ else:
+ self.waypoint_publisher = subprocess.Popen(["roslaunch", ROOT_PATH + '/' + self.waypoint_publisher_path])
+
+ if ros_version == '2':
+ if not hasattr(self, 'control_pub'):
+ # control_pub = self.controller.create_publisher(CarlaControl, '/carla/control', 1)
+ self.control_pub = self.node.create_publisher(CarlaControl, '/carla/control', 1)
+ control_command = CarlaControl()
+ if self.async_mode:
+ control_command.command = 0 # PLAY
+ else:
+ control_command.command = 2 # STEP_ONCE
+ self.control_pub.publish(control_command)
+ else:
+ # self.control_pub = rospy.Publisher('/carla/control', CarlaControl, queue_size=1)
+ control_command = CarlaControl()
+
+ if self.async_mode:
+ control_command.command = 0 # PLAY
+ else:
+ control_command.command = 2 # STEP_ONCE
+ self.control_pub.publish(control_command)
+
+ start_time = datetime.now()
+ start_time_ros = self.ros_clock_time
+ self.execution_completed = False
+ try:
+ self.brains.active_brain.execute()
+ except AttributeError as e:
+ logger.warning('No Brain selected')
+ logger.error(e)
+ except Exception as ex:
+ logger.warning(type(ex).__name__)
+ logger.warning(ex)
+ logger.warning('ERROR Pilot Carla!')
+ self.stop()
+ self.kill()
+ os._exit(-1)
+
+ dt = datetime.now() - start_time
+ ms = (dt.days * 24 * 60 * 60 + dt.seconds) * 1000 + dt.microseconds / 1000.0
+ self.brain_iterations_real_time.append(ms / 1000)
+ if ms < self.time_cycle:
+ time.sleep((self.time_cycle - ms) / 1000.0)
+ self.real_time_factors.append(self.real_time_factor)
+ self.brain_iterations_simulated_time.append(self.ros_clock_time - start_time_ros)
+ if not self.async_mode:
+ self.controller.world.tick()
+ self.execution_completed = True
+ self.kill()
+ logger.info('Pilot: pilot killed.')
+
+ def stop(self):
+ """Pause the main loop"""
+
+ self.stop_event.set()
+
+ def play(self):
+ """Resume the main loop."""
+
+ if self.is_alive():
+ self.stop_event.clear()
+ else:
+ self.start()
+
+ def kill(self):
+ """Destroy the main loop. For exiting"""
+ self.stop_interfaces()
+ self.actuators.kill()
+ self.kill_event.set()
+
+ def reload_brain(self, brain_path, model=None):
+ """Reload a brain specified by brain_path
+
+ This function is useful if one wants to change the environment of the robot (simulated world).
+
+ Arguments:
+ brain_path {str} -- Path to the brain module to load.
+ """
+ self.brains.load_brain(brain_path, model=model)
+
+ def finish_line(self):
+ pose = self.pose3d.getPose3d()
+ current_point = np.array([pose.x, pose.y])
+
+ dist = (self.start_pose - current_point) ** 2
+ dist = np.sum(dist, axis=0)
+ dist = np.sqrt(dist)
+ if dist < self.max_distance:
+ return True
+ return False
+
+ def clock_callback(self, clock_data):
+ if ros_version == '2':
+ self.ros_clock_time = clock_data.clock.sec + clock_data.clock.nanosec * 1e-9
+ else:
+ self.ros_clock_time = clock_data.clock.to_sec()
+
+ def track_stats(self):
+ if ros_version == '2':
+ self.clock_subscriber = self.node.create_subscription(Clock, '/clock', self.clock_callback, 1)
+ else:
+ self.clock_subscriber = rospy.Subscriber("/clock", Clock, self.clock_callback)
diff --git a/behavior_metrics/pilot_gazebo.py b/behavior_metrics/pilot_gazebo.py
index 23d18735..8ef34020 100644
--- a/behavior_metrics/pilot_gazebo.py
+++ b/behavior_metrics/pilot_gazebo.py
@@ -1,307 +1,307 @@
-#!/usr/bin/env python
-""" This module is responsible for handling the logic of the robot and its current brain.
-
-This program is free software: you can redistribute it and/or modify it under
-the terms of the GNU General Public License as published by the Free Software
-Foundation, either version 3 of the License, or (at your option) any later
-version.
-This program is distributed in the hope that it will be useful, but WITHOUT
-ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
-FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
-You should have received a copy of the GNU General Public License along with
-this program. If not, see .
-"""
-
-import os
-import threading
-import threading
-import time
-
-import subprocess
-import traceback
-
-from datetime import datetime
-from brains.brains_handler import Brains
-from robot.actuators import Actuators
-from robot.sensors import Sensors
-from utils.logger import logger
-from utils.constants import MIN_EXPERIMENT_PERCENTAGE_COMPLETED
-from rosgraph_msgs.msg import Clock
-
-import numpy as np
-
-ros_version = os.environ.get('ROS_VERSION', '2')
-if ros_version == '2':
- import rclpy
- from rclpy.node import Node
-else:
- import rospy
-
-__author__ = 'fqez'
-__contributors__ = []
-__license__ = 'GPLv3'
-
-
-class PilotGazebo(threading.Thread):
- """This class handles the robot and its brain.
-
- This class called Pilot that handles the initialization of the robot sensors and actuators and the
- brain that will control the robot. The main logic consists of an infinite loop called every 60 milliseconds that
- invoke an action from the brain.
-
- Attributes:
- controller {utils.controller.Controller} -- Controller instance of the MVC of the application
- configuration {utils.configuration.Config} -- Configuration instance of the application
- sensors {robot.sensors.Sensors} -- Sensors instance of the robot
- actuators {robot.actuators.Actuators} -- Actuators instance of the robot
- brains {brains.brains_handler.Brains} -- Brains controller instance
- """
-
- def __init__(self, node, configuration, controller, brain_path):
- """Constructor of the pilot class
-
- Arguments:
- configuration {utils.configuration.Config} -- Configuration instance of the application
- controller {utils.controller.Controller} -- Controller instance of the MVC of the application
- """
- self.node = node
- self.controller = controller
- self.controller.set_pilot(self)
- self.configuration = configuration
- self.stop_event = threading.Event()
- self.kill_event = threading.Event()
- threading.Thread.__init__(self, args=self.stop_event)
- self.brain_path = brain_path
- self.robot_type = self.brain_path.split("/")[-2]
- self.sensors = None
- self.actuators = None
- self.brains = None
- self.initialize_robot()
- if self.robot_type == 'drone':
- self.pose3d = self.brains.active_brain.getPose3d()
- self.start_pose = np.array([self.pose3d[0], self.pose3d[1]])
- else:
- self.pose3d = self.sensors.get_pose3d('pose3d_0')
- self.start_pose = np.array([self.pose3d.getPose3d().x, self.pose3d.getPose3d().y])
- self.previous = datetime.now()
- self.checkpoints = []
- self.metrics = {}
- self.checkpoint_save = False
- self.max_distance = 0.5
- self.execution_completed = False
- self.stats_thread = threading.Thread(target=self.track_stats)
- self.stats_thread.start()
- self.ros_clock_time = 0
- self.real_time_factor = 0
- self.brain_iterations_real_time = []
- self.brain_iterations_simulated_time = []
- self.real_time_factors = []
- self.real_time_update_rate = 1000
- self.pilot_start_time = 0
- self.time_cycle = self.configuration.pilot_time_cycle
-
- def __wait_gazebo(self):
- """Wait for gazebo to be initialized"""
-
- self.stop_event.set()
-
-
- def initialize_robot(self):
- """Initialize robot interfaces (sensors and actuators) and its brain from configuration"""
- self.stop_interfaces()
-
- if self.robot_type != 'drone':
- self.actuators = Actuators(self.configuration.actuators,self.node)
- self.sensors = Sensors(self.configuration.sensors,self.node)
- if hasattr(self.configuration, 'experiment_model') and type(self.configuration.experiment_model) != list:
- self.brains = Brains(self.sensors, self.actuators, self.brain_path, self.controller,
- self.configuration.experiment_model, self.configuration.brain_kwargs)
- else:
- self.brains = Brains(self.sensors, self.actuators, self.brain_path, self.controller,
- config=self.configuration.brain_kwargs)
- self.__wait_gazebo()
-
- def stop_interfaces(self):
- """Function that kill the current interfaces of the robot. For reloading purposes."""
- if self.sensors:
- self.sensors.kill()
- if self.actuators:
- self.actuators.kill()
- pass
-
- def run(self):
- """Main loop of the class. Calls a brain action every self.time_cycle"""
- "TODO: cleanup measure of ips"
- it = 0
- ss = time.time()
- self.brain_iterations_real_time = []
- self.brain_iterations_simulated_time = []
- self.real_time_factors = []
- self.sensors.get_camera('camera_0').total_frames = 0
- self.pilot_start_time = time.time()
- while not self.kill_event.is_set():
- if not self.stop_event.is_set():
- start_time = datetime.now()
- start_time_ros = self.ros_clock_time
- self.execution_completed = False
- try:
- self.brains.active_brain.execute()
- except AttributeError as e:
- traceback.print_exc()
- logger.warning('No Brain selected')
- logger.error(e)
-
- dt = datetime.now() - start_time
- ms = (dt.days * 24 * 60 * 60 + dt.seconds) * 1000 + dt.microseconds / 1000.0
- self.brain_iterations_real_time.append(ms / 1000)
- elapsed = time.time() - ss
- if elapsed < 1:
- it += 1
- else:
- ss = time.time()
- it = 0
- if ms < self.time_cycle:
- time.sleep((self.time_cycle - ms) / 1000.0)
- self.real_time_factors.append(self.real_time_factor)
- self.brain_iterations_simulated_time.append(self.ros_clock_time - start_time_ros)
- self.execution_completed = True
- if ros_version == '2':
- self.node.destroy_subscription(self.clock_subscriber)
- else:
- self.clock_subscriber.unregister()
- self.stats_process.terminate()
- poll = self.stats_process.poll()
- while poll is None:
- time.sleep(1)
- poll = self.stats_process.poll()
- self.kill()
- logger.info('Pilot: pilot killed.')
-
- def stop(self):
- """Pause the main loop"""
-
- self.stop_event.set()
-
- def play(self):
- """Resume the main loop."""
-
- if self.is_alive():
- self.stop_event.clear()
- else:
- self.start()
-
- def kill(self):
- """Destroy the main loop. For exiting"""
- self.stop_interfaces()
- self.actuators.kill()
- self.kill_event.set()
-
- def reload_brain(self, brain_path, model=None):
- """Reload a brain specified by brain_path
-
- This function is useful if one wants to change the environment of the robot (simulated world).
-
- Arguments:
- brain_path {str} -- Path to the brain module to load.
- """
- self.brains.load_brain(brain_path, model=model)
-
- def finish_line(self):
- pose = self.pose3d.getPose3d()
- current_point = np.array([pose.x, pose.y])
-
- dist = (self.start_pose - current_point) ** 2
- dist = np.sum(dist, axis=0)
- dist = np.sqrt(dist)
- if dist < self.max_distance:
- return True
- return False
-
- def calculate_metrics(self, experiment_metrics):
- if hasattr(self.brains.active_brain, 'inference_times'):
- self.brains.active_brain.inference_times = self.brains.active_brain.inference_times[10:-10]
- mean_inference_time = sum(self.brains.active_brain.inference_times) / len(self.brains.active_brain.inference_times)
- frame_rate = self.sensors.get_camera('camera_0').total_frames / experiment_metrics['experiment_total_simulated_time']
- gpu_inference = self.brains.active_brain.gpu_inference
- real_time_update_rate = self.real_time_update_rate
- first_image = self.brains.active_brain.first_image
- logger.info('* Mean network inference time ---> ' + str(mean_inference_time) + 's')
- logger.info('* Frame rate ---> ' + str(frame_rate) + 'fps')
- else:
- mean_inference_time = 0
- frame_rate = 0
- gpu_inference = False
- real_time_update_rate = self.real_time_update_rate
- first_image = None
- logger.info('No deep learning based brain')
- if self.brain_iterations_real_time and self.brain_iterations_simulated_time and self.brain_iterations_simulated_time:
- mean_brain_iterations_simulated_time = sum(self.brain_iterations_simulated_time) / len(self.brain_iterations_simulated_time)
- real_time_factor = sum(self.real_time_factors) / len(self.real_time_factors)
- brain_iterations_frequency_simulated_time = 1 / mean_brain_iterations_simulated_time
- target_brain_iterations_simulated_time = 1000 / self.time_cycle / round(real_time_factor, 2)
- mean_brain_iterations_real_time = sum(self.brain_iterations_real_time) / len(self.brain_iterations_real_time)
- brain_iterations_frequency_real_time = 1 / mean_brain_iterations_real_time
- target_brain_iterations_real_time = 1 / (self.time_cycle / 1000)
- suddenness_distance = sum(self.brains.active_brain.suddenness_distance) / len(self.brains.active_brain.suddenness_distance)
- else:
- mean_brain_iterations_real_time = 0
- mean_brain_iterations_simulated_time = 0
- real_time_factor = 0
- brain_iterations_frequency_simulated_time = 0
- target_brain_iterations_simulated_time = 0
- brain_iterations_frequency_real_time = 0
- target_brain_iterations_real_time = 0
- suddenness_distance = 0
- logger.info('* Brain iterations frequency simulated time ---> ' + str(brain_iterations_frequency_simulated_time) + 'it/s')
- logger.info('* Target brain iterations simulated time -> ' + str(target_brain_iterations_simulated_time) + 'it/s')
- logger.info('* Mean brain iterations real time ---> ' + str(mean_brain_iterations_real_time) + 's')
- logger.info('* Brain iterations frequency real time ---> ' + str(brain_iterations_frequency_real_time) + 'it/s')
- logger.info('* Target brain iterations real time -> ' + str(target_brain_iterations_real_time) + 'it/s')
- logger.info('* Mean brain iterations simulated time ---> ' + str(mean_brain_iterations_simulated_time) + 's')
- logger.info('* Mean brain iterations simulated time ---> ' + str(real_time_factor))
- logger.info('* Real time update rate ---> ' + str(real_time_update_rate))
- logger.info('* GPU inference ---> ' + str(gpu_inference))
- logger.info('* Suddenness distance ---> ' + str(suddenness_distance))
- logger.info('* Saving experiment ---> ' + str(hasattr(self.controller, 'experiment_metrics_filename')))
- experiment_metrics['brain_iterations_frequency_simulated_time'] = brain_iterations_frequency_simulated_time
- experiment_metrics['target_brain_iterations_simulated_time'] = target_brain_iterations_simulated_time
- experiment_metrics['mean_brain_iterations_real_time'] = mean_brain_iterations_real_time
- experiment_metrics['brain_iterations_frequency_real_time'] = brain_iterations_frequency_real_time
- experiment_metrics['target_brain_iterations_real_time'] = target_brain_iterations_real_time
- experiment_metrics['mean_inference_time'] = mean_inference_time
- experiment_metrics['frame_rate'] = frame_rate
- experiment_metrics['gpu_inference'] = gpu_inference
- experiment_metrics['mean_brain_iterations_simulated_time'] = mean_brain_iterations_simulated_time
- experiment_metrics['real_time_factor'] = real_time_factor
- experiment_metrics['real_time_update_rate'] = real_time_update_rate
- experiment_metrics['suddenness_distance'] = suddenness_distance
- logger.info('Saving metrics to ROS bag')
- return experiment_metrics, first_image
-
- def clock_callback(self, clock_data):
- self.ros_clock_time = clock_data.clock.to_sec()
-
- def track_stats(self):
- args = ["gz", "stats", "-p"]
- # Prints gz statistics. "-p": Output comma-separated values containing-
- # real-time factor (percent), simtime (sec), realtime (sec), paused (T or F)
- self.stats_process = subprocess.Popen(args, stdout=subprocess.PIPE)
- # bufsize=1 enables line-bufferred mode (the input buffer is flushed
- # automatically on newlines if you would write to process.stdin )
- poll = self.stats_process.poll()
- while poll is not None:
- time.sleep(1)
- poll = self.stats_process.poll()
-
- if ros_version == '2':
- self.clock_subscriber = self.node.create_subscription(Clock, "/clock", self.clock_callback,1)
- else:
- self.clock_subscriber = rospy.Subscriber("/clock", Clock, self.clock_callback)
-
- with self.stats_process.stdout:
- for line in iter(self.stats_process.stdout.readline, b''):
- stats_list = [x.strip() for x in line.split(b',')]
- try:
- self.real_time_factor = float(stats_list[0].decode("utf-8"))
- except Exception as ex:
- self.real_time_factor = 0
+#!/usr/bin/env python
+""" This module is responsible for handling the logic of the robot and its current brain.
+
+This program is free software: you can redistribute it and/or modify it under
+the terms of the GNU General Public License as published by the Free Software
+Foundation, either version 3 of the License, or (at your option) any later
+version.
+This program is distributed in the hope that it will be useful, but WITHOUT
+ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
+You should have received a copy of the GNU General Public License along with
+this program. If not, see .
+"""
+
+import os
+import threading
+import threading
+import time
+
+import subprocess
+import traceback
+
+from datetime import datetime
+from brains.brains_handler import Brains
+from robot.actuators import Actuators
+from robot.sensors import Sensors
+from utils.logger import logger
+from utils.constants import MIN_EXPERIMENT_PERCENTAGE_COMPLETED
+from rosgraph_msgs.msg import Clock
+
+import numpy as np
+
+ros_version = os.environ.get('ROS_VERSION', '2')
+if ros_version == '2':
+ import rclpy
+ from rclpy.node import Node
+else:
+ import rospy
+
+__author__ = 'fqez'
+__contributors__ = []
+__license__ = 'GPLv3'
+
+
+class PilotGazebo(threading.Thread):
+ """This class handles the robot and its brain.
+
+ This class called Pilot that handles the initialization of the robot sensors and actuators and the
+ brain that will control the robot. The main logic consists of an infinite loop called every 60 milliseconds that
+ invoke an action from the brain.
+
+ Attributes:
+ controller {utils.controller.Controller} -- Controller instance of the MVC of the application
+ configuration {utils.configuration.Config} -- Configuration instance of the application
+ sensors {robot.sensors.Sensors} -- Sensors instance of the robot
+ actuators {robot.actuators.Actuators} -- Actuators instance of the robot
+ brains {brains.brains_handler.Brains} -- Brains controller instance
+ """
+
+ def __init__(self, node, configuration, controller, brain_path):
+ """Constructor of the pilot class
+
+ Arguments:
+ configuration {utils.configuration.Config} -- Configuration instance of the application
+ controller {utils.controller.Controller} -- Controller instance of the MVC of the application
+ """
+ self.node = node
+ self.controller = controller
+ self.controller.set_pilot(self)
+ self.configuration = configuration
+ self.stop_event = threading.Event()
+ self.kill_event = threading.Event()
+ threading.Thread.__init__(self, args=self.stop_event)
+ self.brain_path = brain_path
+ self.robot_type = self.brain_path.split("/")[-2]
+ self.sensors = None
+ self.actuators = None
+ self.brains = None
+ self.initialize_robot()
+ if self.robot_type == 'drone':
+ self.pose3d = self.brains.active_brain.getPose3d()
+ self.start_pose = np.array([self.pose3d[0], self.pose3d[1]])
+ else:
+ self.pose3d = self.sensors.get_pose3d('pose3d_0')
+ self.start_pose = np.array([self.pose3d.getPose3d().x, self.pose3d.getPose3d().y])
+ self.previous = datetime.now()
+ self.checkpoints = []
+ self.metrics = {}
+ self.checkpoint_save = False
+ self.max_distance = 0.5
+ self.execution_completed = False
+ self.stats_thread = threading.Thread(target=self.track_stats)
+ self.stats_thread.start()
+ self.ros_clock_time = 0
+ self.real_time_factor = 0
+ self.brain_iterations_real_time = []
+ self.brain_iterations_simulated_time = []
+ self.real_time_factors = []
+ self.real_time_update_rate = 1000
+ self.pilot_start_time = 0
+ self.time_cycle = self.configuration.pilot_time_cycle
+
+ def __wait_gazebo(self):
+ """Wait for gazebo to be initialized"""
+
+ self.stop_event.set()
+
+
+ def initialize_robot(self):
+ """Initialize robot interfaces (sensors and actuators) and its brain from configuration"""
+ self.stop_interfaces()
+
+ if self.robot_type != 'drone':
+ self.actuators = Actuators(self.configuration.actuators,self.node)
+ self.sensors = Sensors(self.configuration.sensors,self.node)
+ if hasattr(self.configuration, 'experiment_model') and type(self.configuration.experiment_model) != list:
+ self.brains = Brains(self.sensors, self.actuators, self.brain_path, self.controller,
+ self.configuration.experiment_model, self.configuration.brain_kwargs)
+ else:
+ self.brains = Brains(self.sensors, self.actuators, self.brain_path, self.controller,
+ config=self.configuration.brain_kwargs)
+ self.__wait_gazebo()
+
+ def stop_interfaces(self):
+ """Function that kill the current interfaces of the robot. For reloading purposes."""
+ if self.sensors:
+ self.sensors.kill()
+ if self.actuators:
+ self.actuators.kill()
+ pass
+
+ def run(self):
+ """Main loop of the class. Calls a brain action every self.time_cycle"""
+ "TODO: cleanup measure of ips"
+ it = 0
+ ss = time.time()
+ self.brain_iterations_real_time = []
+ self.brain_iterations_simulated_time = []
+ self.real_time_factors = []
+ self.sensors.get_camera('camera_0').total_frames = 0
+ self.pilot_start_time = time.time()
+ while not self.kill_event.is_set():
+ if not self.stop_event.is_set():
+ start_time = datetime.now()
+ start_time_ros = self.ros_clock_time
+ self.execution_completed = False
+ try:
+ self.brains.active_brain.execute()
+ except AttributeError as e:
+ traceback.print_exc()
+ logger.warning('No Brain selected')
+ logger.error(e)
+
+ dt = datetime.now() - start_time
+ ms = (dt.days * 24 * 60 * 60 + dt.seconds) * 1000 + dt.microseconds / 1000.0
+ self.brain_iterations_real_time.append(ms / 1000)
+ elapsed = time.time() - ss
+ if elapsed < 1:
+ it += 1
+ else:
+ ss = time.time()
+ it = 0
+ if ms < self.time_cycle:
+ time.sleep((self.time_cycle - ms) / 1000.0)
+ self.real_time_factors.append(self.real_time_factor)
+ self.brain_iterations_simulated_time.append(self.ros_clock_time - start_time_ros)
+ self.execution_completed = True
+ if ros_version == '2':
+ self.node.destroy_subscription(self.clock_subscriber)
+ else:
+ self.clock_subscriber.unregister()
+ self.stats_process.terminate()
+ poll = self.stats_process.poll()
+ while poll is None:
+ time.sleep(1)
+ poll = self.stats_process.poll()
+ self.kill()
+ logger.info('Pilot: pilot killed.')
+
+ def stop(self):
+ """Pause the main loop"""
+
+ self.stop_event.set()
+
+ def play(self):
+ """Resume the main loop."""
+
+ if self.is_alive():
+ self.stop_event.clear()
+ else:
+ self.start()
+
+ def kill(self):
+ """Destroy the main loop. For exiting"""
+ self.stop_interfaces()
+ self.actuators.kill()
+ self.kill_event.set()
+
+ def reload_brain(self, brain_path, model=None):
+ """Reload a brain specified by brain_path
+
+ This function is useful if one wants to change the environment of the robot (simulated world).
+
+ Arguments:
+ brain_path {str} -- Path to the brain module to load.
+ """
+ self.brains.load_brain(brain_path, model=model)
+
+ def finish_line(self):
+ pose = self.pose3d.getPose3d()
+ current_point = np.array([pose.x, pose.y])
+
+ dist = (self.start_pose - current_point) ** 2
+ dist = np.sum(dist, axis=0)
+ dist = np.sqrt(dist)
+ if dist < self.max_distance:
+ return True
+ return False
+
+ def calculate_metrics(self, experiment_metrics):
+ if hasattr(self.brains.active_brain, 'inference_times'):
+ self.brains.active_brain.inference_times = self.brains.active_brain.inference_times[10:-10]
+ mean_inference_time = sum(self.brains.active_brain.inference_times) / len(self.brains.active_brain.inference_times)
+ frame_rate = self.sensors.get_camera('camera_0').total_frames / experiment_metrics['experiment_total_simulated_time']
+ gpu_inference = self.brains.active_brain.gpu_inference
+ real_time_update_rate = self.real_time_update_rate
+ first_image = self.brains.active_brain.first_image
+ logger.info('* Mean network inference time ---> ' + str(mean_inference_time) + 's')
+ logger.info('* Frame rate ---> ' + str(frame_rate) + 'fps')
+ else:
+ mean_inference_time = 0
+ frame_rate = 0
+ gpu_inference = False
+ real_time_update_rate = self.real_time_update_rate
+ first_image = None
+ logger.info('No deep learning based brain')
+ if self.brain_iterations_real_time and self.brain_iterations_simulated_time and self.brain_iterations_simulated_time:
+ mean_brain_iterations_simulated_time = sum(self.brain_iterations_simulated_time) / len(self.brain_iterations_simulated_time)
+ real_time_factor = sum(self.real_time_factors) / len(self.real_time_factors)
+ brain_iterations_frequency_simulated_time = 1 / mean_brain_iterations_simulated_time
+ target_brain_iterations_simulated_time = 1000 / self.time_cycle / round(real_time_factor, 2)
+ mean_brain_iterations_real_time = sum(self.brain_iterations_real_time) / len(self.brain_iterations_real_time)
+ brain_iterations_frequency_real_time = 1 / mean_brain_iterations_real_time
+ target_brain_iterations_real_time = 1 / (self.time_cycle / 1000)
+ suddenness_distance = sum(self.brains.active_brain.suddenness_distance) / len(self.brains.active_brain.suddenness_distance)
+ else:
+ mean_brain_iterations_real_time = 0
+ mean_brain_iterations_simulated_time = 0
+ real_time_factor = 0
+ brain_iterations_frequency_simulated_time = 0
+ target_brain_iterations_simulated_time = 0
+ brain_iterations_frequency_real_time = 0
+ target_brain_iterations_real_time = 0
+ suddenness_distance = 0
+ logger.info('* Brain iterations frequency simulated time ---> ' + str(brain_iterations_frequency_simulated_time) + 'it/s')
+ logger.info('* Target brain iterations simulated time -> ' + str(target_brain_iterations_simulated_time) + 'it/s')
+ logger.info('* Mean brain iterations real time ---> ' + str(mean_brain_iterations_real_time) + 's')
+ logger.info('* Brain iterations frequency real time ---> ' + str(brain_iterations_frequency_real_time) + 'it/s')
+ logger.info('* Target brain iterations real time -> ' + str(target_brain_iterations_real_time) + 'it/s')
+ logger.info('* Mean brain iterations simulated time ---> ' + str(mean_brain_iterations_simulated_time) + 's')
+ logger.info('* Mean brain iterations simulated time ---> ' + str(real_time_factor))
+ logger.info('* Real time update rate ---> ' + str(real_time_update_rate))
+ logger.info('* GPU inference ---> ' + str(gpu_inference))
+ logger.info('* Suddenness distance ---> ' + str(suddenness_distance))
+ logger.info('* Saving experiment ---> ' + str(hasattr(self.controller, 'experiment_metrics_filename')))
+ experiment_metrics['brain_iterations_frequency_simulated_time'] = brain_iterations_frequency_simulated_time
+ experiment_metrics['target_brain_iterations_simulated_time'] = target_brain_iterations_simulated_time
+ experiment_metrics['mean_brain_iterations_real_time'] = mean_brain_iterations_real_time
+ experiment_metrics['brain_iterations_frequency_real_time'] = brain_iterations_frequency_real_time
+ experiment_metrics['target_brain_iterations_real_time'] = target_brain_iterations_real_time
+ experiment_metrics['mean_inference_time'] = mean_inference_time
+ experiment_metrics['frame_rate'] = frame_rate
+ experiment_metrics['gpu_inference'] = gpu_inference
+ experiment_metrics['mean_brain_iterations_simulated_time'] = mean_brain_iterations_simulated_time
+ experiment_metrics['real_time_factor'] = real_time_factor
+ experiment_metrics['real_time_update_rate'] = real_time_update_rate
+ experiment_metrics['suddenness_distance'] = suddenness_distance
+ logger.info('Saving metrics to ROS bag')
+ return experiment_metrics, first_image
+
+ def clock_callback(self, clock_data):
+ self.ros_clock_time = clock_data.clock.to_sec()
+
+ def track_stats(self):
+ args = ["gz", "stats", "-p"]
+ # Prints gz statistics. "-p": Output comma-separated values containing-
+ # real-time factor (percent), simtime (sec), realtime (sec), paused (T or F)
+ self.stats_process = subprocess.Popen(args, stdout=subprocess.PIPE)
+ # bufsize=1 enables line-bufferred mode (the input buffer is flushed
+ # automatically on newlines if you would write to process.stdin )
+ poll = self.stats_process.poll()
+ while poll is not None:
+ time.sleep(1)
+ poll = self.stats_process.poll()
+
+ if ros_version == '2':
+ self.clock_subscriber = self.node.create_subscription(Clock, "/clock", self.clock_callback,1)
+ else:
+ self.clock_subscriber = rospy.Subscriber("/clock", Clock, self.clock_callback)
+
+ with self.stats_process.stdout:
+ for line in iter(self.stats_process.stdout.readline, b''):
+ stats_list = [x.strip() for x in line.split(b',')]
+ try:
+ self.real_time_factor = float(stats_list[0].decode("utf-8"))
+ except Exception as ex:
+ self.real_time_factor = 0
diff --git a/behavior_metrics/profiles/default.yml b/behavior_metrics/profiles/default.yml
index d092cc9b..16b36c5d 100644
--- a/behavior_metrics/profiles/default.yml
+++ b/behavior_metrics/profiles/default.yml
@@ -1,42 +1,42 @@
-Behaviors:
- Robot:
- Sensors:
- Cameras:
- Camera_0:
- Name: 'camera_0'
- Topic: '/F1ROS/cameraL/image_raw'
- Pose3D:
- Pose3D_0:
- Name: 'pose3d_0'
- Topic: '/F1ROS/odom'
- Actuators:
- Motors:
- Motors_0:
- Name: 'motors_0'
- Topic: '/F1ROS/cmd_vel'
- MaxV: 3
- MaxW: 0.3
- BrainPath: 'brains/gazebo/f1/brain_f1_opencv.py'
- Type: 'f1'
- Simulation:
- World: /opt/jderobot/share/jderobot/gazebo/launch/simple_circuit.launch
- Dataset:
- In: '/tmp/my_bag.bag'
- Out: ''
- Layout:
- Frame_0:
- Name: frame_0
- Geometry: [1, 1, 2, 2]
- Data: rgbimage
- Frame_1:
- Name: frame_1
- Geometry: [0, 1, 1, 1]
- Data: rgbimage
- Frame_2:
- Name: frame_2
- Geometry: [0, 2, 1, 1]
- Data: rgbimage
- Frame_3:
- Name: frame_3
- Geometry: [0, 3, 3, 1]
- Data: rgbimage
+Behaviors:
+ Robot:
+ Sensors:
+ Cameras:
+ Camera_0:
+ Name: 'camera_0'
+ Topic: '/F1ROS/cameraL/image_raw'
+ Pose3D:
+ Pose3D_0:
+ Name: 'pose3d_0'
+ Topic: '/F1ROS/odom'
+ Actuators:
+ Motors:
+ Motors_0:
+ Name: 'motors_0'
+ Topic: '/F1ROS/cmd_vel'
+ MaxV: 3
+ MaxW: 0.3
+ BrainPath: 'brains/gazebo/f1/brain_f1_opencv.py'
+ Type: 'f1'
+ Simulation:
+ World: /opt/jderobot/share/jderobot/gazebo/launch/simple_circuit.launch
+ Dataset:
+ In: '/tmp/my_bag.bag'
+ Out: ''
+ Layout:
+ Frame_0:
+ Name: frame_0
+ Geometry: [1, 1, 2, 2]
+ Data: rgbimage
+ Frame_1:
+ Name: frame_1
+ Geometry: [0, 1, 1, 1]
+ Data: rgbimage
+ Frame_2:
+ Name: frame_2
+ Geometry: [0, 2, 1, 1]
+ Data: rgbimage
+ Frame_3:
+ Name: frame_3
+ Geometry: [0, 3, 3, 1]
+ Data: rgbimage
diff --git a/behavior_metrics/profiles/drone.yml b/behavior_metrics/profiles/drone.yml
index c34e43db..fbe9bb92 100644
--- a/behavior_metrics/profiles/drone.yml
+++ b/behavior_metrics/profiles/drone.yml
@@ -1,28 +1,28 @@
-Behaviors:
- Robot:
- Sensors: {'Not required due to ROS DroneWrapper'}
- Actuators: {'Not required due to ROS DroneWrapper'}
- BrainPath: 'brains/drone/brain_drone_opencv.py'
- Type: 'drone'
- Simulation:
- World: /home/fran/github/RoboticsAcademy/exercises/follow_road/follow_road.launch
- Dataset:
- In: '/tmp/my_bag.bag'
- Out: ''
- Layout:
- Frame_0:
- Name: frame_0
- Geometry: [1, 1, 2, 2]
- Data: rgbimage
- Frame_1:
- Name: frame_1
- Geometry: [0, 1, 1, 1]
- Data: rgbimage
- Frame_2:
- Name: frame_2
- Geometry: [0, 2, 1, 1]
- Data: rgbimage
- Frame_3:
- Name: frame_3
- Geometry: [0, 3, 3, 1]
- Data: rgbimage
+Behaviors:
+ Robot:
+ Sensors: {'Not required due to ROS DroneWrapper'}
+ Actuators: {'Not required due to ROS DroneWrapper'}
+ BrainPath: 'brains/drone/brain_drone_opencv.py'
+ Type: 'drone'
+ Simulation:
+ World: /home/fran/github/RoboticsAcademy/exercises/follow_road/follow_road.launch
+ Dataset:
+ In: '/tmp/my_bag.bag'
+ Out: ''
+ Layout:
+ Frame_0:
+ Name: frame_0
+ Geometry: [1, 1, 2, 2]
+ Data: rgbimage
+ Frame_1:
+ Name: frame_1
+ Geometry: [0, 1, 1, 1]
+ Data: rgbimage
+ Frame_2:
+ Name: frame_2
+ Geometry: [0, 2, 1, 1]
+ Data: rgbimage
+ Frame_3:
+ Name: frame_3
+ Geometry: [0, 3, 3, 1]
+ Data: rgbimage
diff --git a/behavior_metrics/robot/actuators.py b/behavior_metrics/robot/actuators.py
index 09787fd9..427adab5 100644
--- a/behavior_metrics/robot/actuators.py
+++ b/behavior_metrics/robot/actuators.py
@@ -1,94 +1,94 @@
-#!/usr/bin/env python
-""" This module is responsible for handling the actuators of the robot.
-
-This program is free software: you can redistribute it and/or modify it under
-the terms of the GNU General Public License as published by the Free Software
-Foundation, either version 3 of the License, or (at your option) any later
-version.
-This program is distributed in the hope that it will be useful, but WITHOUT
-ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
-FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
-You should have received a copy of the GNU General Public License along with
-this program. If not, see .
-"""
-
-from .interfaces.motors import PublisherMotors, PublisherCARLAMotors
-
-__author__ = 'fqez'
-__contributors__ = []
-__license__ = 'GPLv3'
-
-
-class Actuators:
- """This class controls the creation of the actuators of the robot
-
- Attributes:
- motors {dict} -- Dictionary which key is the name of the motor and value is a ROS motors publisher instance.
-
- """
-
- def __init__(self, actuators_config, node):
- """Constructor of the class
-
- Arguments:
- actuators_config {dict} -- Configuration of the different actuators.
- """
- self.node = node
- # Load motors
- motors_conf = actuators_config.get('Motors', None)
- carla_motors_conf = actuators_config.get('CARLA_Motors', None)
- self.motors = None
- if motors_conf:
- self.motors = self.__create_actuator(motors_conf, 'motor')
- elif carla_motors_conf:
- self.motors = self.__create_actuator(carla_motors_conf, 'carla_motor')
-
- def __create_actuator(self, actuator_config, actuator_type):
- """Fill the motors dictionary with instances of the motors to control the robot"""
-
- actuator_dict = {}
- for elem in actuator_config:
- name = actuator_config[elem]['Name']
- topic = actuator_config[elem]['Topic']
- vmax = actuator_config[elem]['MaxV']
- wmax = actuator_config[elem]['MaxW']
-
- if 'RL' in actuator_config[elem]:
- if actuator_config[elem]['RL'] == False:
- if actuator_type == 'motor':
- actuator_dict[name] = PublisherMotors(self.node, topic, vmax, wmax, 0, 0)
- else:
- if actuator_type == 'motor':
- actuator_dict[name] = PublisherMotors(self.node, topic, vmax, wmax, 0, 0)
- elif actuator_type == 'carla_motor':
- actuator_dict[name] = PublisherCARLAMotors(self.node, topic, vmax, wmax, 0, 0)
- return actuator_dict
-
- def __get_actuator(self, actuator_name, actuator_type):
- """Retrieve an specific actuator"""
-
- actuator = None
- try:
- if actuator_type == 'motor':
- actuator = self.motors[actuator_name]
- except KeyError:
- return "[ERROR] No existing actuator with {} name.".format(actuator_name)
-
- return actuator
-
- def get_motor(self, motor_name):
- """Retrieve an specific existing motor
-
- Arguments:
- motor_name {str} -- Name of the motor to be retrieved
-
- Returns:
- robot.interfaces.motors.PublisherMotors instance -- ROS motor instance
- """
- return self.__get_actuator(motor_name, 'motor')
-
- def kill(self):
- """Destroy all the running actuators"""
- # do the same for every publisher that requires threading
- for actuator in self.motors.values():
- actuator.stop()
+#!/usr/bin/env python
+""" This module is responsible for handling the actuators of the robot.
+
+This program is free software: you can redistribute it and/or modify it under
+the terms of the GNU General Public License as published by the Free Software
+Foundation, either version 3 of the License, or (at your option) any later
+version.
+This program is distributed in the hope that it will be useful, but WITHOUT
+ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
+You should have received a copy of the GNU General Public License along with
+this program. If not, see .
+"""
+
+from .interfaces.motors import PublisherMotors, PublisherCARLAMotors
+
+__author__ = 'fqez'
+__contributors__ = []
+__license__ = 'GPLv3'
+
+
+class Actuators:
+ """This class controls the creation of the actuators of the robot
+
+ Attributes:
+ motors {dict} -- Dictionary which key is the name of the motor and value is a ROS motors publisher instance.
+
+ """
+
+ def __init__(self, actuators_config, node):
+ """Constructor of the class
+
+ Arguments:
+ actuators_config {dict} -- Configuration of the different actuators.
+ """
+ self.node = node
+ # Load motors
+ motors_conf = actuators_config.get('Motors', None)
+ carla_motors_conf = actuators_config.get('CARLA_Motors', None)
+ self.motors = None
+ if motors_conf:
+ self.motors = self.__create_actuator(motors_conf, 'motor')
+ elif carla_motors_conf:
+ self.motors = self.__create_actuator(carla_motors_conf, 'carla_motor')
+
+ def __create_actuator(self, actuator_config, actuator_type):
+ """Fill the motors dictionary with instances of the motors to control the robot"""
+
+ actuator_dict = {}
+ for elem in actuator_config:
+ name = actuator_config[elem]['Name']
+ topic = actuator_config[elem]['Topic']
+ vmax = actuator_config[elem]['MaxV']
+ wmax = actuator_config[elem]['MaxW']
+
+ if 'RL' in actuator_config[elem]:
+ if actuator_config[elem]['RL'] == False:
+ if actuator_type == 'motor':
+ actuator_dict[name] = PublisherMotors(self.node, topic, vmax, wmax, 0, 0)
+ else:
+ if actuator_type == 'motor':
+ actuator_dict[name] = PublisherMotors(self.node, topic, vmax, wmax, 0, 0)
+ elif actuator_type == 'carla_motor':
+ actuator_dict[name] = PublisherCARLAMotors(self.node, topic, vmax, wmax, 0, 0)
+ return actuator_dict
+
+ def __get_actuator(self, actuator_name, actuator_type):
+ """Retrieve an specific actuator"""
+
+ actuator = None
+ try:
+ if actuator_type == 'motor':
+ actuator = self.motors[actuator_name]
+ except KeyError:
+ return "[ERROR] No existing actuator with {} name.".format(actuator_name)
+
+ return actuator
+
+ def get_motor(self, motor_name):
+ """Retrieve an specific existing motor
+
+ Arguments:
+ motor_name {str} -- Name of the motor to be retrieved
+
+ Returns:
+ robot.interfaces.motors.PublisherMotors instance -- ROS motor instance
+ """
+ return self.__get_actuator(motor_name, 'motor')
+
+ def kill(self):
+ """Destroy all the running actuators"""
+ # do the same for every publisher that requires threading
+ for actuator in self.motors.values():
+ actuator.stop()
diff --git a/behavior_metrics/robot/interfaces/camera.py b/behavior_metrics/robot/interfaces/camera.py
index c4251ef6..c3f7eef5 100644
--- a/behavior_metrics/robot/interfaces/camera.py
+++ b/behavior_metrics/robot/interfaces/camera.py
@@ -1,107 +1,107 @@
-import os
-import threading
-import numpy as np
-# import rospy
-ros_version = os.environ.get('ROS_VERSION', '2')
-if ros_version == '2':
- import rclpy
- from rclpy.node import Node
-else:
- import rospy
-
-from cv_bridge import CvBridge
-from sensor_msgs.msg import Image as ImageROS
-
-MAXRANGE = 8 # max length received from imageD
-MINRANGE = 0
-
-
-def imageMsg2Image(img, bridge):
-
- image = Image()
-
- image.width = img.width
- image.height = img.height
- image.format = "RGB8"
- if ros_version == '2':
- image.timeStamp = img.header.stamp.sec + (img.header.stamp.nanosec * 1e-9)
- else:
- image.timeStamp = img.header.stamp.secs + (img.header.stamp.nsecs * 1e-9)
- cv_image = 0
- if (img.encoding[-2:] == "C1"):
- # gray_img_buff = bridge.imgmsg_to_cv2(img, img.encoding)
- # cv_image = depthToRGB8(gray_img_buff, img.encoding)
- pass
- else:
- cv_image = bridge.imgmsg_to_cv2(img, "rgb8")
- image.data = cv_image
- return image
-
-
-class Image:
-
- def __init__(self):
-
- self.height = 3 # Image height [pixels]
- self.width = 3 # Image width [pixels]
- self.timeStamp = 0 # Time stamp [s] */
- self.format = "" # Image format string (RGB8, BGR,...)
- self.data = np.zeros((self.height, self.width, 3), np.uint8) # The image data itself
- self.data.shape = self.height, self.width, 3
-
- def __str__(self):
- s = "Image: {\n height: " + str(self.height) + "\n width: " + str(self.width)
- s = s + "\n format: " + self.format + "\n timeStamp: " + str(self.timeStamp)
- s = s + "\n data: " + str(self.data) + "\n}"
- return s
-
-
-class ListenerCamera:
-
- def __init__(self, node: Node, topic: str):
- self.node = node
- self.topic = topic
- self.data = Image()
- self.sub = None
- self.lock = threading.Lock()
- self.total_frames = 0
-
- self.bridge = CvBridge()
- self.start()
-
- def __callback(self, img):
- self.total_frames += 1
- image = imageMsg2Image(img, self.bridge)
-
- self.lock.acquire()
- self.data = image
- self.lock.release()
-
- def stop(self):
- if ros_version == '2':
- if self.sub is not None:
- self.node.destroy_subscription(self.sub)
- self.sub = None
- else:
- if self.sub is not None:
- self.sub.unregister()
- self.sub = None
-
- def start(self):
- if ros_version == '2':
- self.sub = self.node.create_subscription(ImageROS, self.topic, self.__callback, 1)
- else:
- self.sub = rospy.Subscriber(self.topic, ImageROS, self.__callback)
-
- def getImage(self):
- self.lock.acquire()
- image = self.data
- self.lock.release()
-
- return image
-
- def getTopic(self):
- return self.topic
-
- def hasproxy(self):
- return hasattr(self, "sub") and self.sub
+import os
+import threading
+import numpy as np
+# import rospy
+ros_version = os.environ.get('ROS_VERSION', '2')
+if ros_version == '2':
+ import rclpy
+ from rclpy.node import Node
+else:
+ import rospy
+
+from cv_bridge import CvBridge
+from sensor_msgs.msg import Image as ImageROS
+
+MAXRANGE = 8 # max length received from imageD
+MINRANGE = 0
+
+
+def imageMsg2Image(img, bridge):
+
+ image = Image()
+
+ image.width = img.width
+ image.height = img.height
+ image.format = "RGB8"
+ if ros_version == '2':
+ image.timeStamp = img.header.stamp.sec + (img.header.stamp.nanosec * 1e-9)
+ else:
+ image.timeStamp = img.header.stamp.secs + (img.header.stamp.nsecs * 1e-9)
+ cv_image = 0
+ if (img.encoding[-2:] == "C1"):
+ # gray_img_buff = bridge.imgmsg_to_cv2(img, img.encoding)
+ # cv_image = depthToRGB8(gray_img_buff, img.encoding)
+ pass
+ else:
+ cv_image = bridge.imgmsg_to_cv2(img, "rgb8")
+ image.data = cv_image
+ return image
+
+
+class Image:
+
+ def __init__(self):
+
+ self.height = 3 # Image height [pixels]
+ self.width = 3 # Image width [pixels]
+ self.timeStamp = 0 # Time stamp [s] */
+ self.format = "" # Image format string (RGB8, BGR,...)
+ self.data = np.zeros((self.height, self.width, 3), np.uint8) # The image data itself
+ self.data.shape = self.height, self.width, 3
+
+ def __str__(self):
+ s = "Image: {\n height: " + str(self.height) + "\n width: " + str(self.width)
+ s = s + "\n format: " + self.format + "\n timeStamp: " + str(self.timeStamp)
+ s = s + "\n data: " + str(self.data) + "\n}"
+ return s
+
+
+class ListenerCamera:
+
+ def __init__(self, node: Node, topic: str):
+ self.node = node
+ self.topic = topic
+ self.data = Image()
+ self.sub = None
+ self.lock = threading.Lock()
+ self.total_frames = 0
+
+ self.bridge = CvBridge()
+ self.start()
+
+ def __callback(self, img):
+ self.total_frames += 1
+ image = imageMsg2Image(img, self.bridge)
+
+ self.lock.acquire()
+ self.data = image
+ self.lock.release()
+
+ def stop(self):
+ if ros_version == '2':
+ if self.sub is not None:
+ self.node.destroy_subscription(self.sub)
+ self.sub = None
+ else:
+ if self.sub is not None:
+ self.sub.unregister()
+ self.sub = None
+
+ def start(self):
+ if ros_version == '2':
+ self.sub = self.node.create_subscription(ImageROS, self.topic, self.__callback, 1)
+ else:
+ self.sub = rospy.Subscriber(self.topic, ImageROS, self.__callback)
+
+ def getImage(self):
+ self.lock.acquire()
+ image = self.data
+ self.lock.release()
+
+ return image
+
+ def getTopic(self):
+ return self.topic
+
+ def hasproxy(self):
+ return hasattr(self, "sub") and self.sub
diff --git a/behavior_metrics/robot/interfaces/laser.py b/behavior_metrics/robot/interfaces/laser.py
index 13b186dc..90188af3 100644
--- a/behavior_metrics/robot/interfaces/laser.py
+++ b/behavior_metrics/robot/interfaces/laser.py
@@ -1,106 +1,106 @@
-import os
-# import rospy
-from sensor_msgs.msg import LaserScan
-import threading
-from math import pi as PI
-from jderobotTypes import LaserData
-
-ros_version = os.environ.get('ROS_VERSION', '2')
-if ros_version == '2':
- import rclpy
- from rclpy.node import Node
-else:
- import rospy
-
-def laserScan2LaserData(scan):
- '''
- Translates from ROS LaserScan to JderobotTypes LaserData.
-
- @param scan: ROS LaserScan to translate
-
- @type scan: LaserScan
-
- @return a LaserData translated from scan
-
- ROS Angle Map JdeRobot Angle Map
- 0 PI/2
- | |
- | |
- PI/2 --------- -PI/2 PI --------- 0
- | |
- | |
- '''
- laser = LaserData()
- laser.values = scan.ranges
- laser.minAngle = scan.angle_min + PI/2
- laser.maxAngle = scan.angle_max + PI/2
- laser.maxRange = scan.range_max
- laser.minRange = scan.range_min
- laser.timeStamp = scan.header.stamp.secs + (scan.header.stamp.nsecs * 1e-9)
- return laser
-
-
-class ListenerLaser:
- '''
- ROS Laser Subscriber. Laser Client to Receive Laser Scans from ROS nodes.
- '''
- def __init__(self, node: Node, topic: str):
- '''
- ListenerLaser Constructor.
-
- @param topic: ROS topic to subscribe
- @type topic: String
-
- '''
- self.node = node
- self.topic = topic
- self.data = LaserData()
- self.sub = None
- self.lock = threading.Lock()
- self.start()
-
- def __callback(self, scan):
- '''
- Callback function to receive and save Laser Scans.
-
- @param scan: ROS LaserScan received
- @type scan: LaserScan
- '''
- laser = laserScan2LaserData(scan)
-
- self.lock.acquire()
- self.data = laser
- self.lock.release()
-
- def stop(self):
- '''
- Stops (Unregisters) the client.
-
- '''
- self.sub.unregister()
-
- def start(self):
- '''
- Starts (Subscribes) the client.
-
- '''
- if ros_version == '2':
- self.node.create_subscription(LaserScan, self.topic, self.__callback, 1)
- else:
- self.sub = rospy.Subscriber(self.topic, LaserScan, self.__callback)
-
- def getLaserData(self):
- '''
- Returns last LaserData.
-
- @return last JdeRobotTypes LaserData saved
-
- '''
- self.lock.acquire()
- laser = self.data
- self.lock.release()
-
- return laser
-
- def getTopic(self):
- return self.topic
+import os
+# import rospy
+from sensor_msgs.msg import LaserScan
+import threading
+from math import pi as PI
+from jderobotTypes import LaserData
+
+ros_version = os.environ.get('ROS_VERSION', '2')
+if ros_version == '2':
+ import rclpy
+ from rclpy.node import Node
+else:
+ import rospy
+
+def laserScan2LaserData(scan):
+ '''
+ Translates from ROS LaserScan to JderobotTypes LaserData.
+
+ @param scan: ROS LaserScan to translate
+
+ @type scan: LaserScan
+
+ @return a LaserData translated from scan
+
+ ROS Angle Map JdeRobot Angle Map
+ 0 PI/2
+ | |
+ | |
+ PI/2 --------- -PI/2 PI --------- 0
+ | |
+ | |
+ '''
+ laser = LaserData()
+ laser.values = scan.ranges
+ laser.minAngle = scan.angle_min + PI/2
+ laser.maxAngle = scan.angle_max + PI/2
+ laser.maxRange = scan.range_max
+ laser.minRange = scan.range_min
+ laser.timeStamp = scan.header.stamp.secs + (scan.header.stamp.nsecs * 1e-9)
+ return laser
+
+
+class ListenerLaser:
+ '''
+ ROS Laser Subscriber. Laser Client to Receive Laser Scans from ROS nodes.
+ '''
+ def __init__(self, node: Node, topic: str):
+ '''
+ ListenerLaser Constructor.
+
+ @param topic: ROS topic to subscribe
+ @type topic: String
+
+ '''
+ self.node = node
+ self.topic = topic
+ self.data = LaserData()
+ self.sub = None
+ self.lock = threading.Lock()
+ self.start()
+
+ def __callback(self, scan):
+ '''
+ Callback function to receive and save Laser Scans.
+
+ @param scan: ROS LaserScan received
+ @type scan: LaserScan
+ '''
+ laser = laserScan2LaserData(scan)
+
+ self.lock.acquire()
+ self.data = laser
+ self.lock.release()
+
+ def stop(self):
+ '''
+ Stops (Unregisters) the client.
+
+ '''
+ self.sub.unregister()
+
+ def start(self):
+ '''
+ Starts (Subscribes) the client.
+
+ '''
+ if ros_version == '2':
+ self.node.create_subscription(LaserScan, self.topic, self.__callback, 1)
+ else:
+ self.sub = rospy.Subscriber(self.topic, LaserScan, self.__callback)
+
+ def getLaserData(self):
+ '''
+ Returns last LaserData.
+
+ @return last JdeRobotTypes LaserData saved
+
+ '''
+ self.lock.acquire()
+ laser = self.data
+ self.lock.release()
+
+ return laser
+
+ def getTopic(self):
+ return self.topic
diff --git a/behavior_metrics/robot/interfaces/motors.py b/behavior_metrics/robot/interfaces/motors.py
index a21d42d3..899c85ee 100644
--- a/behavior_metrics/robot/interfaces/motors.py
+++ b/behavior_metrics/robot/interfaces/motors.py
@@ -1,252 +1,252 @@
-# import rospy
-import os
-from utils.logger import logger
-from geometry_msgs.msg import Twist
-import threading
-from .threadPublisher import ThreadPublisher
-
-ros_version = os.environ.get('ROS_VERSION', '2')
-if ros_version == '2':
- import rclpy
- from rclpy.node import Node
-else:
- import rospy
-
-try:
- from carla_msgs.msg import CarlaEgoVehicleControl
-except ModuleNotFoundError as ex:
- logger.error('CARLA is not supported')
-
-
-def cmdvel2Twist(vel):
-
- tw = Twist()
- tw.linear.x = float(vel.vx)
- tw.linear.y = float(vel.vy)
- tw.linear.z = float(vel.vz)
- tw.angular.x = float(vel.ax)
- tw.angular.y = float(vel.ay)
- tw.angular.z = float(vel.az)
-
- return tw
-
-
-def cmdvel2CarlaEgoVehicleControl(vel):
- vehicle_control = CarlaEgoVehicleControl()
- vehicle_control.throttle = vel.throttle
- vehicle_control.steer = vel.steer
- vehicle_control.brake = vel.brake
- vehicle_control.hand_brake = False
- vehicle_control.reverse = False
- vehicle_control.gear = 0
- vehicle_control.manual_gear_shift = False
-
- return vehicle_control
-
-
-
-class CMDVel():
-
- def __init__(self):
-
- self.vx = 0 # vel in x[m/s] (use this for V in wheeled robots)
- self.vy = 0 # vel in y[m/s]
- self.vz = 0 # vel in z[m/s]
- self.ax = 0 # angular vel in X axis [rad/s]
- self.ay = 0 # angular vel in X axis [rad/s]
- self.az = 0 # angular vel in Z axis [rad/s] (use this for W in wheeled robots)
- self.timeStamp = 0 # Time stamp [s]
- self.v = 0 # vel[m/s]
- self.w = 0 # angular vel [rad/s]
-
- def __str__(self):
- s = "CMDVel: {\n vx: " + str(self.vx) + "\n vy: " + str(self.vy)
- s = s + "\n vz: " + str(self.vz) + "\n ax: " + str(self.ax)
- s = s + "\n ay: " + str(self.ay) + "\n az: " + str(self.az)
- s = s + "\n timeStamp: " + str(self.timeStamp) + "\n}"
- return s
-
-class CARLAVel():
-
- def __init__(self):
-
- self.throttle = 0.0
- self.steer = 0.0
- self.brake = 0.0
- self.hand_brake = False
- self.reverse = False
- self.gear = 0
- self.manual_gear_shift = False
-
- def __str__(self):
- s = "CARLAVel: {\n throttle: " + str(self.throttle) + "\n steer: " + str(self.steer)
- s = s + "\n brake: " + str(self.brake) + "\n hand_brake: " + str(self.hand_brake)
- s = s + "\n reverse: " + str(self.reverse) + "\n gear: " + str(self.gear)
- s = s + "\n manual_gear_shift: " + str(self.manual_gear_shift) + "\n}"
- return s
-
-
-
-class PublisherMotors:
-
- def __init__(self, node: Node, topic: str, maxV, maxW, v, w):
- self.node = node
- self.maxW = maxW
- self.maxV = maxV
- self.v = v
- self.w = w
- self.topic = topic
- self.data = CMDVel()
- if ros_version == '2':
- # rclpy.init()
- self.pub = self.node.create_publisher(Twist, self.topic, 1)
- else:
- self.pub = rospy.Publisher(self.topic, Twist, queue_size=1)
- rospy.init_node("FollowLineF1")
- self.lock = threading.Lock()
- self.kill_event = threading.Event()
- self.thread = ThreadPublisher(self, self.kill_event)
- self.thread.daemon = True
- self.start()
-
- def publish(self):
- self.lock.acquire()
- tw = cmdvel2Twist(self.data)
- self.lock.release()
- self.pub.publish(tw)
-
- def stop(self):
- self.kill_event.set()
- self.pub.unregister()
-
- def start(self):
-
- self.kill_event.clear()
- self.thread.start()
-
- def getTopic(self):
- return self.topic
-
- def getMaxW(self):
- return self.maxW
-
- def getMaxV(self):
- return self.maxV
-
- def sendVelocities(self, vel):
-
- self.lock.acquire()
- self.data = vel
- self.lock.release()
-
- def sendV(self, v):
-
- self.sendVX(v)
- self.v = v
-
- def sendL(self, l):
-
- self.sendVY(l)
-
- def sendW(self, w):
-
- self.sendAZ(w)
- self.w = w
-
- def sendVX(self, vx):
-
- self.lock.acquire()
- self.data.vx = vx
- self.lock.release()
-
- def sendVY(self, vy):
-
- self.lock.acquire()
- self.data.vy = vy
- self.lock.release()
-
- def sendAZ(self, az):
-
- self.lock.acquire()
- self.data.az = az
- self.lock.release()
-
-
-class PublisherCARLAMotors:
-
- def __init__(self, node: Node, topic: str, maxV, maxW, v, w):
- self.node = node
- self.maxW = maxW
- self.maxV = maxV
- self.v = v
- self.w = w
- self.topic = topic
- self.data = CARLAVel()
- if ros_version == '2':
- self.pub = self.node.create_publisher(CarlaEgoVehicleControl, self.topic, 1)
- else:
- self.pub = rospy.Publisher(self.topic, CarlaEgoVehicleControl, queue_size=1)
- rospy.init_node("CARLAMotors")
- self.lock = threading.Lock()
- self.kill_event = threading.Event()
- self.thread = ThreadPublisher(self, self.kill_event)
- self.thread.daemon = True
- self.start()
-
- def publish(self):
- self.lock.acquire()
- vehicle_control = cmdvel2CarlaEgoVehicleControl(self.data)
- self.lock.release()
- self.pub.publish(vehicle_control)
-
- def stop(self):
- self.kill_event.set()
- if ros_version == '2':
- if self.pub is not None:
- self.node.destroy_publisher(self.pub)
- self.pub = None
- else:
- if self.pub is not None:
- self.pub.unregister()
- self.pub = None
-
- def start(self):
-
- self.kill_event.clear()
- self.thread.start()
-
- def getTopic(self):
- return self.topic
-
- def getMaxW(self):
- return self.maxW
-
- def getMaxV(self):
- return self.maxV
-
- def sendVelocities(self, vel):
-
- self.lock.acquire()
- self.data = vel
- self.lock.release()
-
- def sendThrottle(self, throttle):
-
- self.lock.acquire()
- self.data.throttle = throttle
- self.lock.release()
- self.throttle = throttle
-
- def sendSteer(self, steer):
-
- self.lock.acquire()
- self.data.steer = steer
- self.lock.release()
- self.steer = steer
-
- def sendBrake(self, brake):
-
- self.lock.acquire()
- self.data.brake = brake
- self.lock.release()
- self.brake = brake
+# import rospy
+import os
+from utils.logger import logger
+from geometry_msgs.msg import Twist
+import threading
+from .threadPublisher import ThreadPublisher
+
+ros_version = os.environ.get('ROS_VERSION', '2')
+if ros_version == '2':
+ import rclpy
+ from rclpy.node import Node
+else:
+ import rospy
+
+try:
+ from carla_msgs.msg import CarlaEgoVehicleControl
+except ModuleNotFoundError as ex:
+ logger.error('CARLA is not supported')
+
+
+def cmdvel2Twist(vel):
+
+ tw = Twist()
+ tw.linear.x = float(vel.vx)
+ tw.linear.y = float(vel.vy)
+ tw.linear.z = float(vel.vz)
+ tw.angular.x = float(vel.ax)
+ tw.angular.y = float(vel.ay)
+ tw.angular.z = float(vel.az)
+
+ return tw
+
+
+def cmdvel2CarlaEgoVehicleControl(vel):
+ vehicle_control = CarlaEgoVehicleControl()
+ vehicle_control.throttle = vel.throttle
+ vehicle_control.steer = vel.steer
+ vehicle_control.brake = vel.brake
+ vehicle_control.hand_brake = False
+ vehicle_control.reverse = False
+ vehicle_control.gear = 0
+ vehicle_control.manual_gear_shift = False
+
+ return vehicle_control
+
+
+
+class CMDVel():
+
+ def __init__(self):
+
+ self.vx = 0 # vel in x[m/s] (use this for V in wheeled robots)
+ self.vy = 0 # vel in y[m/s]
+ self.vz = 0 # vel in z[m/s]
+ self.ax = 0 # angular vel in X axis [rad/s]
+ self.ay = 0 # angular vel in X axis [rad/s]
+ self.az = 0 # angular vel in Z axis [rad/s] (use this for W in wheeled robots)
+ self.timeStamp = 0 # Time stamp [s]
+ self.v = 0 # vel[m/s]
+ self.w = 0 # angular vel [rad/s]
+
+ def __str__(self):
+ s = "CMDVel: {\n vx: " + str(self.vx) + "\n vy: " + str(self.vy)
+ s = s + "\n vz: " + str(self.vz) + "\n ax: " + str(self.ax)
+ s = s + "\n ay: " + str(self.ay) + "\n az: " + str(self.az)
+ s = s + "\n timeStamp: " + str(self.timeStamp) + "\n}"
+ return s
+
+class CARLAVel():
+
+ def __init__(self):
+
+ self.throttle = 0.0
+ self.steer = 0.0
+ self.brake = 0.0
+ self.hand_brake = False
+ self.reverse = False
+ self.gear = 0
+ self.manual_gear_shift = False
+
+ def __str__(self):
+ s = "CARLAVel: {\n throttle: " + str(self.throttle) + "\n steer: " + str(self.steer)
+ s = s + "\n brake: " + str(self.brake) + "\n hand_brake: " + str(self.hand_brake)
+ s = s + "\n reverse: " + str(self.reverse) + "\n gear: " + str(self.gear)
+ s = s + "\n manual_gear_shift: " + str(self.manual_gear_shift) + "\n}"
+ return s
+
+
+
+class PublisherMotors:
+
+ def __init__(self, node: Node, topic: str, maxV, maxW, v, w):
+ self.node = node
+ self.maxW = maxW
+ self.maxV = maxV
+ self.v = v
+ self.w = w
+ self.topic = topic
+ self.data = CMDVel()
+ if ros_version == '2':
+ # rclpy.init()
+ self.pub = self.node.create_publisher(Twist, self.topic, 1)
+ else:
+ self.pub = rospy.Publisher(self.topic, Twist, queue_size=1)
+ rospy.init_node("FollowLineF1")
+ self.lock = threading.Lock()
+ self.kill_event = threading.Event()
+ self.thread = ThreadPublisher(self, self.kill_event)
+ self.thread.daemon = True
+ self.start()
+
+ def publish(self):
+ self.lock.acquire()
+ tw = cmdvel2Twist(self.data)
+ self.lock.release()
+ self.pub.publish(tw)
+
+ def stop(self):
+ self.kill_event.set()
+ self.pub.unregister()
+
+ def start(self):
+
+ self.kill_event.clear()
+ self.thread.start()
+
+ def getTopic(self):
+ return self.topic
+
+ def getMaxW(self):
+ return self.maxW
+
+ def getMaxV(self):
+ return self.maxV
+
+ def sendVelocities(self, vel):
+
+ self.lock.acquire()
+ self.data = vel
+ self.lock.release()
+
+ def sendV(self, v):
+
+ self.sendVX(v)
+ self.v = v
+
+ def sendL(self, l):
+
+ self.sendVY(l)
+
+ def sendW(self, w):
+
+ self.sendAZ(w)
+ self.w = w
+
+ def sendVX(self, vx):
+
+ self.lock.acquire()
+ self.data.vx = vx
+ self.lock.release()
+
+ def sendVY(self, vy):
+
+ self.lock.acquire()
+ self.data.vy = vy
+ self.lock.release()
+
+ def sendAZ(self, az):
+
+ self.lock.acquire()
+ self.data.az = az
+ self.lock.release()
+
+
+class PublisherCARLAMotors:
+
+ def __init__(self, node: Node, topic: str, maxV, maxW, v, w):
+ self.node = node
+ self.maxW = maxW
+ self.maxV = maxV
+ self.v = v
+ self.w = w
+ self.topic = topic
+ self.data = CARLAVel()
+ if ros_version == '2':
+ self.pub = self.node.create_publisher(CarlaEgoVehicleControl, self.topic, 1)
+ else:
+ self.pub = rospy.Publisher(self.topic, CarlaEgoVehicleControl, queue_size=1)
+ rospy.init_node("CARLAMotors")
+ self.lock = threading.Lock()
+ self.kill_event = threading.Event()
+ self.thread = ThreadPublisher(self, self.kill_event)
+ self.thread.daemon = True
+ self.start()
+
+ def publish(self):
+ self.lock.acquire()
+ vehicle_control = cmdvel2CarlaEgoVehicleControl(self.data)
+ self.lock.release()
+ self.pub.publish(vehicle_control)
+
+ def stop(self):
+ self.kill_event.set()
+ if ros_version == '2':
+ if self.pub is not None:
+ self.node.destroy_publisher(self.pub)
+ self.pub = None
+ else:
+ if self.pub is not None:
+ self.pub.unregister()
+ self.pub = None
+
+ def start(self):
+
+ self.kill_event.clear()
+ self.thread.start()
+
+ def getTopic(self):
+ return self.topic
+
+ def getMaxW(self):
+ return self.maxW
+
+ def getMaxV(self):
+ return self.maxV
+
+ def sendVelocities(self, vel):
+
+ self.lock.acquire()
+ self.data = vel
+ self.lock.release()
+
+ def sendThrottle(self, throttle):
+
+ self.lock.acquire()
+ self.data.throttle = throttle
+ self.lock.release()
+ self.throttle = throttle
+
+ def sendSteer(self, steer):
+
+ self.lock.acquire()
+ self.data.steer = steer
+ self.lock.release()
+ self.steer = steer
+
+ def sendBrake(self, brake):
+
+ self.lock.acquire()
+ self.data.brake = brake
+ self.lock.release()
+ self.brake = brake
diff --git a/behavior_metrics/robot/interfaces/threadPublisher.py b/behavior_metrics/robot/interfaces/threadPublisher.py
index c3a1b86f..6a87b7bf 100644
--- a/behavior_metrics/robot/interfaces/threadPublisher.py
+++ b/behavior_metrics/robot/interfaces/threadPublisher.py
@@ -1,32 +1,32 @@
-
-import threading
-import time
-from datetime import datetime
-# from utils.logger import logger
-
-time_cycle = 80
-
-
-class ThreadPublisher(threading.Thread):
-
- def __init__(self, pub, kill_event):
- super().__init__()
- self.pub = pub
- self.kill_event = kill_event
- # threading.Thread.__init__(self, args=kill_event)
-
- def run(self):
- while not self.kill_event.is_set():
- start_time = datetime.now()
-
- try:
- self.pub.publish()
- except Exception as e:
- print(f"Error in ThreadPublisher: {e}")
- break
-
- finish_time = datetime.now()
- dt = finish_time - start_time
- ms = (dt.days * 24 * 60 * 60 + dt.seconds) * 1000 + dt.microseconds / 1000.0
- if ms < time_cycle:
- time.sleep((time_cycle - ms) / 1000.0)
+
+import threading
+import time
+from datetime import datetime
+# from utils.logger import logger
+
+time_cycle = 80
+
+
+class ThreadPublisher(threading.Thread):
+
+ def __init__(self, pub, kill_event):
+ super().__init__()
+ self.pub = pub
+ self.kill_event = kill_event
+ # threading.Thread.__init__(self, args=kill_event)
+
+ def run(self):
+ while not self.kill_event.is_set():
+ start_time = datetime.now()
+
+ try:
+ self.pub.publish()
+ except Exception as e:
+ print(f"Error in ThreadPublisher: {e}")
+ break
+
+ finish_time = datetime.now()
+ dt = finish_time - start_time
+ ms = (dt.days * 24 * 60 * 60 + dt.seconds) * 1000 + dt.microseconds / 1000.0
+ if ms < time_cycle:
+ time.sleep((time_cycle - ms) / 1000.0)
diff --git a/behavior_metrics/robot/sensors.py b/behavior_metrics/robot/sensors.py
index 6e3f7846..846a6b12 100644
--- a/behavior_metrics/robot/sensors.py
+++ b/behavior_metrics/robot/sensors.py
@@ -1,170 +1,170 @@
-#!/usr/bin/env python
-""" This module is responsible for handling the sensors of the robot.
-
-This program is free software: you can redistribute it and/or modify it under
-the terms of the GNU General Public License as published by the Free Software
-Foundation, either version 3 of the License, or (at your option) any later
-version.
-This program is distributed in the hope that it will be useful, but WITHOUT
-ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
-FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
-You should have received a copy of the GNU General Public License along with
-this program. If not, see .
-"""
-
-from utils.logger import logger
-from robot.interfaces.camera import ListenerCamera
-from robot.interfaces.laser import ListenerLaser
-from robot.interfaces.pose3d import ListenerPose3d
-try:
- from robot.interfaces.birdeyeview import BirdEyeView
-except ModuleNotFoundError as ex:
- logger.error('CARLA is not supported sensor')
-
-from robot.interfaces.speedometer import ListenerSpeedometer
-
-__author__ = 'fqez'
-__contributors__ = []
-__license__ = 'GPLv3'
-
-
-class Sensors:
- """This class controls the creation of the actuators of the robot
-
- Attributes:
- cameras {dict} -- Dictionary which key is the name of the motor and value is a camera instance.
- laser {dict} -- Dictionary which key is the name of the motor and value is a laser sensor instance.
- pose3d {dict} -- Dictionary which key is the name of the motor and value is an odometry instance.
- """
-
- def __init__(self, sensors_config, node):
- """Constructor of the class
-
- Arguments:
- sensors_config {dict} -- Configuration of the different sensors.
- """
- self.node = node
-
- # Load cameras
- cameras_conf = sensors_config.get('Cameras', None)
- self.cameras = None
- if cameras_conf:
- self.cameras = self.__create_sensor(cameras_conf, 'camera')
-
- # Load lasers
- lasers_conf = sensors_config.get('Lasers', None)
- self.lasers = None
- if lasers_conf:
- self.lasers = self.__create_sensor(lasers_conf, 'laser')
-
- # Load pose3d
- pose3d_conf = sensors_config.get('Pose3D', None)
- if pose3d_conf:
- self.pose3d = self.__create_sensor(pose3d_conf, 'pose3d')
-
- # Load BirdEyeView
- bird_eye_view_conf = sensors_config.get('BirdEyeView', None)
- self.bird_eye_view = None
- if bird_eye_view_conf:
- self.bird_eye_view = self.__create_sensor(bird_eye_view_conf, 'bird_eye_view')
-
- # Load speedometer
- speedometer_conf = sensors_config.get('Speedometer', None)
- self.speedometer = None
- if speedometer_conf:
- self.speedometer = self.__create_sensor(speedometer_conf, 'speedometer')
-
- def __create_sensor(self, sensor_config, sensor_type):
- """Fill the sensor dictionary with instances of the sensor_type and sensor_config"""
- sensor_dict = {}
- for elem in sensor_config:
- name = sensor_config[elem]['Name']
- topic = sensor_config[elem]['Topic']
- if sensor_type == 'camera':
- sensor_dict[name] = ListenerCamera(self.node, topic)
- elif sensor_type == 'laser':
- sensor_dict[name] = ListenerLaser(self.node, topic)
- elif sensor_type == 'pose3d':
- sensor_dict[name] = ListenerPose3d(self.node, topic)
- elif sensor_type == 'bird_eye_view':
- sensor_dict[name] = BirdEyeView()
- elif sensor_type == 'speedometer':
- sensor_dict[name] = ListenerSpeedometer(self.node, topic)
-
- return sensor_dict
-
- def __get_sensor(self, sensor_name, sensor_type):
- """Retrieve an specific sensor"""
-
- sensor = None
- try:
- if sensor_type == 'camera':
- sensor = self.cameras[sensor_name]
- elif sensor_type == 'laser':
- sensor = self.lasers[sensor_name]
- elif sensor_type == 'pose3d':
- sensor = self.pose3d[sensor_name]
- elif sensor_type == 'bird_eye_view':
- sensor = self.bird_eye_view[sensor_name]
- elif sensor_type == 'speedometer':
- sensor = self.speedometer[sensor_name]
- except KeyError:
- return "[ERROR] No existing camera with {} name.".format(sensor_name)
-
- return sensor
-
- def get_camera(self, camera_name):
- """Retrieve an specific existing camera
-
- Arguments:
- camera_name {str} -- Name of the camera to be retrieved
-
- Returns:
- robot.interfaces.camera.ListenerCamera instance -- camera instance
- """
- return self.__get_sensor(camera_name, 'camera')
-
- def get_laser(self, laser_name):
- """Retrieve an specific existing laser
-
- Arguments:
- laser_name {str} -- Name of the laser to be retrieved
-
- Returns:
- robot.interfaces.laser.ListenerLaser instance -- laser instance
- """
- return self.__get_sensor(laser_name, 'laser')
-
- def get_pose3d(self, pose_name):
- """Retrieve an specific existing pose3d sensor
-
- Arguments:
- pose_name {str} -- Name of the pose3d to be retrieved
-
- Returns:
- robot.interfaces.pose3d.ListenerPose3d instance -- pose3d instance
- """
- return self.__get_sensor(pose_name, 'pose3d')
-
- def get_bird_eye_view(self, bird_eye_view_name):
- """Retrieve an specific existing bird eye view
-
- Arguments:
- bird_eye_view_name {str} -- Name of the birdeyeview to be retrieved
-
- Returns:
- robot.interfaces.birdeyeview.BirdEyeView instance -- birdeyeview instance
- """
- return self.__get_sensor(bird_eye_view_name, 'bird_eye_view')
-
- def kill(self):
- """Destroy all the running sensors"""
- if self.cameras:
- for camera in self.cameras.values():
- camera.stop()
- if self.lasers:
- for laser in self.lasers.values():
- laser.stop()
- if self.pose3d:
- for pose in self.pose3d.values():
- pose.stop()
+#!/usr/bin/env python
+""" This module is responsible for handling the sensors of the robot.
+
+This program is free software: you can redistribute it and/or modify it under
+the terms of the GNU General Public License as published by the Free Software
+Foundation, either version 3 of the License, or (at your option) any later
+version.
+This program is distributed in the hope that it will be useful, but WITHOUT
+ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
+You should have received a copy of the GNU General Public License along with
+this program. If not, see .
+"""
+
+from utils.logger import logger
+from robot.interfaces.camera import ListenerCamera
+from robot.interfaces.laser import ListenerLaser
+from robot.interfaces.pose3d import ListenerPose3d
+try:
+ from robot.interfaces.birdeyeview import BirdEyeView
+except ModuleNotFoundError as ex:
+ logger.error('CARLA is not supported sensor')
+
+from robot.interfaces.speedometer import ListenerSpeedometer
+
+__author__ = 'fqez'
+__contributors__ = []
+__license__ = 'GPLv3'
+
+
+class Sensors:
+ """This class controls the creation of the actuators of the robot
+
+ Attributes:
+ cameras {dict} -- Dictionary which key is the name of the motor and value is a camera instance.
+ laser {dict} -- Dictionary which key is the name of the motor and value is a laser sensor instance.
+ pose3d {dict} -- Dictionary which key is the name of the motor and value is an odometry instance.
+ """
+
+ def __init__(self, sensors_config, node):
+ """Constructor of the class
+
+ Arguments:
+ sensors_config {dict} -- Configuration of the different sensors.
+ """
+ self.node = node
+
+ # Load cameras
+ cameras_conf = sensors_config.get('Cameras', None)
+ self.cameras = None
+ if cameras_conf:
+ self.cameras = self.__create_sensor(cameras_conf, 'camera')
+
+ # Load lasers
+ lasers_conf = sensors_config.get('Lasers', None)
+ self.lasers = None
+ if lasers_conf:
+ self.lasers = self.__create_sensor(lasers_conf, 'laser')
+
+ # Load pose3d
+ pose3d_conf = sensors_config.get('Pose3D', None)
+ if pose3d_conf:
+ self.pose3d = self.__create_sensor(pose3d_conf, 'pose3d')
+
+ # Load BirdEyeView
+ bird_eye_view_conf = sensors_config.get('BirdEyeView', None)
+ self.bird_eye_view = None
+ if bird_eye_view_conf:
+ self.bird_eye_view = self.__create_sensor(bird_eye_view_conf, 'bird_eye_view')
+
+ # Load speedometer
+ speedometer_conf = sensors_config.get('Speedometer', None)
+ self.speedometer = None
+ if speedometer_conf:
+ self.speedometer = self.__create_sensor(speedometer_conf, 'speedometer')
+
+ def __create_sensor(self, sensor_config, sensor_type):
+ """Fill the sensor dictionary with instances of the sensor_type and sensor_config"""
+ sensor_dict = {}
+ for elem in sensor_config:
+ name = sensor_config[elem]['Name']
+ topic = sensor_config[elem]['Topic']
+ if sensor_type == 'camera':
+ sensor_dict[name] = ListenerCamera(self.node, topic)
+ elif sensor_type == 'laser':
+ sensor_dict[name] = ListenerLaser(self.node, topic)
+ elif sensor_type == 'pose3d':
+ sensor_dict[name] = ListenerPose3d(self.node, topic)
+ elif sensor_type == 'bird_eye_view':
+ sensor_dict[name] = BirdEyeView()
+ elif sensor_type == 'speedometer':
+ sensor_dict[name] = ListenerSpeedometer(self.node, topic)
+
+ return sensor_dict
+
+ def __get_sensor(self, sensor_name, sensor_type):
+ """Retrieve an specific sensor"""
+
+ sensor = None
+ try:
+ if sensor_type == 'camera':
+ sensor = self.cameras[sensor_name]
+ elif sensor_type == 'laser':
+ sensor = self.lasers[sensor_name]
+ elif sensor_type == 'pose3d':
+ sensor = self.pose3d[sensor_name]
+ elif sensor_type == 'bird_eye_view':
+ sensor = self.bird_eye_view[sensor_name]
+ elif sensor_type == 'speedometer':
+ sensor = self.speedometer[sensor_name]
+ except KeyError:
+ return "[ERROR] No existing camera with {} name.".format(sensor_name)
+
+ return sensor
+
+ def get_camera(self, camera_name):
+ """Retrieve an specific existing camera
+
+ Arguments:
+ camera_name {str} -- Name of the camera to be retrieved
+
+ Returns:
+ robot.interfaces.camera.ListenerCamera instance -- camera instance
+ """
+ return self.__get_sensor(camera_name, 'camera')
+
+ def get_laser(self, laser_name):
+ """Retrieve an specific existing laser
+
+ Arguments:
+ laser_name {str} -- Name of the laser to be retrieved
+
+ Returns:
+ robot.interfaces.laser.ListenerLaser instance -- laser instance
+ """
+ return self.__get_sensor(laser_name, 'laser')
+
+ def get_pose3d(self, pose_name):
+ """Retrieve an specific existing pose3d sensor
+
+ Arguments:
+ pose_name {str} -- Name of the pose3d to be retrieved
+
+ Returns:
+ robot.interfaces.pose3d.ListenerPose3d instance -- pose3d instance
+ """
+ return self.__get_sensor(pose_name, 'pose3d')
+
+ def get_bird_eye_view(self, bird_eye_view_name):
+ """Retrieve an specific existing bird eye view
+
+ Arguments:
+ bird_eye_view_name {str} -- Name of the birdeyeview to be retrieved
+
+ Returns:
+ robot.interfaces.birdeyeview.BirdEyeView instance -- birdeyeview instance
+ """
+ return self.__get_sensor(bird_eye_view_name, 'bird_eye_view')
+
+ def kill(self):
+ """Destroy all the running sensors"""
+ if self.cameras:
+ for camera in self.cameras.values():
+ camera.stop()
+ if self.lasers:
+ for laser in self.lasers.values():
+ laser.stop()
+ if self.pose3d:
+ for pose in self.pose3d.values():
+ pose.stop()
diff --git a/behavior_metrics/robot/test_sensor_creation.py b/behavior_metrics/robot/test_sensor_creation.py
index a76ee563..686abcc6 100644
--- a/behavior_metrics/robot/test_sensor_creation.py
+++ b/behavior_metrics/robot/test_sensor_creation.py
@@ -1,10 +1,10 @@
-from sensors import Sensors
-import yaml
-
-if __name__ == '__main__':
-
- with open('../driver.yml') as file:
- cfg = yaml.safe_load(file)
-
- sensors_cfg = cfg['Behaviors']['Robots']['Robot_0']['Sensors']
- sensors = Sensors(sensors_cfg)
+from sensors import Sensors
+import yaml
+
+if __name__ == '__main__':
+
+ with open('../driver.yml') as file:
+ cfg = yaml.safe_load(file)
+
+ sensors_cfg = cfg['Behaviors']['Robots']['Robot_0']['Sensors']
+ sensors = Sensors(sensors_cfg)
diff --git a/behavior_metrics/ui/__init__.py b/behavior_metrics/ui/__init__.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/ui/gui/resources/assets/carla_black.png b/behavior_metrics/ui/gui/resources/assets/carla_black.png
deleted file mode 100644
index 2a800a01..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/carla_black.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/carla_light.png b/behavior_metrics/ui/gui/resources/assets/carla_light.png
deleted file mode 100644
index aee88575..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/carla_light.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/gazebo_dark.png b/behavior_metrics/ui/gui/resources/assets/gazebo_dark.png
deleted file mode 100644
index 8fb29035..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/gazebo_dark.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/gazebo_dark_full.png b/behavior_metrics/ui/gui/resources/assets/gazebo_dark_full.png
deleted file mode 100644
index 3bb79f57..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/gazebo_dark_full.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/gazebo_light.png b/behavior_metrics/ui/gui/resources/assets/gazebo_light.png
deleted file mode 100644
index 2dda1631..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/gazebo_light.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/gazebo_light_full.png b/behavior_metrics/ui/gui/resources/assets/gazebo_light_full.png
deleted file mode 100644
index 93df18a2..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/gazebo_light_full.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/gear_dark.png b/behavior_metrics/ui/gui/resources/assets/gear_dark.png
deleted file mode 100644
index f5ce0e9c..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/gear_dark.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/gear_light.png b/behavior_metrics/ui/gui/resources/assets/gear_light.png
deleted file mode 100644
index deeefd96..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/gear_light.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/github.png b/behavior_metrics/ui/gui/resources/assets/github.png
deleted file mode 100644
index 6c3b3cd1..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/github.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/info_icon.png b/behavior_metrics/ui/gui/resources/assets/info_icon.png
deleted file mode 100644
index 6a01cef6..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/info_icon.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/load.png b/behavior_metrics/ui/gui/resources/assets/load.png
deleted file mode 100644
index 2c941b50..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/load.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/logo.svg b/behavior_metrics/ui/gui/resources/assets/logo.svg
deleted file mode 100644
index 8051c68e..00000000
--- a/behavior_metrics/ui/gui/resources/assets/logo.svg
+++ /dev/null
@@ -1,3 +0,0 @@
-
-
-
\ No newline at end of file
diff --git a/behavior_metrics/ui/gui/resources/assets/logo_100.svg b/behavior_metrics/ui/gui/resources/assets/logo_100.svg
deleted file mode 100644
index 4d50538f..00000000
--- a/behavior_metrics/ui/gui/resources/assets/logo_100.svg
+++ /dev/null
@@ -1,9 +0,0 @@
-
-
diff --git a/behavior_metrics/ui/gui/resources/assets/logo_200.svg b/behavior_metrics/ui/gui/resources/assets/logo_200.svg
deleted file mode 100644
index dc102a72..00000000
--- a/behavior_metrics/ui/gui/resources/assets/logo_200.svg
+++ /dev/null
@@ -1,9 +0,0 @@
-
-
diff --git a/behavior_metrics/ui/gui/resources/assets/pause.png b/behavior_metrics/ui/gui/resources/assets/pause.png
deleted file mode 100644
index 9b08f4e2..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/pause.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/pause_dark.png b/behavior_metrics/ui/gui/resources/assets/pause_dark.png
deleted file mode 100644
index e6bbb685..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/pause_dark.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/play.png b/behavior_metrics/ui/gui/resources/assets/play.png
deleted file mode 100644
index e50351b7..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/play.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/play_dark.png b/behavior_metrics/ui/gui/resources/assets/play_dark.png
deleted file mode 100644
index b95ee955..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/play_dark.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/recording.png b/behavior_metrics/ui/gui/resources/assets/recording.png
deleted file mode 100644
index 55097738..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/recording.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/reload.png b/behavior_metrics/ui/gui/resources/assets/reload.png
deleted file mode 100644
index fe0c2e23..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/reload.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/reload_dark.png b/behavior_metrics/ui/gui/resources/assets/reload_dark.png
deleted file mode 100644
index fc0c8826..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/reload_dark.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/twitter.png b/behavior_metrics/ui/gui/resources/assets/twitter.png
deleted file mode 100644
index 359af70f..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/twitter.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/assets/youtube.png b/behavior_metrics/ui/gui/resources/assets/youtube.png
deleted file mode 100644
index bfd6db39..00000000
Binary files a/behavior_metrics/ui/gui/resources/assets/youtube.png and /dev/null differ
diff --git a/behavior_metrics/ui/gui/resources/worlds.json b/behavior_metrics/ui/gui/resources/worlds.json
deleted file mode 100644
index b25fd33d..00000000
--- a/behavior_metrics/ui/gui/resources/worlds.json
+++ /dev/null
@@ -1,281 +0,0 @@
-{
- "f1": [
- {
- "name": "Simple circuit",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/simple_circuit.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Simple circuit",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/simple_circuit_basic.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Simple circuit",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/simple_circuit_no_red_line.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Simple circuit",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/simple_circuit_no_red_line_no_wall.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Simple circuit",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/simple_circuit_no_sun.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Simple circuit",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/simple_circuit_no_wall.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Simple circuit",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/simple_circuit_white_line.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Simple circuit",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/simple_circuit_white_road.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Simple circuit",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/simple_circuit_white_road_no_red_line.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Nurburgring",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/nurburgring_line.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Nurburgring",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/nurburgring_line_no_wall.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Nurburgring",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/nurburgring_no_red_line.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Nurburgring",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/nurburgring_no_red_line_no_wall.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Montmelo",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/montmelo_line.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Montmelo",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/montmelo_line_no_sun.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Montmelo",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/montmelo_line_no_wall.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Montmelo",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/montmelo_no_red_line.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Montmelo",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/montmelo_no_red_line_no_wall.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Montmelo",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/montmelo_white_line.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Montmelo",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/montmelo_white_road.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Montmelo",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/montmelo_white_road_no_red_line.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Montreal",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/montreal_line.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Montreal",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/montreal_line_no_wall.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Montreal",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/montreal_no_red_line.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Montreal",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/montreal_no_red_line_no_wall.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Many curves",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/many_curves.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Many curves",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/many_curves_no_red_line.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Many curves",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/many_curves_no_red_line_no_wall.launch",
- "description": "Description",
- "model": "f1"
- },
- {
- "name": "Many curves",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/many_curves_no_wall.launch",
- "description": "Description",
- "model": "f1"
- }
- ],
- "f1rl": [
- {
- "name": "Simple circuit",
- "world": "BehaviorMetrics/gym-gazebo/gym_gazebo/envs/assets/launch/F1Lasercircuit_v0.launch",
- "description": "Description",
- "model": "f1-rl"
- }
- ],
- "drone": [
- {
- "name": "Follow road",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/iris_follow_road.launch",
- "description": "Description"
- },
- {
- "name": "Cat and mouse",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/drone_hangar.launch",
- "description": "Description"
- },
- {
- "name": "Labyrinth",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/iris_labyrinth.launch",
- "description": "Description"
- },
- {
- "name": "Hangar",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/iris_drone_hangar.launch",
- "description": "Description"
- },
- {
- "name": "Position control",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/iris_position_control.launch",
- "description": "Description"
- },
- {
- "name": "Follow Turtlebot",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/iris_follow_turtlebot.launch",
- "description": "Description"
- },
- {
- "name": "Visual lander",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/iris_visual_lander.launch",
- "description": "Description"
- },
- {
- "name": "Rescue people",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/iris_rescue_people.launch",
- "description": "Description"
- },
- {
- "name": "Position control",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/iris_position_control.launch",
- "description": "Description"
- }
- ],
- "turtlebot": [
- {
- "name": "Empty world",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/kobuki_1_simpleROS.launch",
- "description": "Description"
- }
- ],
- "car": [
- {
- "name": "Junction",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/car_1_junction.launch",
- "description": "Description"
- },
- {
- "name": "Parking",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/car_1_parking.launch",
- "description": "Description"
- },
- {
- "name": "Global navigation",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/taxiholo_1_citylarge.launch",
- "description": "Description"
- },
- {
- "name": "Global navigation small",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/taxiholo_1_citymedium.launch",
- "description": "Description"
- }
- ],
- "roomba": [
- {
- "name": "Vacuum room",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/roomba_1_houseroom.launch",
- "description": "Description"
- },
- {
- "name": "Vacuum house",
- "world": "/opt/jderobot/share/jderobot/gazebo/launch/roomba_1_house.launch",
- "description": "Description"
- }
- ],
- "CARLA": [
- {
- "name": "Town01",
- "world": "/home/canveo/carla_ws/ros-bridge/src/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py",
- "description": "Description"
- }
- ]
-}
diff --git a/behavior_metrics/ui/gui/views/toolbar.py b/behavior_metrics/ui/gui/views/toolbar.py
index 4a0c4594..1222c001 100644
--- a/behavior_metrics/ui/gui/views/toolbar.py
+++ b/behavior_metrics/ui/gui/views/toolbar.py
@@ -567,6 +567,7 @@ def create_simulation_gb(self):
start_pause_simulation_label.setToolTip('Start/Pause the simulation')
reset_simulation = ClickableLabel('reset', 40, QPixmap(self.gui_views_path + '/resources/assets/reload.png'), parent=self)
reset_simulation.setToolTip('Reset the simulation')
+ reset_simulation.clicked.connect(self.reset_simulation)
if type(self.controller) == controller_carla.ControllerCarla:
carla_image = ClickableLabel('carlacli', 40, QPixmap(self.gui_views_path + '/resources/assets/carla_light.png'), parent=self)
carla_image.setToolTip('Open/Close simulator window')
@@ -794,7 +795,8 @@ def load_brain(self):
self.current_brain_label.setText('Current brain: ' + txt)
# load brain from controller
- self.controller.reload_brain(brains_path + self.configuration.robot_type + '/' + brain)
+ # FIX: Using restart_simulation instead of reload_brain to fully reset CARLA
+ self.controller.restart_simulation()
# save to configuration
self.configuration.brain_path = brains_path + self.configuration.robot_type + '/' + brain
diff --git a/behavior_metrics/ui/tui/__init__.py b/behavior_metrics/ui/tui/__init__.py
old mode 100755
new mode 100644
diff --git a/behavior_metrics/ui/tui/keyboard_handler.py b/behavior_metrics/ui/tui/keyboard_handler.py
old mode 100755
new mode 100644
index 808b1ff8..1d529028
--- a/behavior_metrics/ui/tui/keyboard_handler.py
+++ b/behavior_metrics/ui/tui/keyboard_handler.py
@@ -1,56 +1,56 @@
-"""
- * Grabar dataset (r, record)
- * Cargar dataset (l, load)
- * Pausar piloto (p, pause) -> abrir el tui
- * Relanzar piloto (u, unpause)
- * Cambiar cerebro (c, change)
- * Evaluar comportamiento (e, evaluate)
-"""
-from pynput import keyboard
-
-# from ui.ros_ui_com import Communicator
-
-class KHandler:
-
- last_key = None
-
- def __init__(self, controller):
- self.listener = keyboard.Listener(
- on_press=self.on_press,
- on_release=self.on_release
- )
- self.controller = controller
- # self.comm = Communicator()
-
- def on_press(self, key):
- try:
- # print('Pressed key'.format(key.char))
- # self.comm.send_msg(key.char)
- self.last_key = key.char
- except AttributeError:
- # print('Not alphanumeric'.format(key))
- pass
-
- def on_release(self, key):
- # print('Released'.format(key))
- if key == keyboard.Key.esc:
- self.last_key = '-1'
- # self.comm.send_msg('quit')
- return False
-
- def start(self):
- self.listener.start()
-
- def stop(self):
- self.listener.stop()
-
- def set_dset_dir(self, dset_out):
- pass
-
- def set_dset_name(self, dset_name):
- pass
- def set_topics(self, topics_box):
- pass
-
- def set_brain(self, brain):
+"""
+ * Grabar dataset (r, record)
+ * Cargar dataset (l, load)
+ * Pausar piloto (p, pause) -> abrir el tui
+ * Relanzar piloto (u, unpause)
+ * Cambiar cerebro (c, change)
+ * Evaluar comportamiento (e, evaluate)
+"""
+from pynput import keyboard
+
+# from ui.ros_ui_com import Communicator
+
+class KHandler:
+
+ last_key = None
+
+ def __init__(self, controller):
+ self.listener = keyboard.Listener(
+ on_press=self.on_press,
+ on_release=self.on_release
+ )
+ self.controller = controller
+ # self.comm = Communicator()
+
+ def on_press(self, key):
+ try:
+ # print('Pressed key'.format(key.char))
+ # self.comm.send_msg(key.char)
+ self.last_key = key.char
+ except AttributeError:
+ # print('Not alphanumeric'.format(key))
+ pass
+
+ def on_release(self, key):
+ # print('Released'.format(key))
+ if key == keyboard.Key.esc:
+ self.last_key = '-1'
+ # self.comm.send_msg('quit')
+ return False
+
+ def start(self):
+ self.listener.start()
+
+ def stop(self):
+ self.listener.stop()
+
+ def set_dset_dir(self, dset_out):
+ pass
+
+ def set_dset_name(self, dset_name):
+ pass
+ def set_topics(self, topics_box):
+ pass
+
+ def set_brain(self, brain):
pass
\ No newline at end of file
diff --git a/behavior_metrics/utils/tmp_world_generator.py b/behavior_metrics/utils/tmp_world_generator.py
deleted file mode 100644
index 6511f611..00000000
--- a/behavior_metrics/utils/tmp_world_generator.py
+++ /dev/null
@@ -1,121 +0,0 @@
-#!/usr/bin/env python
-
-"""This module contains the random initializer.
-
-This module is used if you want to use random initialization of your robot
-in the GUI mode. It creates a tmp launch file with the same configuration
-as the original one but with a different initial position of the robot.
-
-This program is free software: you can redistribute it and/or modify it under
-the terms of the GNU General Public License as published by the Free Software
-Foundation, either version 3 of the License, or (at your option) any later
-version.
-This program is distributed in the hope that it will be useful, but WITHOUT
-ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
-FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
-You should have received a copy of the GNU General Public License along with
-this program. If not, see .
-"""
-
-import subprocess
-import xml.etree.ElementTree as ET
-import time
-import os
-# import rospy
-import random
-import sys
-import math
-
-import numpy as np
-
-from utils import metrics_gazebo
-from utils import environment
-from utils.logger import logger
-
-ros_version = os.environ.get('ROS_VERSION', '2')
-if ros_version == '2':
- import rclpy
-else:
- import rospy
-
-def tmp_world_generator(current_world, stats_perfect_lap, real_time_update_rate, randomize=False, gui=False,
- launch=False, close_ros_resources=True):
- environment.close_ros_and_simulators(close_ros_resources)
- tree = ET.parse(current_world)
- root = tree.getroot()
- for child in root[0]:
- if child.attrib['name'] == 'gui':
- if gui:
- child.attrib['value'] = 'true'
- else:
- child.attrib['value'] = 'false'
- if child.attrib['name'] == 'world_name':
- world_name = child.attrib['value']
- child.attrib['value'] = os.getcwd() + '/tmp_world.launch'
-
- tree.write('tmp_circuit.launch')
- tree = ET.parse(os.path.dirname(os.path.dirname(current_world)) + '/worlds/' + world_name)
- root = tree.getroot()
-
- perfect_lap_checkpoints, circuit_diameter = metrics_gazebo.read_perfect_lap_rosbag(stats_perfect_lap)
-
- if randomize:
- random_index = random.randint(0, int(len(perfect_lap_checkpoints)))
- random_point = perfect_lap_checkpoints[random_index]
-
- p1 = perfect_lap_checkpoints[random_index]
- p2 = perfect_lap_checkpoints[random_index + 5]
- delta_y = p2['pose.pose.position.y'] - p1['pose.pose.position.y']
- delta_x = p2['pose.pose.position.x'] - p1['pose.pose.position.x']
- result = math.atan2(delta_y, delta_x)
- result = math.degrees(result)
- if result < 0:
- result = 360 + result
-
- # Half chances of orientating the car to the exactly opposite direction
- random_orientation = random.randint(0, 1)
- if random_orientation == 1:
- result = (result + 180) % 360
-
- radians = math.radians(result)
- orientation_z = radians
-
- random_start_point = np.array(
- [round(random_point['pose.pose.position.x'], 3), round(random_point['pose.pose.position.y'], 3),
- round(random_point['pose.pose.position.z'], 3), round(random_point['pose.pose.orientation.x'], 3),
- round(random_point['pose.pose.orientation.y'], 3), round(orientation_z, 3)])
-
- for child_1 in root[0]:
- if child_1.tag == 'include':
- next = False
- for child_2 in child_1:
- if next:
- child_2.text = str(random_start_point[0]) + " " + str(random_start_point[1]) + " " + str(
- random_start_point[2]) + " " + str(random_start_point[3]) + " " + str(
- random_start_point[4]) + " " + str(random_start_point[5])
- next = False
- elif child_2.text == 'model://f1_renault':
- next = True
-
- # Add physics real time update rate value
- physics_element = ET.SubElement(root[0], 'physics')
- physics_element.set("type", "ode")
- real_time_update_rate_element = ET.SubElement(physics_element, 'real_time_update_rate')
- real_time_update_rate_element.text = str(real_time_update_rate) # 1000 is the default value
-
- tree.write('tmp_world.launch')
- if launch:
- try:
- with open("/tmp/.roslaunch_stdout.log", "w") as out, open("/tmp/.roslaunch_stderr.log", "w") as err:
- if ros_version == '1':
- subprocess.Popen(["roslaunch", 'tmp_circuit.launch'], stdout=out, stderr=err)
- elif ros_version == '2':
- subprocess.Popen(["ros2" "launch", 'tmp_circuit.launch'], stdout=out, stderr=err)
- logger.info("SimulatorEnv: launching gzserver.")
- except OSError as oe:
- logger.error("SimulatorEnv: exception raised launching gzserver. {}".format(oe))
- environment.close_ros_and_simulators()
- sys.exit(-1)
-
- # give simulator some time to initialize
- time.sleep(5)
diff --git a/behavior_metrics/var_entorno.sh b/behavior_metrics/var_entorno.sh
old mode 100755
new mode 100644