From 1af4057526187dea5f8b6501e6cfaa08ead3890e Mon Sep 17 00:00:00 2001 From: annika Date: Tue, 16 Jan 2024 17:35:01 +0100 Subject: [PATCH 01/10] added fixedFrameState.py --- src/svea_sensors/launch/localize.launch | 5 +- .../launch/sensors_launch/rtk.launch | 10 ++- src/svea_sensors/scripts/fixedframestate.py | 89 +++++++++++++++++++ 3 files changed, 101 insertions(+), 3 deletions(-) create mode 100755 src/svea_sensors/scripts/fixedframestate.py diff --git a/src/svea_sensors/launch/localize.launch b/src/svea_sensors/launch/localize.launch index 5888d2a0..43241647 100644 --- a/src/svea_sensors/launch/localize.launch +++ b/src/svea_sensors/launch/localize.launch @@ -89,7 +89,7 @@ - + @@ -160,4 +160,7 @@ + + + diff --git a/src/svea_sensors/launch/sensors_launch/rtk.launch b/src/svea_sensors/launch/sensors_launch/rtk.launch index 3e47fc93..8836f0a6 100644 --- a/src/svea_sensors/launch/sensors_launch/rtk.launch +++ b/src/svea_sensors/launch/sensors_launch/rtk.launch @@ -16,8 +16,14 @@ - - + + + + + + + + diff --git a/src/svea_sensors/scripts/fixedframestate.py b/src/svea_sensors/scripts/fixedframestate.py new file mode 100755 index 00000000..5e79f75a --- /dev/null +++ b/src/svea_sensors/scripts/fixedframestate.py @@ -0,0 +1,89 @@ +#!/usr/bin/env python3 +import rospy +import tf2_ros + +import numpy as np + +from geopy.distance import geodesic + +from std_msgs.msg import Float64 +from sensor_msgs.msg import NavSatFix +from svea_msgs.msg import VehicleState +from geometry_msgs.msg import TransformStamped, Vector3, Quaternion + + +class FixedFrameState: + def __init__(self): + # Initialize node + rospy.init_node('FixedFrameState') + + # Subscriber + rospy.Subscriber('/gps/filtered', NavSatFix, self.gpsFilteredCallback) + + # Publisher + self.FixedFrameState = rospy.Publisher('/FixedFrameState', VehicleState, queue_size=10) + + # Fixed GPS latitude, Longitude + self.fixed_gps = (59.350791, 18.067825) #ITRL pose + + # Transformation + self.buffer = tf2_ros.Buffer(rospy.Duration(10)) + self.listener = tf2_ros.TransformListener(self.buffer) + self.br = tf2_ros.TransformBroadcaster() + + def run(self): + rospy.spin() + + def gpsFilteredCallback(self, msg): + filtered_gps = (msg.latitude, msg.longitude) + x, y = self.LatLongToXY(filtered_gps) + self.StateMsg(msg.header, x,y) + + def LatLongToXY(self, filtered_gps): + distance = geodesic(self.fixed_gps, filtered_gps).meters + + bearing = self.CalculateBearing(filtered_gps) + + # Convert bearing and distance to x, y coordinates + x = distance * np.sin(np.radians(bearing)) + y = distance * np.cos(np.radians(bearing)) + + return x, y + + def CalculateBearing(self, filtered_gps): + lat1 = np.radians(self.fixed_gps[0]) + lat2 = np.radians(filtered_gps[0]) + diffLong = np.radians(filtered_gps[1] - self.fixed_gps[1]) + + x = np.sin(diffLong) * np.cos(lat2) + y = np.cos(lat1) * np.sin(lat2) - (np.sin(lat1) * np.cos(lat2) * np.cos(diffLong)) + + initial_bearing = np.arctan2(x, y) + + initial_bearing = np.degrees(initial_bearing) + compass_bearing = (initial_bearing + 360) % 360 + + return compass_bearing + + def StateMsg(self, header, x, y): + msg = VehicleState() + msg.header = header + msg.child_frame_id = "base_link_fixed" + msg.x = x + msg.y = y + msg.yaw = 0 + msg.v = 0 + msg.covariance = [0, 0, 0, 0, + 0, 0, 0, 0, + 0, 0, 0, 0, + 0, 0, 0, 0] + self.FixedFrameState.publish(msg) + + msgT = TransformStamped() + msgT.header = header + msgT.child_frame_id = "base_link_fixed" + msgT.transform.translation = Vector3(*[x,y,0.0]) + msgT.transform.rotation = Quaternion(*[0.0, 0.0, 0.0, 1.0]) + self.br.sendTransform(msgT) +if __name__ == '__main__': + FixedFrameState().run() From 64ef5c26ee849202f8e9c6dfdd6f90f0d29620f7 Mon Sep 17 00:00:00 2001 From: annika Date: Wed, 17 Jan 2024 12:18:39 +0100 Subject: [PATCH 02/10] Added the fixed_gps frame and requirement --- requirements.txt | 1 + src/svea_sensors/scripts/fixedframestate.py | 48 ++++++++++++++------- 2 files changed, 34 insertions(+), 15 deletions(-) diff --git a/requirements.txt b/requirements.txt index adfbcf5f..facdef68 100644 --- a/requirements.txt +++ b/requirements.txt @@ -11,3 +11,4 @@ pyserial pyubx2 geopy +pyproj \ No newline at end of file diff --git a/src/svea_sensors/scripts/fixedframestate.py b/src/svea_sensors/scripts/fixedframestate.py index 5e79f75a..d6012285 100755 --- a/src/svea_sensors/scripts/fixedframestate.py +++ b/src/svea_sensors/scripts/fixedframestate.py @@ -5,8 +5,8 @@ import numpy as np from geopy.distance import geodesic +from pyproj import Proj -from std_msgs.msg import Float64 from sensor_msgs.msg import NavSatFix from svea_msgs.msg import VehicleState from geometry_msgs.msg import TransformStamped, Vector3, Quaternion @@ -18,25 +18,40 @@ def __init__(self): rospy.init_node('FixedFrameState') # Subscriber - rospy.Subscriber('/gps/filtered', NavSatFix, self.gpsFilteredCallback) + rospy.Subscriber('/gps/filtered', NavSatFix, self.GpsFilteredCallback) # Publisher - self.FixedFrameState = rospy.Publisher('/FixedFrameState', VehicleState, queue_size=10) + self.FixedFrameState = rospy.Publisher('/fixedgps/state', VehicleState, queue_size=10) # Fixed GPS latitude, Longitude - self.fixed_gps = (59.350791, 18.067825) #ITRL pose + self.fixed_gps = rospy.get_param("~fixed_gps", (59.350791, 18.067825)) + self.show_frame = rospy.get_param("~show_frame", True) + # self.fixed_gps = (59.350791, 18.067825) #(latitude, longitude) #ITRL pose # Transformation self.buffer = tf2_ros.Buffer(rospy.Duration(10)) self.listener = tf2_ros.TransformListener(self.buffer) self.br = tf2_ros.TransformBroadcaster() + self.static_br = tf2_ros.StaticTransformBroadcaster() + + self.PublishFixedGpsFrame() def run(self): rospy.spin() - def gpsFilteredCallback(self, msg): - filtered_gps = (msg.latitude, msg.longitude) - x, y = self.LatLongToXY(filtered_gps) + def PublishFixedGpsFrame(self): + projection = Proj(proj='utm', zone=34, ellps='WGS84') + utm = projection(self.fixed_gps[1], self.fixed_gps[0]) + FixedGpsFrame = TransformStamped() + FixedGpsFrame.header.stamp = rospy.Time.now() + FixedGpsFrame.header.frame_id = "utm" + FixedGpsFrame.child_frame_id = "Fixed_gps" + FixedGpsFrame.transform.translation = Vector3(*[utm[0], utm[1], 0.0]) + FixedGpsFrame.transform.rotation = Quaternion(*[0.0, 0.0, 0.0, 1.0]) + self.static_br.sendTransform(FixedGpsFrame) + + def GpsFilteredCallback(self, msg): + x, y = self.LatLongToXY((msg.latitude, msg.longitude)) self.StateMsg(msg.header, x,y) def LatLongToXY(self, filtered_gps): @@ -44,7 +59,6 @@ def LatLongToXY(self, filtered_gps): bearing = self.CalculateBearing(filtered_gps) - # Convert bearing and distance to x, y coordinates x = distance * np.sin(np.radians(bearing)) y = distance * np.cos(np.radians(bearing)) @@ -68,7 +82,8 @@ def CalculateBearing(self, filtered_gps): def StateMsg(self, header, x, y): msg = VehicleState() msg.header = header - msg.child_frame_id = "base_link_fixed" + msg.header.frame_id = "Fixed_gps" + msg.child_frame_id = "base_link_fixed_gps" msg.x = x msg.y = y msg.yaw = 0 @@ -79,11 +94,14 @@ def StateMsg(self, header, x, y): 0, 0, 0, 0] self.FixedFrameState.publish(msg) - msgT = TransformStamped() - msgT.header = header - msgT.child_frame_id = "base_link_fixed" - msgT.transform.translation = Vector3(*[x,y,0.0]) - msgT.transform.rotation = Quaternion(*[0.0, 0.0, 0.0, 1.0]) - self.br.sendTransform(msgT) + if self.show_frame: + msgT = TransformStamped() + msgT.header = header + msgT.header.frame_id = "Fixed_gps" + msgT.child_frame_id = "base_link_fixed_gps" + msgT.transform.translation = Vector3(*[x,y,0.0]) + msgT.transform.rotation = Quaternion(*[0.0, 0.0, 0.0, 1.0]) + self.br.sendTransform(msgT) + if __name__ == '__main__': FixedFrameState().run() From c8dd379a4f6553f0c9a2213a8a2a9a6714c9020a Mon Sep 17 00:00:00 2001 From: annika Date: Tue, 23 Jan 2024 11:43:05 +0100 Subject: [PATCH 03/10] First commit --- src/svea_sensors/params/robot_localization/global_ekf.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/svea_sensors/params/robot_localization/global_ekf.yaml b/src/svea_sensors/params/robot_localization/global_ekf.yaml index ad412183..983a829e 100644 --- a/src/svea_sensors/params/robot_localization/global_ekf.yaml +++ b/src/svea_sensors/params/robot_localization/global_ekf.yaml @@ -48,7 +48,7 @@ odom0_queue_size: 8 odom0_nodelay: true odom0_relative: false odom0_differential: false -odom0_pose_rejection_threshold: 5 +odom0_pose_rejection_threshold: 200 ########################################## # BNO055 IMU ############################# From 8d86a18740d95ab637fcf41e0abc3549e3eea916 Mon Sep 17 00:00:00 2001 From: Annika-wyt Date: Tue, 23 Jan 2024 11:49:30 +0100 Subject: [PATCH 04/10] added analysis --- .gitignore | 3 +- analysis.ipynb | 2980 ++++++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 2982 insertions(+), 1 deletion(-) create mode 100644 analysis.ipynb diff --git a/.gitignore b/.gitignore index 946666c3..bbe812a6 100644 --- a/.gitignore +++ b/.gitignore @@ -12,4 +12,5 @@ __pycache__/ src/.vscode/ venv/ -site/ \ No newline at end of file +site/ +rosbag/ \ No newline at end of file diff --git a/analysis.ipynb b/analysis.ipynb new file mode 100644 index 00000000..26211f16 --- /dev/null +++ b/analysis.ipynb @@ -0,0 +1,2980 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "import rosbag\n", + "from std_msgs.msg import String # Import the message type you expect to read\n", + "\n", + "# Specify the path to your ROS bag file\n", + "bag_path = '/home/annika/ITRL/GPS_frame/rosbag/2024-01-23-11-08-25.bag'\n", + "FixedFrameState1 = []\n", + "Lat1 = []\n", + "Long1 = []\n", + "# Open the bag file\n", + "with rosbag.Bag(bag_path, 'r') as bag:\n", + " # Iterate through messages in the bag\n", + " for topic, msg, t in bag.read_messages():\n", + " # Process the messages based on the topic\n", + " if topic == '/fixedgps/state':\n", + " FixedFrameState1.append([msg.x,msg.y])\n", + " if topic == '/gps/filtered':\n", + " Lat1.append(msg.latitude)\n", + " Long1.append(msg.longitude)\n", + "# Note: Replace '/your/topic' with the actual topic you are interested in\n", + "# You also need to import the correct message type for the specified topic\n" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "import rosbag\n", + "from std_msgs.msg import String # Import the message type you expect to read\n", + "\n", + "# Specify the path to your ROS bag file\n", + "bag_path = '/home/annika/ITRL/GPS_frame/rosbag/2024-01-23-11-12-00.bag'\n", + "FixedFrameState2 = []\n", + "Lat2 = []\n", + "Long2 = []\n", + "\n", + "# Open the bag file\n", + "with rosbag.Bag(bag_path, 'r') as bag:\n", + " # Iterate through messages in the bag\n", + " for topic, msg, t in bag.read_messages():\n", + " # Process the messages based on the topic\n", + " if topic == '/fixedgps/state':\n", + " FixedFrameState2.append([msg.x,msg.y])\n", + " if topic == '/gps/filtered':\n", + " Lat2.append(msg.latitude)\n", + " Long2.append(msg.longitude)\n", + "# Note: Replace '/your/topic' with the actual topic you are interested in\n", + "# You also need to import the correct message type for the specified topic\n" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "import matplotlib.pyplot as plt\n", + "\n", + "x_values1, y_values1 = zip(*FixedFrameState1)\n", + "x_values2, y_values2 = zip(*FixedFrameState2)\n", + "\n", + "# Create a scatter plot for the first set of coordinates\n", + "plt.scatter(x_values1, y_values1, marker='o', label='Coordinates 1')\n", + "\n", + "# Create a scatter plot for the second set of coordinates\n", + "plt.scatter(x_values2, y_values2, marker='s', label='Coordinates 2')\n", + "\n", + "# Add labels and title\n", + "plt.xlabel('X-axis')\n", + "plt.xlim(10,20)\n", + "plt.ylim(5,20)\n", + "plt.ylabel('Y-axis')\n", + "plt.title('Scatter Plot of Coordinates')\n", + "\n", + "# Add a legend\n", + "plt.legend()\n", + "\n", + "# Display the plot\n", + "plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "ename": "ValueError", + "evalue": "Mime type rendering requires nbformat>=4.2.0 but it is not installed", + "output_type": "error", + "traceback": [ + "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", + "\u001b[0;31mValueError\u001b[0m Traceback (most recent call last)", + "File \u001b[0;32m~/.local/lib/python3.8/site-packages/IPython/core/formatters.py:922\u001b[0m, in \u001b[0;36mIPythonDisplayFormatter.__call__\u001b[0;34m(self, obj)\u001b[0m\n\u001b[1;32m 920\u001b[0m method \u001b[38;5;241m=\u001b[39m get_real_method(obj, \u001b[38;5;28mself\u001b[39m\u001b[38;5;241m.\u001b[39mprint_method)\n\u001b[1;32m 921\u001b[0m \u001b[38;5;28;01mif\u001b[39;00m method \u001b[38;5;129;01mis\u001b[39;00m \u001b[38;5;129;01mnot\u001b[39;00m \u001b[38;5;28;01mNone\u001b[39;00m:\n\u001b[0;32m--> 922\u001b[0m \u001b[43mmethod\u001b[49m\u001b[43m(\u001b[49m\u001b[43m)\u001b[49m\n\u001b[1;32m 923\u001b[0m \u001b[38;5;28;01mreturn\u001b[39;00m \u001b[38;5;28;01mTrue\u001b[39;00m\n", + "File \u001b[0;32m/usr/local/lib/python3.8/dist-packages/plotly/basedatatypes.py:834\u001b[0m, in \u001b[0;36mBaseFigure._ipython_display_\u001b[0;34m(self)\u001b[0m\n\u001b[1;32m 831\u001b[0m \u001b[38;5;28;01mimport\u001b[39;00m \u001b[38;5;21;01mplotly\u001b[39;00m\u001b[38;5;21;01m.\u001b[39;00m\u001b[38;5;21;01mio\u001b[39;00m \u001b[38;5;28;01mas\u001b[39;00m \u001b[38;5;21;01mpio\u001b[39;00m\n\u001b[1;32m 833\u001b[0m \u001b[38;5;28;01mif\u001b[39;00m pio\u001b[38;5;241m.\u001b[39mrenderers\u001b[38;5;241m.\u001b[39mrender_on_display \u001b[38;5;129;01mand\u001b[39;00m pio\u001b[38;5;241m.\u001b[39mrenderers\u001b[38;5;241m.\u001b[39mdefault:\n\u001b[0;32m--> 834\u001b[0m \u001b[43mpio\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43mshow\u001b[49m\u001b[43m(\u001b[49m\u001b[38;5;28;43mself\u001b[39;49m\u001b[43m)\u001b[49m\n\u001b[1;32m 835\u001b[0m \u001b[38;5;28;01melse\u001b[39;00m:\n\u001b[1;32m 836\u001b[0m \u001b[38;5;28mprint\u001b[39m(\u001b[38;5;28mrepr\u001b[39m(\u001b[38;5;28mself\u001b[39m))\n", + "File \u001b[0;32m/usr/local/lib/python3.8/dist-packages/plotly/io/_renderers.py:396\u001b[0m, in \u001b[0;36mshow\u001b[0;34m(fig, renderer, validate, **kwargs)\u001b[0m\n\u001b[1;32m 391\u001b[0m \u001b[38;5;28;01mraise\u001b[39;00m \u001b[38;5;167;01mValueError\u001b[39;00m(\n\u001b[1;32m 392\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mMime type rendering requires ipython but it is not installed\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 393\u001b[0m )\n\u001b[1;32m 395\u001b[0m \u001b[38;5;28;01mif\u001b[39;00m \u001b[38;5;129;01mnot\u001b[39;00m nbformat \u001b[38;5;129;01mor\u001b[39;00m Version(nbformat\u001b[38;5;241m.\u001b[39m__version__) \u001b[38;5;241m<\u001b[39m Version(\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m4.2.0\u001b[39m\u001b[38;5;124m\"\u001b[39m):\n\u001b[0;32m--> 396\u001b[0m \u001b[38;5;28;01mraise\u001b[39;00m \u001b[38;5;167;01mValueError\u001b[39;00m(\n\u001b[1;32m 397\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mMime type rendering requires nbformat>=4.2.0 but it is not installed\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 398\u001b[0m )\n\u001b[1;32m 400\u001b[0m ipython_display\u001b[38;5;241m.\u001b[39mdisplay(bundle, raw\u001b[38;5;241m=\u001b[39m\u001b[38;5;28;01mTrue\u001b[39;00m)\n\u001b[1;32m 402\u001b[0m \u001b[38;5;66;03m# external renderers\u001b[39;00m\n", + "\u001b[0;31mValueError\u001b[0m: Mime type rendering requires nbformat>=4.2.0 but it is not installed" + ] + }, + { + "data": { + "application/vnd.plotly.v1+json": { + "config": { + "plotlyServerURL": "https://plot.ly" + }, + "data": [ + { + "lat": [ + 59.35093418921517, + 59.35093398436031, + 59.350933935363415, + 59.35093387974216, + 59.350933760629964, + 59.35093368184484, + 59.3509335391803, + 59.3509334457256, + 59.35093333923206, + 59.35093316716608, + 59.35093303167464, + 59.350934231064635, + 59.35093430464705, + 59.350934389006454, + 59.350934476434645, + 59.3509345923912, + 59.350934706177256, + 59.350934828526285, + 59.35093496337312, + 59.350935121971744, + 59.35093527722425, + 59.35093412574053, + 59.350934088774295, + 59.35093404225967, + 59.350933993284286, + 59.35093413395637, + 59.350934141258556, + 59.35093414209081, + 59.350934142193296, + 59.35093414220788, + 59.35093414220909, + 59.35093415700226, + 59.35093415700288, + 59.350934157002875, + 59.35093420499426, + 59.3509343526174, + 59.35093461806497, + 59.3509348657099, + 59.350935186423854, + 59.350935435252964, + 59.350935687096, + 59.35093423684614, + 59.350934273691195, + 59.350934285401856, + 59.3509342890854, + 59.3509342896016, + 59.35093429013192, + 59.35093429030198, + 59.35093429029902, + 59.3509342903276, + 59.350934290328894, + 59.35093384439928, + 59.35093384440822, + 59.35093384440454, + 59.35093384440602, + 59.350933844405205, + 59.35093384440529, + 59.35093384440526, + 59.35093384440529, + 59.35093390270209, + 59.35093406389306, + 59.35093411791978, + 59.35093432775067, + 59.350934509545986, + 59.35093471364097, + 59.350934886688464, + 59.35093508103694, + 59.350935252507924, + 59.3509354106334, + 59.35093560962067, + 59.35093576175538, + 59.35093386304307, + 59.35093390144817, + 59.350933918380534, + 59.35093392395752, + 59.350933925329294, + 59.350933926013795, + 59.35093392624577, + 59.35093392627217, + 59.35093392630084, + 59.350933926300144, + 59.35093351642469, + 59.35093361313984, + 59.35093370793795, + 59.35093382066967, + 59.35093388650657, + 59.350933902566595, + 59.35093394427, + 59.350934026290766, + 59.35093413579156, + 59.350934173856494, + 59.35093339811412, + 59.35093340308407, + 59.35093344802081, + 59.350933546252925, + 59.35093360070151, + 59.35093362565511, + 59.35093363395441, + 59.35093363634482, + 59.35093363732256, + 59.35093369340774, + 59.350933536161435, + 59.3509337542757, + 59.3509339452777, + 59.35093400844815, + 59.350934031534436, + 59.35093403899366, + 59.35093404121382, + 59.3509340418686, + 59.35093404208594, + 59.35093406359414, + 59.35093354288257, + 59.3509336617239, + 59.35093382753525, + 59.35093403297353, + 59.3509342500317, + 59.3509344654844, + 59.350934678942025, + 59.35093485341199, + 59.35093492525569, + 59.35093495863062, + 59.35093362863677, + 59.350933780198254, + 59.35093397203836, + 59.35093412844597, + 59.35093432559991, + 59.35093447896678, + 59.35093464621281, + 59.35093480790871, + 59.35093496393824, + 59.35093512111655, + 59.350932311448005, + 59.350932294612946, + 59.350932278557224, + 59.35093226209446, + 59.35093224419259, + 59.35093222327809, + 59.350932204365336, + 59.35093218189516, + 59.350932161779326, + 59.35093106291146, + 59.350930949423244, + 59.35093083524947, + 59.35093071894353, + 59.35093060085244, + 59.35093047989987, + 59.35093035811927, + 59.350930235958025, + 59.35093011253774, + 59.350929988789574, + 59.35092986331414, + 59.35092993059303, + 59.350929771103566, + 59.35092961003053, + 59.35092944390035, + 59.3509292861645, + 59.350929122814236, + 59.35092899704665, + 59.350928948072, + 59.35092893151625, + 59.35092892633827, + 59.35092929790413, + 59.35092929716669, + 59.350929296987665, + 59.35092929692059, + 59.35092929690455, + 59.35092929690117, + 59.350929296899636, + 59.350929288658136, + 59.35092921784193, + 59.350929110512915, + 59.35092868456478, + 59.35092853732186, + 59.35092837137857, + 59.350928199180274, + 59.35092802578967, + 59.350927850597685, + 59.35092767544515, + 59.35092750005734, + 59.35092732378136, + 59.35092715272943, + 59.350928838975655, + 59.35092867978488, + 59.35092852251859, + 59.350928363500444, + 59.35092819469746, + 59.35092805174688, + 59.35092789166208, + 59.350927765309926, + 59.350927624521674, + 59.35092749880752, + 59.350927976899456, + 59.35092786598216, + 59.35092773886214, + 59.35092764549164, + 59.35092754502211, + 59.35092744747949, + 59.350927350774086, + 59.3509272508211, + 59.350927167570674, + 59.35092710284661, + 59.350927692979475, + 59.35092768721027, + 59.35092770074705, + 59.35092772668241, + 59.350927763023904, + 59.35092781977926, + 59.3509278922694, + 59.350927990688334, + 59.350928108270466, + 59.35092824714802, + 59.35092822331859, + 59.350928438961674, + 59.350928687394855, + 59.35092893417952, + 59.35092921683767, + 59.35092952539368, + 59.35092984806608, + 59.35093018849278, + 59.350930543869424, + 59.35092879772979, + 59.35092914347311, + 59.35092951704213, + 59.35092990035939, + 59.35093029659973, + 59.35093070972458, + 59.35093113266277, + 59.350931568453326, + 59.35093200051941, + 59.3509324621964, + 59.350929868395724, + 59.350930358589544, + 59.350930769555944, + 59.350931282954754, + 59.350931707772006, + 59.35093218852673, + 59.350932674546186, + 59.35093316864486, + 59.35093367204806, + 59.35093416779679, + 59.35093467472233, + 59.350931549204866, + 59.35093205872458, + 59.35093257509615, + 59.35093310004483, + 59.350933603093054, + 59.35093415331548, + 59.35093463608049, + 59.35093518519277, + 59.35093566784275, + 59.350936210629925, + 59.350928324716214, + 59.35092875679359, + 59.35092919874967, + 59.35092964218899, + 59.350930099084785, + 59.35093056415445, + 59.35093105837103, + 59.350931515778576, + 59.35093200038381, + 59.35093538760263, + 59.35093590914744, + 59.35093642215316, + 59.35093693653519, + 59.35093744665977, + 59.3509379539465, + 59.350938460203615, + 59.35093896219679, + 59.35093945739746, + 59.35093994717977, + 59.350936843305995, + 59.35093725280038, + 59.35093765329236, + 59.35093809695475, + 59.35093842455919, + 59.350938850504235, + 59.35093917921713, + 59.35093960674663, + 59.350939948656645, + 59.35094037140777, + 59.350937911537265, + 59.3509382419917, + 59.35093856140071, + 59.35093884800918, + 59.350939207821135, + 59.35093948143346, + 59.35093983594604, + 59.35094015022942, + 59.35094049546687, + 59.350940819860256, + 59.35094114854415, + 59.35093836024402, + 59.35093864039827, + 59.35093891460035, + 59.35093916104285, + 59.3509394825852, + 59.35093972686004, + 59.35094001368817, + 59.35094030603591, + 59.35094058689316, + 59.35093964054362, + 59.350939917547976, + 59.35094019227588, + 59.35094046563531, + 59.35094073247508, + 59.35094098877525, + 59.350941231352536, + 59.35094146053603, + 59.35094165125453, + 59.35094182752093, + 59.35094198522418, + 59.35093988631573, + 59.35093995797311, + 59.35094000987185, + 59.350940046522155, + 59.35094006532367, + 59.350940074566836, + 59.350940067094385, + 59.350940030133664, + 59.350939981499806, + 59.35094035193397, + 59.350940241050225, + 59.35094011703565, + 59.35093997040628, + 59.35093983036406, + 59.35093963881806, + 59.35093946600912, + 59.350939227795365, + 59.35093903248613, + 59.35093875218389, + 59.35093909859334, + 59.350938694335255, + 59.35093833577274, + 59.35093794157552, + 59.35093769998254, + 59.350937612344254, + 59.3509375847802, + 59.35093757486702, + 59.35093757295401, + 59.35093757148168, + 59.35093760940036, + 59.35093760930323, + 59.35093760923344, + 59.350937609230726, + 59.350937609223166, + 59.35093759467626, + 59.35093745869899, + 59.35093718012152, + 59.35093694723406, + 59.350936658601775, + 59.350937230880135, + 59.35093686034517, + 59.35093648821283, + 59.350936092956985, + 59.350935685978214, + 59.35093526292049, + 59.35093483096496, + 59.35093438466812, + 59.350933922964444, + 59.35093345154467, + 59.35093684121075, + 59.35093636549968, + 59.350935829142415, + 59.3509353860495, + 59.35093488767717, + 59.35093438487492, + 59.35093388064546, + 59.35093337627727, + 59.35093287299384, + 59.35093237317109, + 59.35093187639585, + 59.35093532702728, + 59.35093485011764, + 59.35093434845632, + 59.35093384604876, + 59.35093335739511, + 59.35093281770641, + 59.35093238157786, + 59.3509318589327, + 59.350931429291805, + 59.35093091302221, + 59.35093151677364, + 59.350931129356844, + 59.3509308384278, + 59.35093049428842, + 59.350930215777666, + 59.35092989864302, + 59.3509296396273, + 59.35092937070198, + 59.350929112281655, + 59.35093059424409, + 59.35093036031125, + 59.35093017054177, + 59.35092997356601, + 59.35092982341361, + 59.35092966243366, + 59.35092955117404, + 59.35092941596698, + 59.35092933384739, + 59.350929261710874, + 59.350929574070264, + 59.35092956209695, + 59.35092955792841, + 59.350929556752845, + 59.350929556361905, + 59.35092955625916, + 59.35092955622726, + 59.35092955621632, + 59.35092955621485, + 59.35092955621349, + 59.35092955621336, + 59.35092942003162, + 59.350929420029004, + 59.350929420029146, + 59.350929420029544, + 59.350929420029814, + 59.35092942002986, + 59.350929420029885, + 59.350929420029885, + 59.3509294200299, + 59.350929656134845, + 59.35092965613816, + 59.3509296561383, + 59.35092965613814, + 59.35092965613798, + 59.35092965613799, + 59.350929656138, + 59.35092965613799, + 59.35092965613799, + 59.35092965613799, + 59.350929656413555, + 59.350929656413555, + 59.35092965641357, + 59.35092965641357, + 59.350929656413555, + 59.35092965641357, + 59.35092965641357, + 59.35092965641357, + 59.35092965641357, + 59.35092965641357, + 59.3509296563938, + 59.35092965639449, + 59.35092965639451, + 59.35092965639454, + 59.35092965639449, + 59.35092965639449, + 59.35092965639449, + 59.35092965639449, + 59.35092965639449, + 59.35092965639449 + ], + "lon": [ + 18.068044270978096, + 18.068044399069947, + 18.068044429706774, + 18.068044464485688, + 18.068044538964273, + 18.06804458822712, + 18.068044677432532, + 18.068044735867982, + 18.06804480245637, + 18.068044910045945, + 18.068044994766165, + 18.068044076414775, + 18.068044001334393, + 18.068043916795133, + 18.068043830401233, + 18.06804371720048, + 18.068043607263267, + 18.068043490017033, + 18.068043361704834, + 18.068043211763367, + 18.068043065806403, + 18.068044190032012, + 18.068044232584143, + 18.06804428607588, + 18.068044342356433, + 18.068044180313112, + 18.068044170313513, + 18.068044170188987, + 18.068044170177046, + 18.068044170173962, + 18.068044170173334, + 18.06804425436381, + 18.068044254365162, + 18.068044254365127, + 18.06804435180146, + 18.068044651017583, + 18.06804519095303, + 18.068045699559402, + 18.06804636362203, + 18.068046884421904, + 18.06804741971073, + 18.068044379654488, + 18.068044461788727, + 18.068044487931914, + 18.068044496179755, + 18.068044497337794, + 18.068044498525264, + 18.068044498906016, + 18.068044498899386, + 18.06804449896336, + 18.068044498966252, + 18.0680463932585, + 18.068046393282504, + 18.068046393276344, + 18.068046393279168, + 18.068046393277776, + 18.06804639327785, + 18.068046393277847, + 18.068046393277857, + 18.068046530797165, + 18.068046911038774, + 18.068046692263998, + 18.06804717935538, + 18.068047603267143, + 18.06804808059392, + 18.068048487066065, + 18.068048946454184, + 18.068049353879786, + 18.06804973059318, + 18.06805020580577, + 18.06805057046187, + 18.06804731031794, + 18.068047425363993, + 18.068047476141718, + 18.06804749285017, + 18.06804749696182, + 18.068047499013833, + 18.068047499709248, + 18.06804749978838, + 18.068047499874343, + 18.0680474998722, + 18.06804858851682, + 18.068048899232192, + 18.068049203769572, + 18.068049565925776, + 18.06804977742912, + 18.06804982902291, + 18.068049962998014, + 18.06805022649512, + 18.068050578273677, + 18.068050700559684, + 18.0680486757371, + 18.068048693014543, + 18.068048849229, + 18.06804919071698, + 18.06804937999841, + 18.068049466745517, + 18.068049495596654, + 18.068049503906515, + 18.068049507305453, + 18.068049702276383, + 18.068049447773202, + 18.068050228579665, + 18.068050911800327, + 18.068051141139087, + 18.06805122653528, + 18.06805125447385, + 18.068051262865232, + 18.068051265346238, + 18.068051266170777, + 18.068051347422465, + 18.06804960546435, + 18.068050061797905, + 18.06805070069659, + 18.06805148765542, + 18.068052321461064, + 18.068053158187347, + 18.0680539957559, + 18.068054686505256, + 18.068054973934355, + 18.0680551074447, + 18.06805012435196, + 18.068050742631684, + 18.068051532442034, + 18.068052183357107, + 18.06805300556322, + 18.068053650587103, + 18.068054379483435, + 18.068055117081993, + 18.068055832037963, + 18.06805655800351, + 18.068055179590065, + 18.06805597130505, + 18.068056764641415, + 18.068057555070542, + 18.068058343702333, + 18.068059194307722, + 18.068059908799373, + 18.068060747935892, + 18.068061456536288, + 18.06805860836428, + 18.068059355525076, + 18.068060092929684, + 18.068060835010574, + 18.068061574115987, + 18.068062313817887, + 18.06806305331513, + 18.068063790619764, + 18.068064532900603, + 18.068065273771126, + 18.068066024722356, + 18.068062486685513, + 18.068063216571232, + 18.06806394429477, + 18.068064692184652, + 18.068065399327317, + 18.06806612716666, + 18.06806667885379, + 18.06806689048227, + 18.06806696077664, + 18.068066982675585, + 18.068064884955323, + 18.068064887863972, + 18.068064888566862, + 18.068064888834776, + 18.068064888899205, + 18.06806488891288, + 18.06806488891911, + 18.06806492228206, + 18.06806520900503, + 18.0680656462445, + 18.068067088541, + 18.068067688754773, + 18.068068368793938, + 18.06806907196335, + 18.068069774212148, + 18.068070471507873, + 18.068071167444902, + 18.06807186138991, + 18.068072562046503, + 18.068073240561972, + 18.068067040203722, + 18.068067733744876, + 18.068068420300527, + 18.068069109178303, + 18.068069845912547, + 18.068070491600064, + 18.068071252398514, + 18.06807189523664, + 18.06807263014523, + 18.068073313809606, + 18.068070374639095, + 18.06807105978413, + 18.06807188134906, + 18.06807252718845, + 18.068073278608267, + 18.06807405153765, + 18.06807487452078, + 18.0680758094319, + 18.068076778837078, + 18.068077764241167, + 18.06807310470392, + 18.068074096434554, + 18.0680750827815, + 18.068076136083114, + 18.068077054098662, + 18.068078037100083, + 18.068079014257876, + 18.06807998488901, + 18.06808094488517, + 18.06808190291682, + 18.06807569783922, + 18.06807659163512, + 18.068077516487584, + 18.06807832432996, + 18.068079164442093, + 18.068079977093777, + 18.068080768272793, + 18.068081528861793, + 18.06808226045889, + 18.068078880315152, + 18.068079576647875, + 18.068080280437123, + 18.06808096046572, + 18.068081609427427, + 18.068082221767956, + 18.068082802237374, + 18.06808337079745, + 18.068083892008346, + 18.06808442378937, + 18.068081829616297, + 18.06808238779722, + 18.068082829627368, + 18.068083324164323, + 18.068083688190818, + 18.06808406902386, + 18.068084404438583, + 18.06808470759826, + 18.06808498705045, + 18.06808521877751, + 18.06808541561446, + 18.068083832490895, + 18.06808398934757, + 18.068084108202598, + 18.068084176405314, + 18.06808420770965, + 18.06808421403432, + 18.068084184368004, + 18.068084129164113, + 18.06808405447041, + 18.0680839469454, + 18.0680895553547, + 18.068090117971472, + 18.068090660854512, + 18.068091161002513, + 18.06809163733856, + 18.068092070393654, + 18.068092500891186, + 18.06809286211202, + 18.068093203845482, + 18.068082547046025, + 18.068082533577062, + 18.068082482862774, + 18.068082386620596, + 18.068082238088493, + 18.068082065972515, + 18.068081866123794, + 18.06808162838559, + 18.068081346025515, + 18.068081026185148, + 18.06807945255899, + 18.06807884322642, + 18.068078194037188, + 18.068077445268184, + 18.06807685923018, + 18.068076085359223, + 18.068075489882293, + 18.068074718097236, + 18.06807410633173, + 18.068073353894256, + 18.068075042682256, + 18.068074227119116, + 18.068073441243016, + 18.06807273254761, + 18.06807184414594, + 18.06807117434116, + 18.068070312212456, + 18.06806955544296, + 18.068068729350312, + 18.068067960461537, + 18.068067185220308, + 18.06807136760974, + 18.06807051045569, + 18.068069669786972, + 18.06806892440256, + 18.068067965046755, + 18.068067240891875, + 18.06806639656642, + 18.068065541244636, + 18.0680647260125, + 18.068067161537442, + 18.068066309080205, + 18.068065455509018, + 18.068064594664143, + 18.06806372713506, + 18.06806284530087, + 18.068061954036246, + 18.06806101558981, + 18.068060104740276, + 18.06805915093841, + 18.068058190647037, + 18.068063956754916, + 18.068062953064814, + 18.06806194183457, + 18.068060937173897, + 18.068059923387548, + 18.06805884060054, + 18.068057897265504, + 18.068056809188974, + 18.068055875508175, + 18.06805968644596, + 18.068058692398736, + 18.068057697831165, + 18.06805662613639, + 18.068055750975407, + 18.068054692394306, + 18.06805385714054, + 18.068052801297732, + 18.06805201790378, + 18.068051034402632, + 18.068057139428124, + 18.06805635183646, + 18.06805575420205, + 18.068055129674175, + 18.06805475310267, + 18.068054616929025, + 18.06805457408982, + 18.06805455865628, + 18.06805455568191, + 18.068054553391526, + 18.068054369685626, + 18.068054369529168, + 18.068054369416608, + 18.06805436941225, + 18.068054369400098, + 18.06805434592176, + 18.06805412640177, + 18.068053672734628, + 18.06805327034051, + 18.068052766932226, + 18.068053271531582, + 18.068052619077466, + 18.06805199783137, + 18.068051378032894, + 18.068050785178098, + 18.068050235099854, + 18.068049715459118, + 18.068049243810602, + 18.068048841660165, + 18.06804847897015, + 18.068051358042002, + 18.06805102690322, + 18.068050736507438, + 18.068050554153718, + 18.06805039641038, + 18.06805029658236, + 18.06805025284264, + 18.06805028338577, + 18.06805036299542, + 18.06805049497995, + 18.06805067938137, + 18.06804819851349, + 18.068048270384484, + 18.068048399049285, + 18.068048553431314, + 18.06804875437379, + 18.068049011435555, + 18.068049260934785, + 18.068049595803007, + 18.068049917961325, + 18.068050364162882, + 18.06805261039489, + 18.06805341706755, + 18.068054075691684, + 18.068054921067468, + 18.068055639145832, + 18.068056513335915, + 18.068057268901132, + 18.06805811021954, + 18.068058965431746, + 18.068054637122152, + 18.068055579259134, + 18.068056433152687, + 18.068057421412867, + 18.068058296394415, + 18.068059357423312, + 18.06806020084976, + 18.068061302098144, + 18.068062140465745, + 18.068063071452002, + 18.068058263918783, + 18.06805841705041, + 18.068058470353726, + 18.068058485653548, + 18.06805849078667, + 18.068058492134373, + 18.068058492551472, + 18.068058492694536, + 18.068058492713604, + 18.068058492731375, + 18.068058492733098, + 18.06806130898071, + 18.068061309013746, + 18.06806130900965, + 18.068061309004314, + 18.068061309000864, + 18.06806130900019, + 18.06806130899982, + 18.068061308999752, + 18.06806130899972, + 18.068060647738147, + 18.068060647704616, + 18.06806064770419, + 18.06806064770658, + 18.068060647709334, + 18.06806064770854, + 18.068060647708652, + 18.06806064770872, + 18.068060647708727, + 18.068060647708737, + 18.06806064731873, + 18.0680606473187, + 18.0680606473187, + 18.068060647318696, + 18.0680606473187, + 18.0680606473187, + 18.0680606473187, + 18.0680606473187, + 18.0680606473187, + 18.0680606473187, + 18.068060547349212, + 18.068060547339705, + 18.0680605473393, + 18.068060547339172, + 18.068060547339613, + 18.06806054733956, + 18.068060547339606, + 18.068060547339595, + 18.0680605473396, + 18.0680605473396 + ], + "marker": { + "size": 10 + }, + "mode": "markers", + "type": "scattermapbox" + }, + { + "lat": [ + 59.35089426416136, + 59.35089481178939, + 59.35089483355297, + 59.350894857744606, + 59.35089488604177, + 59.35089491808581, + 59.35089494709089, + 59.350894990631645, + 59.35089502438268, + 59.350895077367376, + 59.35089511663734, + 59.35089489941767, + 59.350894915125295, + 59.35089492254493, + 59.35089493043813, + 59.35089494733787, + 59.35089495735938, + 59.3508949704765, + 59.35089498131451, + 59.35089499210641, + 59.35089500422632, + 59.350895015966955, + 59.350894884148445, + 59.35089487277662, + 59.35089486170763, + 59.35089484847376, + 59.35089483387418, + 59.35089481861798, + 59.350894803809354, + 59.35089478153899, + 59.35089476101665, + 59.35089477698152, + 59.350894758875285, + 59.350894740395816, + 59.35089472108076, + 59.350894708044535, + 59.35089468134352, + 59.35089465931041, + 59.35089464092461, + 59.35089461227294, + 59.350894588277754, + 59.35089491297137, + 59.35089494521897, + 59.35089497743465, + 59.35089501944495, + 59.35089505989556, + 59.35089510405016, + 59.35089513895837, + 59.35089520754802, + 59.35089526482648, + 59.350894967406774, + 59.35089489132773, + 59.350894891329744, + 59.35089489972674, + 59.350895008355124, + 59.35089518545526, + 59.35089542517829, + 59.35089570256227, + 59.35089603161906, + 59.35089638116867, + 59.350896736108524, + 59.35089514953104, + 59.350895502958416, + 59.35089584844485, + 59.350896192073265, + 59.35089653467157, + 59.350896881363454, + 59.35089721878933, + 59.35089755974104, + 59.350897900344194, + 59.35089824179036, + 59.35089503033628, + 59.3508953069802, + 59.350895585751914, + 59.35089585888737, + 59.350896129029785, + 59.350896403690335, + 59.350896676924364, + 59.350896958245634, + 59.35089723249662, + 59.350897500780775, + 59.35089777407419, + 59.35089458744109, + 59.350894751747155, + 59.35089491696863, + 59.35089508408747, + 59.35089524820105, + 59.350895412350056, + 59.350895576760884, + 59.350895739803875, + 59.350895902112015, + 59.35089418580134, + 59.3508942542131, + 59.3508943115218, + 59.35089435546547, + 59.350894382713655, + 59.350894403805924, + 59.350894415825465, + 59.3508944128607, + 59.35089439470288, + 59.350894367513, + 59.350893305616495, + 59.35089317512329, + 59.350893029043434, + 59.35089286712533, + 59.35089266813452, + 59.350892432024494, + 59.35089215828093, + 59.350891872544665, + 59.35089157855295, + 59.35089127651043, + 59.35089235483179, + 59.35089201092318, + 59.3508916665259, + 59.350891320831934, + 59.350890972804294, + 59.35089062073128, + 59.350890270602804, + 59.350889915969276, + 59.350889560281495, + 59.35088920176892, + 59.35089044217648, + 59.35089004501909, + 59.35088964993529, + 59.35088925269734, + 59.35088885304779, + 59.350888439943404, + 59.3508880163734, + 59.35088757453939, + 59.35088713069728, + 59.35088666676289, + 59.35088796677862, + 59.350887488240176, + 59.35088699890433, + 59.35088650261533, + 59.35088600401848, + 59.35088549894629, + 59.35088497691321, + 59.350884473028906, + 59.35088394295721, + 59.350883445573565, + 59.35088525635668, + 59.35088474374119, + 59.3508842140822, + 59.3508836854307, + 59.350883133996454, + 59.350882593316136, + 59.3508820192221, + 59.35088146394614, + 59.350880884986, + 59.35088030657597, + 59.35088251960579, + 59.35088194801503, + 59.3508813587174, + 59.35088076848102, + 59.35088017883154, + 59.35087958740493, + 59.350878994810785, + 59.35087839651149, + 59.35087779111474, + 59.350877175295196, + 59.35087952708666, + 59.3508788852045, + 59.35087825041093, + 59.350877607432274, + 59.35087696625533, + 59.35087632613093, + 59.35087569052442, + 59.35087505388759, + 59.35087442444979, + 59.35087379194317, + 59.35087634298634, + 59.3508757028188, + 59.3508750647851, + 59.3508744301612, + 59.350873785677656, + 59.350873171351765, + 59.35087254266169, + 59.35087193963725, + 59.35087132224504, + 59.35087070615073, + 59.350873262689284, + 59.35087265044318, + 59.350872036140885, + 59.35087145388596, + 59.35087085750199, + 59.35087024392279, + 59.35086966569765, + 59.35086905551995, + 59.350868480858516, + 59.35087017121438, + 59.350869578145755, + 59.35086898869731, + 59.35086841133142, + 59.35086783383478, + 59.35086729573523, + 59.35086676894713, + 59.35086628009489, + 59.35086580479336, + 59.35086533131583, + 59.35086485682632, + 59.35086708281183, + 59.350866625313955, + 59.35086617086624, + 59.35086572502274, + 59.35086528614771, + 59.3508648548292, + 59.35086443368472, + 59.35086401790091, + 59.35086361423221, + 59.350863229141865, + 59.35086514424597, + 59.35086482680545, + 59.35086452513248, + 59.35086422911814, + 59.35086393523538, + 59.35086364197119, + 59.350863354965156, + 59.35086306872698, + 59.350862784320036, + 59.350862499280595, + 59.350863481065005, + 59.350863191990314, + 59.350862913966694, + 59.350862685991174, + 59.35086247847149, + 59.35086228668381, + 59.350862109074185, + 59.35086194750835, + 59.35086179417394, + 59.350861643643796, + 59.35086208467341, + 59.35086192253591, + 59.35086176029951, + 59.350861594215594, + 59.35086143973059, + 59.350861305998606, + 59.35086119116022, + 59.3508610981957, + 59.350861022992646, + 59.35086097750508, + 59.35086108214358, + 59.35086104414599, + 59.35086103010241, + 59.35086104477518, + 59.35086107372636, + 59.35086113019616, + 59.350861221051275, + 59.35086133856241, + 59.35086147837711, + 59.350861649857265, + 59.35086107630636, + 59.35086127661161, + 59.35086149443762, + 59.35086173778335, + 59.350862008484405, + 59.350862297780424, + 59.35086261811741, + 59.35086295943634, + 59.350863314919906, + 59.35086369067464, + 59.35086292597562, + 59.35086337877567, + 59.3508638488521, + 59.3508643600849, + 59.35086494815109, + 59.35086557751477, + 59.35086623635847, + 59.350866866474234, + 59.35086751962399, + 59.35086817685246, + 59.35086536905845, + 59.35086606606825, + 59.350866795365874, + 59.35086755663228, + 59.35086831167877, + 59.35086901406256, + 59.35086967967811, + 59.350870304904355, + 59.350870903698194, + 59.35087149833118, + 59.35086965908489, + 59.35087034518172, + 59.350871040489494, + 59.35087182312473, + 59.35087267530369, + 59.35087359535588, + 59.35087436794525, + 59.350875529964554, + 59.35087650032969, + 59.350877466293845, + 59.35087447636613, + 59.35087555557493, + 59.35087663177882, + 59.35087770932861, + 59.35087878689188, + 59.35087986533125, + 59.35088091749047, + 59.3508819624343, + 59.35088300620228, + 59.35088399398818, + 59.35088113233132, + 59.35088221115129, + 59.350883234945854, + 59.35088427681998, + 59.35088530263639, + 59.35088633711331, + 59.35088733059348, + 59.3508883502824, + 59.35088930191655, + 59.350890240752136, + 59.350888046489786, + 59.35088895919863, + 59.3508898506569, + 59.35089069391997, + 59.350891512113776, + 59.35089222678698, + 59.350892843392195, + 59.35089336396737, + 59.35089378812939, + 59.35089417689619, + 59.350893375301624, + 59.350893731605105, + 59.3508940242313, + 59.350894273074246, + 59.35089439227349, + 59.35089441718019, + 59.35089437522054, + 59.3508942570421, + 59.350894041029974, + 59.35089376116582, + 59.350894790172546, + 59.35089436234193, + 59.35089390882058, + 59.350893642666875, + 59.3508935476532, + 59.350893516780616, + 59.350893507428935, + 59.350893505101915, + 59.35089350429378, + 59.35089350413135, + 59.350893397398465, + 59.35089339735671, + 59.35089339735589, + 59.350893397354895, + 59.35089339735606, + 59.35089339735619, + 59.35089339735633, + 59.350893397356344, + 59.35089339735636, + 59.350893397356366, + 59.35089225803699, + 59.35089225802862, + 59.350892258026064, + 59.350892258027955, + 59.35089225802881, + 59.35089225802896, + 59.35089225802906, + 59.35089225802909, + 59.35089225614966, + 59.35089219698152, + 59.35089226605588, + 59.35089209534729, + 59.35089192997447, + 59.35089181108448, + 59.350891740642865, + 59.350891729770396, + 59.350891764956, + 59.3508918711664, + 59.35089203492451, + 59.35089226242424, + 59.350892985432544, + 59.35089344006977, + 59.350893963512206, + 59.3508945761891, + 59.35089529093171, + 59.350896013723286, + 59.35089680953534, + 59.350897623325295, + 59.3508985116032, + 59.350899384648, + 59.35089406818349, + 59.350894950375746, + 59.350895861697055, + 59.350896769997775, + 59.35089767282997, + 59.350898560748476, + 59.35089942485952, + 59.35090010023818, + 59.350900373504516, + 59.35090047590303, + 59.35089664278651, + 59.35089701499415, + 59.35089751258033, + 59.35089805498744, + 59.35089860980274, + 59.350899174213765, + 59.350899804238736, + 59.35090047859503, + 59.35090117050399, + 59.35090188841505, + 59.35090107876722, + 59.35090178688759, + 59.35090248482883, + 59.35090318443002, + 59.35090388357572, + 59.350904582066875, + 59.35090527384688, + 59.350905968319395, + 59.35090667159564, + 59.35090733560586, + 59.35090502767389, + 59.350905692958946, + 59.35090636131393, + 59.350907006571724, + 59.35090764791467, + 59.350908290822545, + 59.350908934318426, + 59.35090958002851, + 59.35091022693214, + 59.35091087072291, + 59.35090858421944, + 59.35090924953346, + 59.3509098831874, + 59.35091053811038, + 59.350911189587414, + 59.35091184276713, + 59.350912497117704, + 59.35091315183328, + 59.350913807960524, + 59.350914466802706, + 59.350912045344685, + 59.35091269136423, + 59.350913326609955, + 59.35091396944548, + 59.35091460872697, + 59.350915232717234, + 59.350915853391626, + 59.350916470913035, + 59.35091714682184, + 59.35091789751115, + 59.35091567279986, + 59.35091646458256, + 59.350917248496366, + 59.35091804800825, + 59.35091885597863, + 59.35091965846212, + 59.35092046890737, + 59.35092128169465, + 59.350922094162776, + 59.35092292556207, + 59.35091668811458, + 59.35091751863007, + 59.35091833648157, + 59.35091921293795, + 59.35092009875725, + 59.350921024871276, + 59.35092191801848, + 59.3509228382237, + 59.35092377946739, + 59.350924680741514, + 59.35091807635655, + 59.350918985505054, + 59.35091989458792, + 59.350920801740415, + 59.35092158575473, + 59.350921952557755, + 59.350922067124145, + 59.350922118672905, + 59.35092212913534, + 59.350922132942856, + 59.35092634028344, + 59.350926348513646, + 59.35092635066019, + 59.35092635095495, + 59.35092635099192, + 59.35092635099505, + 59.35092635099555, + 59.350926350995636, + 59.350926350995564, + 59.350926350995564, + 59.350926917884124, + 59.35092691788555, + 59.35092691788664, + 59.35092691788664, + 59.35092691788672, + 59.35092691788672, + 59.350926917886724, + 59.350926917886724, + 59.350926917886724, + 59.350926917886724, + 59.35092447730996, + 59.35092447731183, + 59.35092447731192, + 59.350924477311764, + 59.350924477311665, + 59.35092447731165, + 59.35092447731162, + 59.35092447731162, + 59.35092447731162, + 59.35092447731162, + 59.35092473299392 + ], + "lon": [ + 18.068049518147564, + 18.06804963070863, + 18.068049633812763, + 18.068049637262, + 18.068049641295524, + 18.068049645862168, + 18.068049649995068, + 18.068049656198266, + 18.06804966100617, + 18.06804966855319, + 18.068049674146224, + 18.06804962743101, + 18.068049625749588, + 18.06804962481957, + 18.068049623736364, + 18.068049621098265, + 18.068049619332797, + 18.068049616801087, + 18.068049614524035, + 18.068049612093443, + 18.068049609173276, + 18.068049606156045, + 18.06804962856267, + 18.06804962912369, + 18.0680496296726, + 18.068049630331334, + 18.06804963106027, + 18.068049631823833, + 18.068049632566375, + 18.068049633685064, + 18.068049634717617, + 18.06804962801919, + 18.06804962782654, + 18.068049627607817, + 18.068049627359052, + 18.068049627181033, + 18.068049626794387, + 18.068049626455934, + 18.068049626161823, + 18.06804962568487, + 18.06804962527, + 18.068049628194217, + 18.068049628273215, + 18.068049628355862, + 18.068049628467772, + 18.0680496285789, + 18.068049628703143, + 18.06804962880313, + 18.068049629003255, + 18.068049629173405, + 18.068049641853293, + 18.068049728166635, + 18.068049728165107, + 18.068049741309785, + 18.0680499122098, + 18.068050191054375, + 18.068050569531643, + 18.06805100925277, + 18.06805153418553, + 18.068052096752616, + 18.06805267024514, + 18.06805006868354, + 18.06805063500242, + 18.068051192132053, + 18.06805174929395, + 18.0680523078585, + 18.06805287336548, + 18.0680534231743, + 18.06805398268156, + 18.06805454085978, + 18.068055102776803, + 18.068052557524133, + 18.068053239330823, + 18.06805393100986, + 18.068054613823392, + 18.068055286612047, + 18.068055969330175, + 18.06805664910021, + 18.068057350262826, + 18.0680580337412, + 18.068058700810138, + 18.06805938120101, + 18.068056947886458, + 18.068057757034506, + 18.068058567798964, + 18.068059385332603, + 18.06806018995783, + 18.068060995457024, + 18.068061809472802, + 18.068062616955316, + 18.0680634329896, + 18.06806081422862, + 18.068061684112088, + 18.068062561732496, + 18.06806344584744, + 18.068064331176362, + 18.068065219490684, + 18.06806611784048, + 18.068066996183553, + 18.0680678883311, + 18.068068799721658, + 18.068064779063892, + 18.068065674116454, + 18.068066582889422, + 18.06806747426862, + 18.06806845719929, + 18.068069527590154, + 18.068070594650028, + 18.068071658969476, + 18.068072716817703, + 18.068073795528807, + 18.068067049766988, + 18.068068072069366, + 18.068069093978774, + 18.068070112165373, + 18.06807113021368, + 18.068072155381145, + 18.068073173504136, + 18.068074201564624, + 18.068075229326194, + 18.0680762609174, + 18.06807095276072, + 18.068071938350023, + 18.06807291671985, + 18.068073894814418, + 18.068074867687816, + 18.068075815711797, + 18.06807674637033, + 18.068077662063654, + 18.068078550557647, + 18.06807944428213, + 18.068076216192676, + 18.068077044829515, + 18.068077852050905, + 18.068078631592886, + 18.068079377531998, + 18.068080082111795, + 18.068080797565294, + 18.068081483160526, + 18.06808220739541, + 18.06808288814042, + 18.068080606508893, + 18.06808131344281, + 18.068081985288423, + 18.068082616016238, + 18.068083247507477, + 18.068083829633977, + 18.068084391162344, + 18.068084875028994, + 18.068085353964648, + 18.068085829223715, + 18.06808350471461, + 18.068083970181675, + 18.068084454833112, + 18.068084953043797, + 18.06808545400141, + 18.068085949714963, + 18.068086440072094, + 18.068086905745837, + 18.0680873202459, + 18.068087690782843, + 18.0680851429695, + 18.06808533571179, + 18.068085432808367, + 18.068085463500204, + 18.068085375016466, + 18.068085209980715, + 18.068085016082758, + 18.068084801842193, + 18.068084586663964, + 18.068084365153616, + 18.06808591416657, + 18.068085762768835, + 18.06808560367622, + 18.068085371816554, + 18.068085089767564, + 18.068084767139826, + 18.06808437828608, + 18.06808399226634, + 18.068083592490726, + 18.068083188311128, + 18.068084483898055, + 18.068084035253992, + 18.0680835700379, + 18.068083112721926, + 18.06808262636212, + 18.06808211802703, + 18.06808163956806, + 18.068081132628926, + 18.068080654051318, + 18.068082216060972, + 18.06808171884319, + 18.06808119259998, + 18.068080628510224, + 18.068080005462647, + 18.068079353395493, + 18.068078577434324, + 18.068077779591547, + 18.068076919598248, + 18.068076049309276, + 18.068075176393496, + 18.068078092014034, + 18.0680771890307, + 18.068076284677723, + 18.068075378237335, + 18.06807445581157, + 18.0680735152575, + 18.068072557338137, + 18.068071584848767, + 18.068070597031355, + 18.06806957763271, + 18.06807296326592, + 18.068071860907356, + 18.0680707352291, + 18.068069607855477, + 18.068068483669332, + 18.068067350026134, + 18.068066214961508, + 18.06806508219124, + 18.06806395313946, + 18.06806281952632, + 18.068067048444615, + 18.068065914389976, + 18.068064766533233, + 18.068063579760178, + 18.06806238430564, + 18.06806118096309, + 18.06805996485777, + 18.068058740395774, + 18.068057510113405, + 18.068056273857827, + 18.068060346524152, + 18.068059108810104, + 18.06805787263127, + 18.068056633551407, + 18.06805539071792, + 18.068054132423068, + 18.068052871457557, + 18.06805160197853, + 18.068050331020654, + 18.068049046299137, + 18.06805301916355, + 18.06805173201424, + 18.068050445696795, + 18.06804916179264, + 18.068047879392342, + 18.068046598968703, + 18.068045326955104, + 18.068044060356605, + 18.068042797477236, + 18.068041558628295, + 18.068045920449734, + 18.06804468956814, + 18.06804348884778, + 18.06804229640144, + 18.068041127220226, + 18.068039975153305, + 18.068038851672988, + 18.06803773459053, + 18.0680366790928, + 18.068035624293167, + 18.068040156818956, + 18.068039224905103, + 18.06803832371821, + 18.068037463175454, + 18.06803655552242, + 18.06803559913361, + 18.068034587472297, + 18.068033617951127, + 18.068032642992097, + 18.06803166856465, + 18.068036871518384, + 18.06803604589762, + 18.068035309083616, + 18.068035670111495, + 18.068036341922788, + 18.068037144960996, + 18.06803808702539, + 18.068039110113236, + 18.068040188024256, + 18.068041272077238, + 18.06803546206438, + 18.06803631344967, + 18.06803718342059, + 18.068038170750622, + 18.068039237665314, + 18.068040395538766, + 18.068041374520895, + 18.068042873152248, + 18.06804411772229, + 18.068045362785263, + 18.06803552264646, + 18.068036297431057, + 18.068037083405105, + 18.068037841918862, + 18.06803861604375, + 18.068039417114935, + 18.068040293226066, + 18.06804123742242, + 18.06804228256841, + 18.06804332227195, + 18.068035598654195, + 18.06803648330845, + 18.068037377805805, + 18.068038353228044, + 18.06803936822306, + 18.0680404317656, + 18.06804152448428, + 18.068042696775507, + 18.068043896858185, + 18.068045206043625, + 18.068039924284893, + 18.06804124178577, + 18.068042664684278, + 18.068044215361528, + 18.068045886661597, + 18.068047600550894, + 18.068049508925082, + 18.068051536674787, + 18.06805364821081, + 18.068055775993138, + 18.06804875954991, + 18.06805097133403, + 18.06805310762357, + 18.068055316257624, + 18.068057563253976, + 18.068059827479875, + 18.068062089648087, + 18.068064346322515, + 18.068066567299553, + 18.068068772597204, + 18.068060410854805, + 18.06806250991521, + 18.068064526006587, + 18.068065653547052, + 18.068066047057126, + 18.06806617311883, + 18.06806621113169, + 18.068066220684884, + 18.068066223993476, + 18.068066224656807, + 18.068070833554177, + 18.06807083380154, + 18.06807083381015, + 18.068070833815117, + 18.068070833808722, + 18.068070833807855, + 18.068070833807113, + 18.068070833806978, + 18.06807083380689, + 18.06807083380686, + 18.06807425036253, + 18.06807425040148, + 18.068074250416636, + 18.06807425040528, + 18.068074250400763, + 18.06807425039983, + 18.068074250399125, + 18.068074250399032, + 18.06807426143433, + 18.068074608525535, + 18.06807484802861, + 18.068075991571156, + 18.068077359620546, + 18.06807884528855, + 18.06808033067369, + 18.06808188966564, + 18.068083359348268, + 18.068084859189273, + 18.068086335804146, + 18.068087783079957, + 18.068075795004155, + 18.06807701676326, + 18.068078275867574, + 18.06807948577034, + 18.068080637712796, + 18.068081626858007, + 18.06808251762444, + 18.068083285989253, + 18.068083851413483, + 18.068084169692725, + 18.068080817757913, + 18.068080963361204, + 18.06808100365729, + 18.068080933007785, + 18.06808071877441, + 18.068080345632943, + 18.068079846558486, + 18.068079376370545, + 18.06807917297917, + 18.068079096674243, + 18.068085795428026, + 18.068085787024664, + 18.06808580386101, + 18.06808586725765, + 18.068085967656092, + 18.06808607681462, + 18.0680862045123, + 18.068086343856, + 18.068086476924602, + 18.068086581471565, + 18.068085915030448, + 18.068085917464472, + 18.068085871034302, + 18.06808577262936, + 18.06808562165416, + 18.068085451267567, + 18.068085247109508, + 18.06808499526458, + 18.06808470086693, + 18.068084371392068, + 18.06808624411338, + 18.068085901148685, + 18.068085507388325, + 18.068085075746474, + 18.068084614429516, + 18.068084160903837, + 18.0680837150523, + 18.06808327733901, + 18.068082837627145, + 18.068082405336426, + 18.06808422529473, + 18.068083810762673, + 18.068083420694716, + 18.06808302308487, + 18.068082637676508, + 18.06808225297017, + 18.068081870626976, + 18.068081492164655, + 18.06808112719857, + 18.06808076056516, + 18.068080751440128, + 18.06808028300427, + 18.06807982655154, + 18.068079371524156, + 18.068078892506442, + 18.06807836143864, + 18.068077781764032, + 18.06807711825425, + 18.06807630637, + 18.06807538851327, + 18.068077149003976, + 18.068076148659646, + 18.06807517345825, + 18.06807420521238, + 18.068073246241667, + 18.068072308567228, + 18.06807137876455, + 18.068070442022425, + 18.06806952762099, + 18.068068619633795, + 18.068074528508067, + 18.06807359511694, + 18.068072786356847, + 18.06807207877381, + 18.068071556688658, + 18.068071185952544, + 18.068070953223515, + 18.06807082716005, + 18.06807074009883, + 18.068070662539782, + 18.068073704289326, + 18.068073880415135, + 18.06807406020827, + 18.068074244685228, + 18.068074423443854, + 18.06807451300939, + 18.068074543632108, + 18.068074558321612, + 18.068074561317772, + 18.068074562429626, + 18.068064505230012, + 18.068064492405824, + 18.068064489061673, + 18.068064488603888, + 18.06806448854689, + 18.068064488542337, + 18.068064488541584, + 18.068064488541435, + 18.068064488541577, + 18.068064488541594, + 18.068065988544625, + 18.06806598854576, + 18.06806598854572, + 18.068065988545282, + 18.0680659885452, + 18.068065988545133, + 18.068065988545126, + 18.068065988545115, + 18.068065988545115, + 18.068065988545115, + 18.068070127564237, + 18.06807012756457, + 18.068070127564233, + 18.068070127564365, + 18.06807012756445, + 18.068070127564457, + 18.068070127564468, + 18.06807012756447, + 18.06807012756447, + 18.06807012756447, + 18.06807032891735 + ], + "marker": { + "size": 10 + }, + "mode": "markers", + "type": "scattermapbox" + }, + { + "lat": [ + 59.350791 + ], + "lon": [ + 18.067825 + ], + "marker": { + "size": 10 + }, + "mode": "markers", + "type": "scattermapbox" + } + ], + "layout": { + "mapbox": { + "center": { + "lat": 59.350791, + "lon": 18.067825 + }, + "style": "open-street-map", + "zoom": 18 + }, + "margin": { + "b": 10, + "l": 10, + "r": 10, + "t": 10 + }, + "template": { + "data": { + "bar": [ + { + "error_x": { + "color": "#2a3f5f" + }, + "error_y": { + "color": "#2a3f5f" + }, + "marker": { + "line": { + "color": "#E5ECF6", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "bar" + } + ], + "barpolar": [ + { + "marker": { + "line": { + "color": "#E5ECF6", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "barpolar" + } + ], + "carpet": [ + { + "aaxis": { + "endlinecolor": "#2a3f5f", + "gridcolor": "white", + "linecolor": "white", + "minorgridcolor": "white", + "startlinecolor": "#2a3f5f" + }, + "baxis": { + "endlinecolor": "#2a3f5f", + "gridcolor": "white", + "linecolor": "white", + "minorgridcolor": "white", + "startlinecolor": "#2a3f5f" + }, + "type": "carpet" + } + ], + "choropleth": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "choropleth" + } + ], + "contour": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "contour" + } + ], + "contourcarpet": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "contourcarpet" + } + ], + "heatmap": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "heatmap" + } + ], + "heatmapgl": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "heatmapgl" + } + ], + "histogram": [ + { + "marker": { + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "histogram" + } + ], + "histogram2d": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "histogram2d" + } + ], + "histogram2dcontour": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "histogram2dcontour" + } + ], + "mesh3d": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "mesh3d" + } + ], + "parcoords": [ + { + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "parcoords" + } + ], + "pie": [ + { + "automargin": true, + "type": "pie" + } + ], + "scatter": [ + { + "fillpattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + }, + "type": "scatter" + } + ], + "scatter3d": [ + { + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatter3d" + } + ], + "scattercarpet": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattercarpet" + } + ], + "scattergeo": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattergeo" + } + ], + "scattergl": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattergl" + } + ], + "scattermapbox": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattermapbox" + } + ], + "scatterpolar": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterpolar" + } + ], + "scatterpolargl": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterpolargl" + } + ], + "scatterternary": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterternary" + } + ], + "surface": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "surface" + } + ], + "table": [ + { + "cells": { + "fill": { + "color": "#EBF0F8" + }, + "line": { + "color": "white" + } + }, + "header": { + "fill": { + "color": "#C8D4E3" + }, + "line": { + "color": "white" + } + }, + "type": "table" + } + ] + }, + "layout": { + "annotationdefaults": { + "arrowcolor": "#2a3f5f", + "arrowhead": 0, + "arrowwidth": 1 + }, + "autotypenumbers": "strict", + "coloraxis": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "colorscale": { + "diverging": [ + [ + 0, + "#8e0152" + ], + [ + 0.1, + "#c51b7d" + ], + [ + 0.2, + "#de77ae" + ], + [ + 0.3, + "#f1b6da" + ], + [ + 0.4, + "#fde0ef" + ], + [ + 0.5, + "#f7f7f7" + ], + [ + 0.6, + "#e6f5d0" + ], + [ + 0.7, + "#b8e186" + ], + [ + 0.8, + "#7fbc41" + ], + [ + 0.9, + "#4d9221" + ], + [ + 1, + "#276419" + ] + ], + "sequential": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "sequentialminus": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ] + }, + "colorway": [ + "#636efa", + "#EF553B", + "#00cc96", + "#ab63fa", + "#FFA15A", + "#19d3f3", + "#FF6692", + "#B6E880", + "#FF97FF", + "#FECB52" + ], + "font": { + "color": "#2a3f5f" + }, + "geo": { + "bgcolor": "white", + "lakecolor": "white", + "landcolor": "#E5ECF6", + "showlakes": true, + "showland": true, + "subunitcolor": "white" + }, + "hoverlabel": { + "align": "left" + }, + "hovermode": "closest", + "mapbox": { + "style": "light" + }, + "paper_bgcolor": "white", + "plot_bgcolor": "#E5ECF6", + "polar": { + "angularaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "bgcolor": "#E5ECF6", + "radialaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + } + }, + "scene": { + "xaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + }, + "yaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + }, + "zaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + } + }, + "shapedefaults": { + "line": { + "color": "#2a3f5f" + } + }, + "ternary": { + "aaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "baxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "bgcolor": "#E5ECF6", + "caxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + } + }, + "title": { + "x": 0.05 + }, + "xaxis": { + "automargin": true, + "gridcolor": "white", + "linecolor": "white", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "white", + "zerolinewidth": 2 + }, + "yaxis": { + "automargin": true, + "gridcolor": "white", + "linecolor": "white", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "white", + "zerolinewidth": 2 + } + } + } + } + }, + "text/html": [ + "
\n", + "
" + ], + "text/plain": [ + "Figure({\n", + " 'data': [{'lat': [59.35093418921517, 59.35093398436031, 59.350933935363415,\n", + " ..., 59.35092965639449, 59.35092965639449, 59.35092965639449],\n", + " 'lon': [18.068044270978096, 18.068044399069947, 18.068044429706774,\n", + " ..., 18.068060547339595, 18.0680605473396, 18.0680605473396],\n", + " 'marker': {'size': 10},\n", + " 'mode': 'markers',\n", + " 'type': 'scattermapbox'},\n", + " {'lat': [59.35089426416136, 59.35089481178939, 59.35089483355297,\n", + " ..., 59.35092447731162, 59.35092447731162, 59.35092473299392],\n", + " 'lon': [18.068049518147564, 18.06804963070863, 18.068049633812763,\n", + " ..., 18.06807012756447, 18.06807012756447, 18.06807032891735],\n", + " 'marker': {'size': 10},\n", + " 'mode': 'markers',\n", + " 'type': 'scattermapbox'},\n", + " {'lat': [59.350791], 'lon': [18.067825], 'marker': {'size': 10}, 'mode': 'markers', 'type': 'scattermapbox'}],\n", + " 'layout': {'mapbox': {'center': {'lat': 59.350791, 'lon': 18.067825}, 'style': 'open-street-map', 'zoom': 18},\n", + " 'margin': {'b': 10, 'l': 10, 'r': 10, 't': 10},\n", + " 'template': '...'}\n", + "})" + ] + }, + "execution_count": 6, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "import plotly.graph_objects as go\n", + "fig = go.Figure(go.Scattermapbox(\n", + " mode = \"markers\",\n", + " lon = Long1,\n", + " lat = Lat1,\n", + " marker = {'size': 10}))\n", + "fig.add_trace(go.Scattermapbox(\n", + " mode = \"markers\",\n", + " lon = Long2,\n", + " lat = Lat2,\n", + " marker = {'size': 10}))\n", + "fig.add_trace(go.Scattermapbox(\n", + " mode = \"markers\",\n", + " lon = [18.067825],\n", + " lat = [59.350791],\n", + " marker = {'size': 10}))\n", + "fig.update_layout(\n", + " margin ={'l':10,'t':10,'b':10,'r':10},\n", + " mapbox = {\n", + " 'center': {'lon': 18.067825, 'lat': 59.350791},\n", + " 'style': \"open-street-map\",\n", + " 'zoom': 18\n", + " })" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} From 73286a40db1e9c769f922d073d8f6e219ae56e42 Mon Sep 17 00:00:00 2001 From: annika Date: Mon, 29 Jan 2024 13:22:27 +0100 Subject: [PATCH 05/10] Separeted into 2 scripts one for publishing the frame, one for doing calculation --- src/svea_sensors/launch/localize.launch | 9 +- src/svea_sensors/scripts/fixedframestate.py | 107 ------------------ src/svea_sensors/scripts/latlong_to_xy.py | 94 +++++++++++++++ .../scripts/reference_gps_frame.py | 57 ++++++++++ 4 files changed, 159 insertions(+), 108 deletions(-) delete mode 100755 src/svea_sensors/scripts/fixedframestate.py create mode 100755 src/svea_sensors/scripts/latlong_to_xy.py create mode 100755 src/svea_sensors/scripts/reference_gps_frame.py diff --git a/src/svea_sensors/launch/localize.launch b/src/svea_sensors/launch/localize.launch index 43241647..f58971df 100644 --- a/src/svea_sensors/launch/localize.launch +++ b/src/svea_sensors/launch/localize.launch @@ -161,6 +161,13 @@ - + + + reference_gps: [59.350791, 18.067825] + + + + + diff --git a/src/svea_sensors/scripts/fixedframestate.py b/src/svea_sensors/scripts/fixedframestate.py deleted file mode 100755 index d6012285..00000000 --- a/src/svea_sensors/scripts/fixedframestate.py +++ /dev/null @@ -1,107 +0,0 @@ -#!/usr/bin/env python3 -import rospy -import tf2_ros - -import numpy as np - -from geopy.distance import geodesic -from pyproj import Proj - -from sensor_msgs.msg import NavSatFix -from svea_msgs.msg import VehicleState -from geometry_msgs.msg import TransformStamped, Vector3, Quaternion - - -class FixedFrameState: - def __init__(self): - # Initialize node - rospy.init_node('FixedFrameState') - - # Subscriber - rospy.Subscriber('/gps/filtered', NavSatFix, self.GpsFilteredCallback) - - # Publisher - self.FixedFrameState = rospy.Publisher('/fixedgps/state', VehicleState, queue_size=10) - - # Fixed GPS latitude, Longitude - self.fixed_gps = rospy.get_param("~fixed_gps", (59.350791, 18.067825)) - self.show_frame = rospy.get_param("~show_frame", True) - # self.fixed_gps = (59.350791, 18.067825) #(latitude, longitude) #ITRL pose - - # Transformation - self.buffer = tf2_ros.Buffer(rospy.Duration(10)) - self.listener = tf2_ros.TransformListener(self.buffer) - self.br = tf2_ros.TransformBroadcaster() - self.static_br = tf2_ros.StaticTransformBroadcaster() - - self.PublishFixedGpsFrame() - - def run(self): - rospy.spin() - - def PublishFixedGpsFrame(self): - projection = Proj(proj='utm', zone=34, ellps='WGS84') - utm = projection(self.fixed_gps[1], self.fixed_gps[0]) - FixedGpsFrame = TransformStamped() - FixedGpsFrame.header.stamp = rospy.Time.now() - FixedGpsFrame.header.frame_id = "utm" - FixedGpsFrame.child_frame_id = "Fixed_gps" - FixedGpsFrame.transform.translation = Vector3(*[utm[0], utm[1], 0.0]) - FixedGpsFrame.transform.rotation = Quaternion(*[0.0, 0.0, 0.0, 1.0]) - self.static_br.sendTransform(FixedGpsFrame) - - def GpsFilteredCallback(self, msg): - x, y = self.LatLongToXY((msg.latitude, msg.longitude)) - self.StateMsg(msg.header, x,y) - - def LatLongToXY(self, filtered_gps): - distance = geodesic(self.fixed_gps, filtered_gps).meters - - bearing = self.CalculateBearing(filtered_gps) - - x = distance * np.sin(np.radians(bearing)) - y = distance * np.cos(np.radians(bearing)) - - return x, y - - def CalculateBearing(self, filtered_gps): - lat1 = np.radians(self.fixed_gps[0]) - lat2 = np.radians(filtered_gps[0]) - diffLong = np.radians(filtered_gps[1] - self.fixed_gps[1]) - - x = np.sin(diffLong) * np.cos(lat2) - y = np.cos(lat1) * np.sin(lat2) - (np.sin(lat1) * np.cos(lat2) * np.cos(diffLong)) - - initial_bearing = np.arctan2(x, y) - - initial_bearing = np.degrees(initial_bearing) - compass_bearing = (initial_bearing + 360) % 360 - - return compass_bearing - - def StateMsg(self, header, x, y): - msg = VehicleState() - msg.header = header - msg.header.frame_id = "Fixed_gps" - msg.child_frame_id = "base_link_fixed_gps" - msg.x = x - msg.y = y - msg.yaw = 0 - msg.v = 0 - msg.covariance = [0, 0, 0, 0, - 0, 0, 0, 0, - 0, 0, 0, 0, - 0, 0, 0, 0] - self.FixedFrameState.publish(msg) - - if self.show_frame: - msgT = TransformStamped() - msgT.header = header - msgT.header.frame_id = "Fixed_gps" - msgT.child_frame_id = "base_link_fixed_gps" - msgT.transform.translation = Vector3(*[x,y,0.0]) - msgT.transform.rotation = Quaternion(*[0.0, 0.0, 0.0, 1.0]) - self.br.sendTransform(msgT) - -if __name__ == '__main__': - FixedFrameState().run() diff --git a/src/svea_sensors/scripts/latlong_to_xy.py b/src/svea_sensors/scripts/latlong_to_xy.py new file mode 100755 index 00000000..b8d60fb5 --- /dev/null +++ b/src/svea_sensors/scripts/latlong_to_xy.py @@ -0,0 +1,94 @@ +#!/usr/bin/env python3 +import rospy +import tf2_ros + +import numpy as np + +from geopy.distance import geodesic + +from sensor_msgs.msg import NavSatFix +from svea_msgs.msg import VehicleState +from geometry_msgs.msg import TransformStamped, Vector3, Quaternion + +class latlong_to_xy: + def __init__(self): + # Initialize node + rospy.init_node('latlong_to_xy') + + self.reference_gps = (-1, -1) + + # Subscriber + rospy.Subscriber('/gps/filtered', NavSatFix, self.vehicle_gps_callback) + rospy.Subscriber('/gps/reference_point', NavSatFix, self.reference_gps_callback) + + # Publisher + self.RefernceGpsState = rospy.Publisher('/gps/reference_state', VehicleState, queue_size=10) + + # Transformation + self.buffer = tf2_ros.Buffer(rospy.Duration(10)) + self.listener = tf2_ros.TransformListener(self.buffer) + self.br = tf2_ros.TransformBroadcaster() + self.static_br = tf2_ros.StaticTransformBroadcaster() + + def run(self): + rospy.spin() + + def reference_gps_callback(self, msg): + if -1 in self.reference_gps: + self.reference_gps = (msg.latitude, msg.longitude) + + def vehicle_gps_callback(self, msg): + if not -1 in self.reference_gps: + x, y = self.LatLongToXY((msg.latitude, msg.longitude)) + self.StateMsg(msg.header, x,y) + + def LatLongToXY(self, vehicle_gps): + distance = geodesic(self.reference_gps, vehicle_gps).meters + + bearing = self.CalculateBearing(vehicle_gps) + + x = distance * np.sin(np.radians(bearing)) + y = distance * np.cos(np.radians(bearing)) + + return x, y + + def CalculateBearing(self, vehicle_gps): + lat1 = np.radians(self.reference_gps[0]) + lat2 = np.radians(vehicle_gps[0]) + diffLong = np.radians(vehicle_gps[1] - self.reference_gps[1]) + + x = np.sin(diffLong) * np.cos(lat2) + y = np.cos(lat1) * np.sin(lat2) - (np.sin(lat1) * np.cos(lat2) * np.cos(diffLong)) + + initial_bearing = np.arctan2(x, y) + + initial_bearing = np.degrees(initial_bearing) + compass_bearing = (initial_bearing + 360) % 360 + + return compass_bearing + + def StateMsg(self, header, x, y): + msg = VehicleState() + msg.header = header + msg.header.frame_id = "Reference_gps" + msg.child_frame_id = "base_link_fixed_gps" + msg.x = x + msg.y = y + msg.yaw = 0 + msg.v = 0 + msg.covariance = [0, 0, 0, 0, + 0, 0, 0, 0, + 0, 0, 0, 0, + 0, 0, 0, 0] + self.RefernceGpsState.publish(msg) + + msgT = TransformStamped() + msgT.header = header + msgT.header.frame_id = "Reference_gps" + msgT.child_frame_id = "base_link_fixed_gps" + msgT.transform.translation = Vector3(*[x,y,0.0]) + msgT.transform.rotation = Quaternion(*[0.0, 0.0, 0.0, 1.0]) + self.br.sendTransform(msgT) + +if __name__ == '__main__': + latlong_to_xy().run() diff --git a/src/svea_sensors/scripts/reference_gps_frame.py b/src/svea_sensors/scripts/reference_gps_frame.py new file mode 100755 index 00000000..de9fe4ab --- /dev/null +++ b/src/svea_sensors/scripts/reference_gps_frame.py @@ -0,0 +1,57 @@ +#!/usr/bin/env python3 +import rospy +import tf2_ros + +from pyproj import Proj + +from geometry_msgs.msg import TransformStamped, Vector3, Quaternion +from sensor_msgs.msg import NavSatFix + +#################################################### +### Publish the reference gps frame in utm frame ### +#################################################### + +class reference_gps_frame: + def __init__(self): + # Initialize node + rospy.init_node('reference_gps_frame') + + # Reference GPS latitude, Longitude + self.reference_gps = rospy.get_param("~reference_gps", [59.350791, 18.067825]) #ITRL + + # Publisher + self.reference_gps_publisher = rospy.Publisher('/gps/reference_point', NavSatFix, queue_size=10) + + # Transformation + self.buffer = tf2_ros.Buffer(rospy.Duration(10)) + self.static_br = tf2_ros.StaticTransformBroadcaster() + + # Variables + self.rate = rospy.Rate(10) + self.seq = 0 + + def PublishReferenceGpsFrame(self): + projection = Proj(proj='utm', zone=34, ellps='WGS84') + utm = projection(self.reference_gps[1], self.reference_gps[0]) + FixedGpsFrame = TransformStamped() + FixedGpsFrame.header.stamp = rospy.Time.now() + FixedGpsFrame.header.frame_id = "utm" + FixedGpsFrame.child_frame_id = "reference_gps" + FixedGpsFrame.transform.translation = Vector3(*[utm[0], utm[1], 0.0]) + FixedGpsFrame.transform.rotation = Quaternion(*[0.0, 0.0, 0.0, 1.0]) + self.static_br.sendTransform(FixedGpsFrame) + + reference_msg = NavSatFix() + reference_msg.header.stamp = rospy.Time.now() + reference_msg.header.frame_id = "utm" + reference_msg.latitude = self.reference_gps[0] + reference_msg.longitude = self.reference_gps[1] + + while not rospy.is_shutdown(): + reference_msg.header.seq = self.seq + self.seq += 1 + self.reference_gps_publisher.publish(reference_msg) + self.rate.sleep() + +if __name__ == '__main__': + reference_gps_frame().PublishReferenceGpsFrame() From 1b605e566bf4f408b1d1810edc7a261be550ed13 Mon Sep 17 00:00:00 2001 From: annika Date: Tue, 30 Jan 2024 10:18:25 +0100 Subject: [PATCH 06/10] updated frame name --- src/svea_sensors/scripts/latlong_to_xy.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/svea_sensors/scripts/latlong_to_xy.py b/src/svea_sensors/scripts/latlong_to_xy.py index b8d60fb5..3fcc4c99 100755 --- a/src/svea_sensors/scripts/latlong_to_xy.py +++ b/src/svea_sensors/scripts/latlong_to_xy.py @@ -70,7 +70,7 @@ def CalculateBearing(self, vehicle_gps): def StateMsg(self, header, x, y): msg = VehicleState() msg.header = header - msg.header.frame_id = "Reference_gps" + msg.header.frame_id = "reference_gps" msg.child_frame_id = "base_link_fixed_gps" msg.x = x msg.y = y @@ -84,7 +84,7 @@ def StateMsg(self, header, x, y): msgT = TransformStamped() msgT.header = header - msgT.header.frame_id = "Reference_gps" + msgT.header.frame_id = "reference_gps" msgT.child_frame_id = "base_link_fixed_gps" msgT.transform.translation = Vector3(*[x,y,0.0]) msgT.transform.rotation = Quaternion(*[0.0, 0.0, 0.0, 1.0]) From 3c4f7aeb289c81f2050d911a8c81356f63276b92 Mon Sep 17 00:00:00 2001 From: Annika-wyt Date: Tue, 30 Jan 2024 10:27:44 +0100 Subject: [PATCH 07/10] cleanup repo for pr --- analysis.ipynb | 2980 ------------------------------------------------ 1 file changed, 2980 deletions(-) delete mode 100644 analysis.ipynb diff --git a/analysis.ipynb b/analysis.ipynb deleted file mode 100644 index 26211f16..00000000 --- a/analysis.ipynb +++ /dev/null @@ -1,2980 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [], - "source": [ - "import rosbag\n", - "from std_msgs.msg import String # Import the message type you expect to read\n", - "\n", - "# Specify the path to your ROS bag file\n", - "bag_path = '/home/annika/ITRL/GPS_frame/rosbag/2024-01-23-11-08-25.bag'\n", - "FixedFrameState1 = []\n", - "Lat1 = []\n", - "Long1 = []\n", - "# Open the bag file\n", - "with rosbag.Bag(bag_path, 'r') as bag:\n", - " # Iterate through messages in the bag\n", - " for topic, msg, t in bag.read_messages():\n", - " # Process the messages based on the topic\n", - " if topic == '/fixedgps/state':\n", - " FixedFrameState1.append([msg.x,msg.y])\n", - " if topic == '/gps/filtered':\n", - " Lat1.append(msg.latitude)\n", - " Long1.append(msg.longitude)\n", - "# Note: Replace '/your/topic' with the actual topic you are interested in\n", - "# You also need to import the correct message type for the specified topic\n" - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [], - "source": [ - "import rosbag\n", - "from std_msgs.msg import String # Import the message type you expect to read\n", - "\n", - "# Specify the path to your ROS bag file\n", - "bag_path = '/home/annika/ITRL/GPS_frame/rosbag/2024-01-23-11-12-00.bag'\n", - "FixedFrameState2 = []\n", - "Lat2 = []\n", - "Long2 = []\n", - "\n", - "# Open the bag file\n", - "with rosbag.Bag(bag_path, 'r') as bag:\n", - " # Iterate through messages in the bag\n", - " for topic, msg, t in bag.read_messages():\n", - " # Process the messages based on the topic\n", - " if topic == '/fixedgps/state':\n", - " FixedFrameState2.append([msg.x,msg.y])\n", - " if topic == '/gps/filtered':\n", - " Lat2.append(msg.latitude)\n", - " Long2.append(msg.longitude)\n", - "# Note: Replace '/your/topic' with the actual topic you are interested in\n", - "# You also need to import the correct message type for the specified topic\n" - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "import matplotlib.pyplot as plt\n", - "\n", - "x_values1, y_values1 = zip(*FixedFrameState1)\n", - "x_values2, y_values2 = zip(*FixedFrameState2)\n", - "\n", - "# Create a scatter plot for the first set of coordinates\n", - "plt.scatter(x_values1, y_values1, marker='o', label='Coordinates 1')\n", - "\n", - "# Create a scatter plot for the second set of coordinates\n", - "plt.scatter(x_values2, y_values2, marker='s', label='Coordinates 2')\n", - "\n", - "# Add labels and title\n", - "plt.xlabel('X-axis')\n", - "plt.xlim(10,20)\n", - "plt.ylim(5,20)\n", - "plt.ylabel('Y-axis')\n", - "plt.title('Scatter Plot of Coordinates')\n", - "\n", - "# Add a legend\n", - "plt.legend()\n", - "\n", - "# Display the plot\n", - "plt.show()" - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "metadata": {}, - "outputs": [ - { - "ename": "ValueError", - "evalue": "Mime type rendering requires nbformat>=4.2.0 but it is not installed", - "output_type": "error", - "traceback": [ - "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", - "\u001b[0;31mValueError\u001b[0m Traceback (most recent call last)", - "File \u001b[0;32m~/.local/lib/python3.8/site-packages/IPython/core/formatters.py:922\u001b[0m, in \u001b[0;36mIPythonDisplayFormatter.__call__\u001b[0;34m(self, obj)\u001b[0m\n\u001b[1;32m 920\u001b[0m method \u001b[38;5;241m=\u001b[39m get_real_method(obj, \u001b[38;5;28mself\u001b[39m\u001b[38;5;241m.\u001b[39mprint_method)\n\u001b[1;32m 921\u001b[0m \u001b[38;5;28;01mif\u001b[39;00m method \u001b[38;5;129;01mis\u001b[39;00m \u001b[38;5;129;01mnot\u001b[39;00m \u001b[38;5;28;01mNone\u001b[39;00m:\n\u001b[0;32m--> 922\u001b[0m \u001b[43mmethod\u001b[49m\u001b[43m(\u001b[49m\u001b[43m)\u001b[49m\n\u001b[1;32m 923\u001b[0m \u001b[38;5;28;01mreturn\u001b[39;00m \u001b[38;5;28;01mTrue\u001b[39;00m\n", - "File \u001b[0;32m/usr/local/lib/python3.8/dist-packages/plotly/basedatatypes.py:834\u001b[0m, in \u001b[0;36mBaseFigure._ipython_display_\u001b[0;34m(self)\u001b[0m\n\u001b[1;32m 831\u001b[0m \u001b[38;5;28;01mimport\u001b[39;00m \u001b[38;5;21;01mplotly\u001b[39;00m\u001b[38;5;21;01m.\u001b[39;00m\u001b[38;5;21;01mio\u001b[39;00m \u001b[38;5;28;01mas\u001b[39;00m \u001b[38;5;21;01mpio\u001b[39;00m\n\u001b[1;32m 833\u001b[0m \u001b[38;5;28;01mif\u001b[39;00m pio\u001b[38;5;241m.\u001b[39mrenderers\u001b[38;5;241m.\u001b[39mrender_on_display \u001b[38;5;129;01mand\u001b[39;00m pio\u001b[38;5;241m.\u001b[39mrenderers\u001b[38;5;241m.\u001b[39mdefault:\n\u001b[0;32m--> 834\u001b[0m \u001b[43mpio\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43mshow\u001b[49m\u001b[43m(\u001b[49m\u001b[38;5;28;43mself\u001b[39;49m\u001b[43m)\u001b[49m\n\u001b[1;32m 835\u001b[0m \u001b[38;5;28;01melse\u001b[39;00m:\n\u001b[1;32m 836\u001b[0m \u001b[38;5;28mprint\u001b[39m(\u001b[38;5;28mrepr\u001b[39m(\u001b[38;5;28mself\u001b[39m))\n", - "File \u001b[0;32m/usr/local/lib/python3.8/dist-packages/plotly/io/_renderers.py:396\u001b[0m, in \u001b[0;36mshow\u001b[0;34m(fig, renderer, validate, **kwargs)\u001b[0m\n\u001b[1;32m 391\u001b[0m \u001b[38;5;28;01mraise\u001b[39;00m \u001b[38;5;167;01mValueError\u001b[39;00m(\n\u001b[1;32m 392\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mMime type rendering requires ipython but it is not installed\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 393\u001b[0m )\n\u001b[1;32m 395\u001b[0m \u001b[38;5;28;01mif\u001b[39;00m \u001b[38;5;129;01mnot\u001b[39;00m nbformat \u001b[38;5;129;01mor\u001b[39;00m Version(nbformat\u001b[38;5;241m.\u001b[39m__version__) \u001b[38;5;241m<\u001b[39m Version(\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124m4.2.0\u001b[39m\u001b[38;5;124m\"\u001b[39m):\n\u001b[0;32m--> 396\u001b[0m \u001b[38;5;28;01mraise\u001b[39;00m \u001b[38;5;167;01mValueError\u001b[39;00m(\n\u001b[1;32m 397\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mMime type rendering requires nbformat>=4.2.0 but it is not installed\u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 398\u001b[0m )\n\u001b[1;32m 400\u001b[0m ipython_display\u001b[38;5;241m.\u001b[39mdisplay(bundle, raw\u001b[38;5;241m=\u001b[39m\u001b[38;5;28;01mTrue\u001b[39;00m)\n\u001b[1;32m 402\u001b[0m \u001b[38;5;66;03m# external renderers\u001b[39;00m\n", - "\u001b[0;31mValueError\u001b[0m: Mime type rendering requires nbformat>=4.2.0 but it is not installed" - ] - }, - { - "data": { - "application/vnd.plotly.v1+json": { - "config": { - "plotlyServerURL": "https://plot.ly" - }, - "data": [ - { - "lat": [ - 59.35093418921517, - 59.35093398436031, - 59.350933935363415, - 59.35093387974216, - 59.350933760629964, - 59.35093368184484, - 59.3509335391803, - 59.3509334457256, - 59.35093333923206, - 59.35093316716608, - 59.35093303167464, - 59.350934231064635, - 59.35093430464705, - 59.350934389006454, - 59.350934476434645, - 59.3509345923912, - 59.350934706177256, - 59.350934828526285, - 59.35093496337312, - 59.350935121971744, - 59.35093527722425, - 59.35093412574053, - 59.350934088774295, - 59.35093404225967, - 59.350933993284286, - 59.35093413395637, - 59.350934141258556, - 59.35093414209081, - 59.350934142193296, - 59.35093414220788, - 59.35093414220909, - 59.35093415700226, - 59.35093415700288, - 59.350934157002875, - 59.35093420499426, - 59.3509343526174, - 59.35093461806497, - 59.3509348657099, - 59.350935186423854, - 59.350935435252964, - 59.350935687096, - 59.35093423684614, - 59.350934273691195, - 59.350934285401856, - 59.3509342890854, - 59.3509342896016, - 59.35093429013192, - 59.35093429030198, - 59.35093429029902, - 59.3509342903276, - 59.350934290328894, - 59.35093384439928, - 59.35093384440822, - 59.35093384440454, - 59.35093384440602, - 59.350933844405205, - 59.35093384440529, - 59.35093384440526, - 59.35093384440529, - 59.35093390270209, - 59.35093406389306, - 59.35093411791978, - 59.35093432775067, - 59.350934509545986, - 59.35093471364097, - 59.350934886688464, - 59.35093508103694, - 59.350935252507924, - 59.3509354106334, - 59.35093560962067, - 59.35093576175538, - 59.35093386304307, - 59.35093390144817, - 59.350933918380534, - 59.35093392395752, - 59.350933925329294, - 59.350933926013795, - 59.35093392624577, - 59.35093392627217, - 59.35093392630084, - 59.350933926300144, - 59.35093351642469, - 59.35093361313984, - 59.35093370793795, - 59.35093382066967, - 59.35093388650657, - 59.350933902566595, - 59.35093394427, - 59.350934026290766, - 59.35093413579156, - 59.350934173856494, - 59.35093339811412, - 59.35093340308407, - 59.35093344802081, - 59.350933546252925, - 59.35093360070151, - 59.35093362565511, - 59.35093363395441, - 59.35093363634482, - 59.35093363732256, - 59.35093369340774, - 59.350933536161435, - 59.3509337542757, - 59.3509339452777, - 59.35093400844815, - 59.350934031534436, - 59.35093403899366, - 59.35093404121382, - 59.3509340418686, - 59.35093404208594, - 59.35093406359414, - 59.35093354288257, - 59.3509336617239, - 59.35093382753525, - 59.35093403297353, - 59.3509342500317, - 59.3509344654844, - 59.350934678942025, - 59.35093485341199, - 59.35093492525569, - 59.35093495863062, - 59.35093362863677, - 59.350933780198254, - 59.35093397203836, - 59.35093412844597, - 59.35093432559991, - 59.35093447896678, - 59.35093464621281, - 59.35093480790871, - 59.35093496393824, - 59.35093512111655, - 59.350932311448005, - 59.350932294612946, - 59.350932278557224, - 59.35093226209446, - 59.35093224419259, - 59.35093222327809, - 59.350932204365336, - 59.35093218189516, - 59.350932161779326, - 59.35093106291146, - 59.350930949423244, - 59.35093083524947, - 59.35093071894353, - 59.35093060085244, - 59.35093047989987, - 59.35093035811927, - 59.350930235958025, - 59.35093011253774, - 59.350929988789574, - 59.35092986331414, - 59.35092993059303, - 59.350929771103566, - 59.35092961003053, - 59.35092944390035, - 59.3509292861645, - 59.350929122814236, - 59.35092899704665, - 59.350928948072, - 59.35092893151625, - 59.35092892633827, - 59.35092929790413, - 59.35092929716669, - 59.350929296987665, - 59.35092929692059, - 59.35092929690455, - 59.35092929690117, - 59.350929296899636, - 59.350929288658136, - 59.35092921784193, - 59.350929110512915, - 59.35092868456478, - 59.35092853732186, - 59.35092837137857, - 59.350928199180274, - 59.35092802578967, - 59.350927850597685, - 59.35092767544515, - 59.35092750005734, - 59.35092732378136, - 59.35092715272943, - 59.350928838975655, - 59.35092867978488, - 59.35092852251859, - 59.350928363500444, - 59.35092819469746, - 59.35092805174688, - 59.35092789166208, - 59.350927765309926, - 59.350927624521674, - 59.35092749880752, - 59.350927976899456, - 59.35092786598216, - 59.35092773886214, - 59.35092764549164, - 59.35092754502211, - 59.35092744747949, - 59.350927350774086, - 59.3509272508211, - 59.350927167570674, - 59.35092710284661, - 59.350927692979475, - 59.35092768721027, - 59.35092770074705, - 59.35092772668241, - 59.350927763023904, - 59.35092781977926, - 59.3509278922694, - 59.350927990688334, - 59.350928108270466, - 59.35092824714802, - 59.35092822331859, - 59.350928438961674, - 59.350928687394855, - 59.35092893417952, - 59.35092921683767, - 59.35092952539368, - 59.35092984806608, - 59.35093018849278, - 59.350930543869424, - 59.35092879772979, - 59.35092914347311, - 59.35092951704213, - 59.35092990035939, - 59.35093029659973, - 59.35093070972458, - 59.35093113266277, - 59.350931568453326, - 59.35093200051941, - 59.3509324621964, - 59.350929868395724, - 59.350930358589544, - 59.350930769555944, - 59.350931282954754, - 59.350931707772006, - 59.35093218852673, - 59.350932674546186, - 59.35093316864486, - 59.35093367204806, - 59.35093416779679, - 59.35093467472233, - 59.350931549204866, - 59.35093205872458, - 59.35093257509615, - 59.35093310004483, - 59.350933603093054, - 59.35093415331548, - 59.35093463608049, - 59.35093518519277, - 59.35093566784275, - 59.350936210629925, - 59.350928324716214, - 59.35092875679359, - 59.35092919874967, - 59.35092964218899, - 59.350930099084785, - 59.35093056415445, - 59.35093105837103, - 59.350931515778576, - 59.35093200038381, - 59.35093538760263, - 59.35093590914744, - 59.35093642215316, - 59.35093693653519, - 59.35093744665977, - 59.3509379539465, - 59.350938460203615, - 59.35093896219679, - 59.35093945739746, - 59.35093994717977, - 59.350936843305995, - 59.35093725280038, - 59.35093765329236, - 59.35093809695475, - 59.35093842455919, - 59.350938850504235, - 59.35093917921713, - 59.35093960674663, - 59.350939948656645, - 59.35094037140777, - 59.350937911537265, - 59.3509382419917, - 59.35093856140071, - 59.35093884800918, - 59.350939207821135, - 59.35093948143346, - 59.35093983594604, - 59.35094015022942, - 59.35094049546687, - 59.350940819860256, - 59.35094114854415, - 59.35093836024402, - 59.35093864039827, - 59.35093891460035, - 59.35093916104285, - 59.3509394825852, - 59.35093972686004, - 59.35094001368817, - 59.35094030603591, - 59.35094058689316, - 59.35093964054362, - 59.350939917547976, - 59.35094019227588, - 59.35094046563531, - 59.35094073247508, - 59.35094098877525, - 59.350941231352536, - 59.35094146053603, - 59.35094165125453, - 59.35094182752093, - 59.35094198522418, - 59.35093988631573, - 59.35093995797311, - 59.35094000987185, - 59.350940046522155, - 59.35094006532367, - 59.350940074566836, - 59.350940067094385, - 59.350940030133664, - 59.350939981499806, - 59.35094035193397, - 59.350940241050225, - 59.35094011703565, - 59.35093997040628, - 59.35093983036406, - 59.35093963881806, - 59.35093946600912, - 59.350939227795365, - 59.35093903248613, - 59.35093875218389, - 59.35093909859334, - 59.350938694335255, - 59.35093833577274, - 59.35093794157552, - 59.35093769998254, - 59.350937612344254, - 59.3509375847802, - 59.35093757486702, - 59.35093757295401, - 59.35093757148168, - 59.35093760940036, - 59.35093760930323, - 59.35093760923344, - 59.350937609230726, - 59.350937609223166, - 59.35093759467626, - 59.35093745869899, - 59.35093718012152, - 59.35093694723406, - 59.350936658601775, - 59.350937230880135, - 59.35093686034517, - 59.35093648821283, - 59.350936092956985, - 59.350935685978214, - 59.35093526292049, - 59.35093483096496, - 59.35093438466812, - 59.350933922964444, - 59.35093345154467, - 59.35093684121075, - 59.35093636549968, - 59.350935829142415, - 59.3509353860495, - 59.35093488767717, - 59.35093438487492, - 59.35093388064546, - 59.35093337627727, - 59.35093287299384, - 59.35093237317109, - 59.35093187639585, - 59.35093532702728, - 59.35093485011764, - 59.35093434845632, - 59.35093384604876, - 59.35093335739511, - 59.35093281770641, - 59.35093238157786, - 59.3509318589327, - 59.350931429291805, - 59.35093091302221, - 59.35093151677364, - 59.350931129356844, - 59.3509308384278, - 59.35093049428842, - 59.350930215777666, - 59.35092989864302, - 59.3509296396273, - 59.35092937070198, - 59.350929112281655, - 59.35093059424409, - 59.35093036031125, - 59.35093017054177, - 59.35092997356601, - 59.35092982341361, - 59.35092966243366, - 59.35092955117404, - 59.35092941596698, - 59.35092933384739, - 59.350929261710874, - 59.350929574070264, - 59.35092956209695, - 59.35092955792841, - 59.350929556752845, - 59.350929556361905, - 59.35092955625916, - 59.35092955622726, - 59.35092955621632, - 59.35092955621485, - 59.35092955621349, - 59.35092955621336, - 59.35092942003162, - 59.350929420029004, - 59.350929420029146, - 59.350929420029544, - 59.350929420029814, - 59.35092942002986, - 59.350929420029885, - 59.350929420029885, - 59.3509294200299, - 59.350929656134845, - 59.35092965613816, - 59.3509296561383, - 59.35092965613814, - 59.35092965613798, - 59.35092965613799, - 59.350929656138, - 59.35092965613799, - 59.35092965613799, - 59.35092965613799, - 59.350929656413555, - 59.350929656413555, - 59.35092965641357, - 59.35092965641357, - 59.350929656413555, - 59.35092965641357, - 59.35092965641357, - 59.35092965641357, - 59.35092965641357, - 59.35092965641357, - 59.3509296563938, - 59.35092965639449, - 59.35092965639451, - 59.35092965639454, - 59.35092965639449, - 59.35092965639449, - 59.35092965639449, - 59.35092965639449, - 59.35092965639449, - 59.35092965639449 - ], - "lon": [ - 18.068044270978096, - 18.068044399069947, - 18.068044429706774, - 18.068044464485688, - 18.068044538964273, - 18.06804458822712, - 18.068044677432532, - 18.068044735867982, - 18.06804480245637, - 18.068044910045945, - 18.068044994766165, - 18.068044076414775, - 18.068044001334393, - 18.068043916795133, - 18.068043830401233, - 18.06804371720048, - 18.068043607263267, - 18.068043490017033, - 18.068043361704834, - 18.068043211763367, - 18.068043065806403, - 18.068044190032012, - 18.068044232584143, - 18.06804428607588, - 18.068044342356433, - 18.068044180313112, - 18.068044170313513, - 18.068044170188987, - 18.068044170177046, - 18.068044170173962, - 18.068044170173334, - 18.06804425436381, - 18.068044254365162, - 18.068044254365127, - 18.06804435180146, - 18.068044651017583, - 18.06804519095303, - 18.068045699559402, - 18.06804636362203, - 18.068046884421904, - 18.06804741971073, - 18.068044379654488, - 18.068044461788727, - 18.068044487931914, - 18.068044496179755, - 18.068044497337794, - 18.068044498525264, - 18.068044498906016, - 18.068044498899386, - 18.06804449896336, - 18.068044498966252, - 18.0680463932585, - 18.068046393282504, - 18.068046393276344, - 18.068046393279168, - 18.068046393277776, - 18.06804639327785, - 18.068046393277847, - 18.068046393277857, - 18.068046530797165, - 18.068046911038774, - 18.068046692263998, - 18.06804717935538, - 18.068047603267143, - 18.06804808059392, - 18.068048487066065, - 18.068048946454184, - 18.068049353879786, - 18.06804973059318, - 18.06805020580577, - 18.06805057046187, - 18.06804731031794, - 18.068047425363993, - 18.068047476141718, - 18.06804749285017, - 18.06804749696182, - 18.068047499013833, - 18.068047499709248, - 18.06804749978838, - 18.068047499874343, - 18.0680474998722, - 18.06804858851682, - 18.068048899232192, - 18.068049203769572, - 18.068049565925776, - 18.06804977742912, - 18.06804982902291, - 18.068049962998014, - 18.06805022649512, - 18.068050578273677, - 18.068050700559684, - 18.0680486757371, - 18.068048693014543, - 18.068048849229, - 18.06804919071698, - 18.06804937999841, - 18.068049466745517, - 18.068049495596654, - 18.068049503906515, - 18.068049507305453, - 18.068049702276383, - 18.068049447773202, - 18.068050228579665, - 18.068050911800327, - 18.068051141139087, - 18.06805122653528, - 18.06805125447385, - 18.068051262865232, - 18.068051265346238, - 18.068051266170777, - 18.068051347422465, - 18.06804960546435, - 18.068050061797905, - 18.06805070069659, - 18.06805148765542, - 18.068052321461064, - 18.068053158187347, - 18.0680539957559, - 18.068054686505256, - 18.068054973934355, - 18.0680551074447, - 18.06805012435196, - 18.068050742631684, - 18.068051532442034, - 18.068052183357107, - 18.06805300556322, - 18.068053650587103, - 18.068054379483435, - 18.068055117081993, - 18.068055832037963, - 18.06805655800351, - 18.068055179590065, - 18.06805597130505, - 18.068056764641415, - 18.068057555070542, - 18.068058343702333, - 18.068059194307722, - 18.068059908799373, - 18.068060747935892, - 18.068061456536288, - 18.06805860836428, - 18.068059355525076, - 18.068060092929684, - 18.068060835010574, - 18.068061574115987, - 18.068062313817887, - 18.06806305331513, - 18.068063790619764, - 18.068064532900603, - 18.068065273771126, - 18.068066024722356, - 18.068062486685513, - 18.068063216571232, - 18.06806394429477, - 18.068064692184652, - 18.068065399327317, - 18.06806612716666, - 18.06806667885379, - 18.06806689048227, - 18.06806696077664, - 18.068066982675585, - 18.068064884955323, - 18.068064887863972, - 18.068064888566862, - 18.068064888834776, - 18.068064888899205, - 18.06806488891288, - 18.06806488891911, - 18.06806492228206, - 18.06806520900503, - 18.0680656462445, - 18.068067088541, - 18.068067688754773, - 18.068068368793938, - 18.06806907196335, - 18.068069774212148, - 18.068070471507873, - 18.068071167444902, - 18.06807186138991, - 18.068072562046503, - 18.068073240561972, - 18.068067040203722, - 18.068067733744876, - 18.068068420300527, - 18.068069109178303, - 18.068069845912547, - 18.068070491600064, - 18.068071252398514, - 18.06807189523664, - 18.06807263014523, - 18.068073313809606, - 18.068070374639095, - 18.06807105978413, - 18.06807188134906, - 18.06807252718845, - 18.068073278608267, - 18.06807405153765, - 18.06807487452078, - 18.0680758094319, - 18.068076778837078, - 18.068077764241167, - 18.06807310470392, - 18.068074096434554, - 18.0680750827815, - 18.068076136083114, - 18.068077054098662, - 18.068078037100083, - 18.068079014257876, - 18.06807998488901, - 18.06808094488517, - 18.06808190291682, - 18.06807569783922, - 18.06807659163512, - 18.068077516487584, - 18.06807832432996, - 18.068079164442093, - 18.068079977093777, - 18.068080768272793, - 18.068081528861793, - 18.06808226045889, - 18.068078880315152, - 18.068079576647875, - 18.068080280437123, - 18.06808096046572, - 18.068081609427427, - 18.068082221767956, - 18.068082802237374, - 18.06808337079745, - 18.068083892008346, - 18.06808442378937, - 18.068081829616297, - 18.06808238779722, - 18.068082829627368, - 18.068083324164323, - 18.068083688190818, - 18.06808406902386, - 18.068084404438583, - 18.06808470759826, - 18.06808498705045, - 18.06808521877751, - 18.06808541561446, - 18.068083832490895, - 18.06808398934757, - 18.068084108202598, - 18.068084176405314, - 18.06808420770965, - 18.06808421403432, - 18.068084184368004, - 18.068084129164113, - 18.06808405447041, - 18.0680839469454, - 18.0680895553547, - 18.068090117971472, - 18.068090660854512, - 18.068091161002513, - 18.06809163733856, - 18.068092070393654, - 18.068092500891186, - 18.06809286211202, - 18.068093203845482, - 18.068082547046025, - 18.068082533577062, - 18.068082482862774, - 18.068082386620596, - 18.068082238088493, - 18.068082065972515, - 18.068081866123794, - 18.06808162838559, - 18.068081346025515, - 18.068081026185148, - 18.06807945255899, - 18.06807884322642, - 18.068078194037188, - 18.068077445268184, - 18.06807685923018, - 18.068076085359223, - 18.068075489882293, - 18.068074718097236, - 18.06807410633173, - 18.068073353894256, - 18.068075042682256, - 18.068074227119116, - 18.068073441243016, - 18.06807273254761, - 18.06807184414594, - 18.06807117434116, - 18.068070312212456, - 18.06806955544296, - 18.068068729350312, - 18.068067960461537, - 18.068067185220308, - 18.06807136760974, - 18.06807051045569, - 18.068069669786972, - 18.06806892440256, - 18.068067965046755, - 18.068067240891875, - 18.06806639656642, - 18.068065541244636, - 18.0680647260125, - 18.068067161537442, - 18.068066309080205, - 18.068065455509018, - 18.068064594664143, - 18.06806372713506, - 18.06806284530087, - 18.068061954036246, - 18.06806101558981, - 18.068060104740276, - 18.06805915093841, - 18.068058190647037, - 18.068063956754916, - 18.068062953064814, - 18.06806194183457, - 18.068060937173897, - 18.068059923387548, - 18.06805884060054, - 18.068057897265504, - 18.068056809188974, - 18.068055875508175, - 18.06805968644596, - 18.068058692398736, - 18.068057697831165, - 18.06805662613639, - 18.068055750975407, - 18.068054692394306, - 18.06805385714054, - 18.068052801297732, - 18.06805201790378, - 18.068051034402632, - 18.068057139428124, - 18.06805635183646, - 18.06805575420205, - 18.068055129674175, - 18.06805475310267, - 18.068054616929025, - 18.06805457408982, - 18.06805455865628, - 18.06805455568191, - 18.068054553391526, - 18.068054369685626, - 18.068054369529168, - 18.068054369416608, - 18.06805436941225, - 18.068054369400098, - 18.06805434592176, - 18.06805412640177, - 18.068053672734628, - 18.06805327034051, - 18.068052766932226, - 18.068053271531582, - 18.068052619077466, - 18.06805199783137, - 18.068051378032894, - 18.068050785178098, - 18.068050235099854, - 18.068049715459118, - 18.068049243810602, - 18.068048841660165, - 18.06804847897015, - 18.068051358042002, - 18.06805102690322, - 18.068050736507438, - 18.068050554153718, - 18.06805039641038, - 18.06805029658236, - 18.06805025284264, - 18.06805028338577, - 18.06805036299542, - 18.06805049497995, - 18.06805067938137, - 18.06804819851349, - 18.068048270384484, - 18.068048399049285, - 18.068048553431314, - 18.06804875437379, - 18.068049011435555, - 18.068049260934785, - 18.068049595803007, - 18.068049917961325, - 18.068050364162882, - 18.06805261039489, - 18.06805341706755, - 18.068054075691684, - 18.068054921067468, - 18.068055639145832, - 18.068056513335915, - 18.068057268901132, - 18.06805811021954, - 18.068058965431746, - 18.068054637122152, - 18.068055579259134, - 18.068056433152687, - 18.068057421412867, - 18.068058296394415, - 18.068059357423312, - 18.06806020084976, - 18.068061302098144, - 18.068062140465745, - 18.068063071452002, - 18.068058263918783, - 18.06805841705041, - 18.068058470353726, - 18.068058485653548, - 18.06805849078667, - 18.068058492134373, - 18.068058492551472, - 18.068058492694536, - 18.068058492713604, - 18.068058492731375, - 18.068058492733098, - 18.06806130898071, - 18.068061309013746, - 18.06806130900965, - 18.068061309004314, - 18.068061309000864, - 18.06806130900019, - 18.06806130899982, - 18.068061308999752, - 18.06806130899972, - 18.068060647738147, - 18.068060647704616, - 18.06806064770419, - 18.06806064770658, - 18.068060647709334, - 18.06806064770854, - 18.068060647708652, - 18.06806064770872, - 18.068060647708727, - 18.068060647708737, - 18.06806064731873, - 18.0680606473187, - 18.0680606473187, - 18.068060647318696, - 18.0680606473187, - 18.0680606473187, - 18.0680606473187, - 18.0680606473187, - 18.0680606473187, - 18.0680606473187, - 18.068060547349212, - 18.068060547339705, - 18.0680605473393, - 18.068060547339172, - 18.068060547339613, - 18.06806054733956, - 18.068060547339606, - 18.068060547339595, - 18.0680605473396, - 18.0680605473396 - ], - "marker": { - "size": 10 - }, - "mode": "markers", - "type": "scattermapbox" - }, - { - "lat": [ - 59.35089426416136, - 59.35089481178939, - 59.35089483355297, - 59.350894857744606, - 59.35089488604177, - 59.35089491808581, - 59.35089494709089, - 59.350894990631645, - 59.35089502438268, - 59.350895077367376, - 59.35089511663734, - 59.35089489941767, - 59.350894915125295, - 59.35089492254493, - 59.35089493043813, - 59.35089494733787, - 59.35089495735938, - 59.3508949704765, - 59.35089498131451, - 59.35089499210641, - 59.35089500422632, - 59.350895015966955, - 59.350894884148445, - 59.35089487277662, - 59.35089486170763, - 59.35089484847376, - 59.35089483387418, - 59.35089481861798, - 59.350894803809354, - 59.35089478153899, - 59.35089476101665, - 59.35089477698152, - 59.350894758875285, - 59.350894740395816, - 59.35089472108076, - 59.350894708044535, - 59.35089468134352, - 59.35089465931041, - 59.35089464092461, - 59.35089461227294, - 59.350894588277754, - 59.35089491297137, - 59.35089494521897, - 59.35089497743465, - 59.35089501944495, - 59.35089505989556, - 59.35089510405016, - 59.35089513895837, - 59.35089520754802, - 59.35089526482648, - 59.350894967406774, - 59.35089489132773, - 59.350894891329744, - 59.35089489972674, - 59.350895008355124, - 59.35089518545526, - 59.35089542517829, - 59.35089570256227, - 59.35089603161906, - 59.35089638116867, - 59.350896736108524, - 59.35089514953104, - 59.350895502958416, - 59.35089584844485, - 59.350896192073265, - 59.35089653467157, - 59.350896881363454, - 59.35089721878933, - 59.35089755974104, - 59.350897900344194, - 59.35089824179036, - 59.35089503033628, - 59.3508953069802, - 59.350895585751914, - 59.35089585888737, - 59.350896129029785, - 59.350896403690335, - 59.350896676924364, - 59.350896958245634, - 59.35089723249662, - 59.350897500780775, - 59.35089777407419, - 59.35089458744109, - 59.350894751747155, - 59.35089491696863, - 59.35089508408747, - 59.35089524820105, - 59.350895412350056, - 59.350895576760884, - 59.350895739803875, - 59.350895902112015, - 59.35089418580134, - 59.3508942542131, - 59.3508943115218, - 59.35089435546547, - 59.350894382713655, - 59.350894403805924, - 59.350894415825465, - 59.3508944128607, - 59.35089439470288, - 59.350894367513, - 59.350893305616495, - 59.35089317512329, - 59.350893029043434, - 59.35089286712533, - 59.35089266813452, - 59.350892432024494, - 59.35089215828093, - 59.350891872544665, - 59.35089157855295, - 59.35089127651043, - 59.35089235483179, - 59.35089201092318, - 59.3508916665259, - 59.350891320831934, - 59.350890972804294, - 59.35089062073128, - 59.350890270602804, - 59.350889915969276, - 59.350889560281495, - 59.35088920176892, - 59.35089044217648, - 59.35089004501909, - 59.35088964993529, - 59.35088925269734, - 59.35088885304779, - 59.350888439943404, - 59.3508880163734, - 59.35088757453939, - 59.35088713069728, - 59.35088666676289, - 59.35088796677862, - 59.350887488240176, - 59.35088699890433, - 59.35088650261533, - 59.35088600401848, - 59.35088549894629, - 59.35088497691321, - 59.350884473028906, - 59.35088394295721, - 59.350883445573565, - 59.35088525635668, - 59.35088474374119, - 59.3508842140822, - 59.3508836854307, - 59.350883133996454, - 59.350882593316136, - 59.3508820192221, - 59.35088146394614, - 59.350880884986, - 59.35088030657597, - 59.35088251960579, - 59.35088194801503, - 59.3508813587174, - 59.35088076848102, - 59.35088017883154, - 59.35087958740493, - 59.350878994810785, - 59.35087839651149, - 59.35087779111474, - 59.350877175295196, - 59.35087952708666, - 59.3508788852045, - 59.35087825041093, - 59.350877607432274, - 59.35087696625533, - 59.35087632613093, - 59.35087569052442, - 59.35087505388759, - 59.35087442444979, - 59.35087379194317, - 59.35087634298634, - 59.3508757028188, - 59.3508750647851, - 59.3508744301612, - 59.350873785677656, - 59.350873171351765, - 59.35087254266169, - 59.35087193963725, - 59.35087132224504, - 59.35087070615073, - 59.350873262689284, - 59.35087265044318, - 59.350872036140885, - 59.35087145388596, - 59.35087085750199, - 59.35087024392279, - 59.35086966569765, - 59.35086905551995, - 59.350868480858516, - 59.35087017121438, - 59.350869578145755, - 59.35086898869731, - 59.35086841133142, - 59.35086783383478, - 59.35086729573523, - 59.35086676894713, - 59.35086628009489, - 59.35086580479336, - 59.35086533131583, - 59.35086485682632, - 59.35086708281183, - 59.350866625313955, - 59.35086617086624, - 59.35086572502274, - 59.35086528614771, - 59.3508648548292, - 59.35086443368472, - 59.35086401790091, - 59.35086361423221, - 59.350863229141865, - 59.35086514424597, - 59.35086482680545, - 59.35086452513248, - 59.35086422911814, - 59.35086393523538, - 59.35086364197119, - 59.350863354965156, - 59.35086306872698, - 59.350862784320036, - 59.350862499280595, - 59.350863481065005, - 59.350863191990314, - 59.350862913966694, - 59.350862685991174, - 59.35086247847149, - 59.35086228668381, - 59.350862109074185, - 59.35086194750835, - 59.35086179417394, - 59.350861643643796, - 59.35086208467341, - 59.35086192253591, - 59.35086176029951, - 59.350861594215594, - 59.35086143973059, - 59.350861305998606, - 59.35086119116022, - 59.3508610981957, - 59.350861022992646, - 59.35086097750508, - 59.35086108214358, - 59.35086104414599, - 59.35086103010241, - 59.35086104477518, - 59.35086107372636, - 59.35086113019616, - 59.350861221051275, - 59.35086133856241, - 59.35086147837711, - 59.350861649857265, - 59.35086107630636, - 59.35086127661161, - 59.35086149443762, - 59.35086173778335, - 59.350862008484405, - 59.350862297780424, - 59.35086261811741, - 59.35086295943634, - 59.350863314919906, - 59.35086369067464, - 59.35086292597562, - 59.35086337877567, - 59.3508638488521, - 59.3508643600849, - 59.35086494815109, - 59.35086557751477, - 59.35086623635847, - 59.350866866474234, - 59.35086751962399, - 59.35086817685246, - 59.35086536905845, - 59.35086606606825, - 59.350866795365874, - 59.35086755663228, - 59.35086831167877, - 59.35086901406256, - 59.35086967967811, - 59.350870304904355, - 59.350870903698194, - 59.35087149833118, - 59.35086965908489, - 59.35087034518172, - 59.350871040489494, - 59.35087182312473, - 59.35087267530369, - 59.35087359535588, - 59.35087436794525, - 59.350875529964554, - 59.35087650032969, - 59.350877466293845, - 59.35087447636613, - 59.35087555557493, - 59.35087663177882, - 59.35087770932861, - 59.35087878689188, - 59.35087986533125, - 59.35088091749047, - 59.3508819624343, - 59.35088300620228, - 59.35088399398818, - 59.35088113233132, - 59.35088221115129, - 59.350883234945854, - 59.35088427681998, - 59.35088530263639, - 59.35088633711331, - 59.35088733059348, - 59.3508883502824, - 59.35088930191655, - 59.350890240752136, - 59.350888046489786, - 59.35088895919863, - 59.3508898506569, - 59.35089069391997, - 59.350891512113776, - 59.35089222678698, - 59.350892843392195, - 59.35089336396737, - 59.35089378812939, - 59.35089417689619, - 59.350893375301624, - 59.350893731605105, - 59.3508940242313, - 59.350894273074246, - 59.35089439227349, - 59.35089441718019, - 59.35089437522054, - 59.3508942570421, - 59.350894041029974, - 59.35089376116582, - 59.350894790172546, - 59.35089436234193, - 59.35089390882058, - 59.350893642666875, - 59.3508935476532, - 59.350893516780616, - 59.350893507428935, - 59.350893505101915, - 59.35089350429378, - 59.35089350413135, - 59.350893397398465, - 59.35089339735671, - 59.35089339735589, - 59.350893397354895, - 59.35089339735606, - 59.35089339735619, - 59.35089339735633, - 59.350893397356344, - 59.35089339735636, - 59.350893397356366, - 59.35089225803699, - 59.35089225802862, - 59.350892258026064, - 59.350892258027955, - 59.35089225802881, - 59.35089225802896, - 59.35089225802906, - 59.35089225802909, - 59.35089225614966, - 59.35089219698152, - 59.35089226605588, - 59.35089209534729, - 59.35089192997447, - 59.35089181108448, - 59.350891740642865, - 59.350891729770396, - 59.350891764956, - 59.3508918711664, - 59.35089203492451, - 59.35089226242424, - 59.350892985432544, - 59.35089344006977, - 59.350893963512206, - 59.3508945761891, - 59.35089529093171, - 59.350896013723286, - 59.35089680953534, - 59.350897623325295, - 59.3508985116032, - 59.350899384648, - 59.35089406818349, - 59.350894950375746, - 59.350895861697055, - 59.350896769997775, - 59.35089767282997, - 59.350898560748476, - 59.35089942485952, - 59.35090010023818, - 59.350900373504516, - 59.35090047590303, - 59.35089664278651, - 59.35089701499415, - 59.35089751258033, - 59.35089805498744, - 59.35089860980274, - 59.350899174213765, - 59.350899804238736, - 59.35090047859503, - 59.35090117050399, - 59.35090188841505, - 59.35090107876722, - 59.35090178688759, - 59.35090248482883, - 59.35090318443002, - 59.35090388357572, - 59.350904582066875, - 59.35090527384688, - 59.350905968319395, - 59.35090667159564, - 59.35090733560586, - 59.35090502767389, - 59.350905692958946, - 59.35090636131393, - 59.350907006571724, - 59.35090764791467, - 59.350908290822545, - 59.350908934318426, - 59.35090958002851, - 59.35091022693214, - 59.35091087072291, - 59.35090858421944, - 59.35090924953346, - 59.3509098831874, - 59.35091053811038, - 59.350911189587414, - 59.35091184276713, - 59.350912497117704, - 59.35091315183328, - 59.350913807960524, - 59.350914466802706, - 59.350912045344685, - 59.35091269136423, - 59.350913326609955, - 59.35091396944548, - 59.35091460872697, - 59.350915232717234, - 59.350915853391626, - 59.350916470913035, - 59.35091714682184, - 59.35091789751115, - 59.35091567279986, - 59.35091646458256, - 59.350917248496366, - 59.35091804800825, - 59.35091885597863, - 59.35091965846212, - 59.35092046890737, - 59.35092128169465, - 59.350922094162776, - 59.35092292556207, - 59.35091668811458, - 59.35091751863007, - 59.35091833648157, - 59.35091921293795, - 59.35092009875725, - 59.350921024871276, - 59.35092191801848, - 59.3509228382237, - 59.35092377946739, - 59.350924680741514, - 59.35091807635655, - 59.350918985505054, - 59.35091989458792, - 59.350920801740415, - 59.35092158575473, - 59.350921952557755, - 59.350922067124145, - 59.350922118672905, - 59.35092212913534, - 59.350922132942856, - 59.35092634028344, - 59.350926348513646, - 59.35092635066019, - 59.35092635095495, - 59.35092635099192, - 59.35092635099505, - 59.35092635099555, - 59.350926350995636, - 59.350926350995564, - 59.350926350995564, - 59.350926917884124, - 59.35092691788555, - 59.35092691788664, - 59.35092691788664, - 59.35092691788672, - 59.35092691788672, - 59.350926917886724, - 59.350926917886724, - 59.350926917886724, - 59.350926917886724, - 59.35092447730996, - 59.35092447731183, - 59.35092447731192, - 59.350924477311764, - 59.350924477311665, - 59.35092447731165, - 59.35092447731162, - 59.35092447731162, - 59.35092447731162, - 59.35092447731162, - 59.35092473299392 - ], - "lon": [ - 18.068049518147564, - 18.06804963070863, - 18.068049633812763, - 18.068049637262, - 18.068049641295524, - 18.068049645862168, - 18.068049649995068, - 18.068049656198266, - 18.06804966100617, - 18.06804966855319, - 18.068049674146224, - 18.06804962743101, - 18.068049625749588, - 18.06804962481957, - 18.068049623736364, - 18.068049621098265, - 18.068049619332797, - 18.068049616801087, - 18.068049614524035, - 18.068049612093443, - 18.068049609173276, - 18.068049606156045, - 18.06804962856267, - 18.06804962912369, - 18.0680496296726, - 18.068049630331334, - 18.06804963106027, - 18.068049631823833, - 18.068049632566375, - 18.068049633685064, - 18.068049634717617, - 18.06804962801919, - 18.06804962782654, - 18.068049627607817, - 18.068049627359052, - 18.068049627181033, - 18.068049626794387, - 18.068049626455934, - 18.068049626161823, - 18.06804962568487, - 18.06804962527, - 18.068049628194217, - 18.068049628273215, - 18.068049628355862, - 18.068049628467772, - 18.0680496285789, - 18.068049628703143, - 18.06804962880313, - 18.068049629003255, - 18.068049629173405, - 18.068049641853293, - 18.068049728166635, - 18.068049728165107, - 18.068049741309785, - 18.0680499122098, - 18.068050191054375, - 18.068050569531643, - 18.06805100925277, - 18.06805153418553, - 18.068052096752616, - 18.06805267024514, - 18.06805006868354, - 18.06805063500242, - 18.068051192132053, - 18.06805174929395, - 18.0680523078585, - 18.06805287336548, - 18.0680534231743, - 18.06805398268156, - 18.06805454085978, - 18.068055102776803, - 18.068052557524133, - 18.068053239330823, - 18.06805393100986, - 18.068054613823392, - 18.068055286612047, - 18.068055969330175, - 18.06805664910021, - 18.068057350262826, - 18.0680580337412, - 18.068058700810138, - 18.06805938120101, - 18.068056947886458, - 18.068057757034506, - 18.068058567798964, - 18.068059385332603, - 18.06806018995783, - 18.068060995457024, - 18.068061809472802, - 18.068062616955316, - 18.0680634329896, - 18.06806081422862, - 18.068061684112088, - 18.068062561732496, - 18.06806344584744, - 18.068064331176362, - 18.068065219490684, - 18.06806611784048, - 18.068066996183553, - 18.0680678883311, - 18.068068799721658, - 18.068064779063892, - 18.068065674116454, - 18.068066582889422, - 18.06806747426862, - 18.06806845719929, - 18.068069527590154, - 18.068070594650028, - 18.068071658969476, - 18.068072716817703, - 18.068073795528807, - 18.068067049766988, - 18.068068072069366, - 18.068069093978774, - 18.068070112165373, - 18.06807113021368, - 18.068072155381145, - 18.068073173504136, - 18.068074201564624, - 18.068075229326194, - 18.0680762609174, - 18.06807095276072, - 18.068071938350023, - 18.06807291671985, - 18.068073894814418, - 18.068074867687816, - 18.068075815711797, - 18.06807674637033, - 18.068077662063654, - 18.068078550557647, - 18.06807944428213, - 18.068076216192676, - 18.068077044829515, - 18.068077852050905, - 18.068078631592886, - 18.068079377531998, - 18.068080082111795, - 18.068080797565294, - 18.068081483160526, - 18.06808220739541, - 18.06808288814042, - 18.068080606508893, - 18.06808131344281, - 18.068081985288423, - 18.068082616016238, - 18.068083247507477, - 18.068083829633977, - 18.068084391162344, - 18.068084875028994, - 18.068085353964648, - 18.068085829223715, - 18.06808350471461, - 18.068083970181675, - 18.068084454833112, - 18.068084953043797, - 18.06808545400141, - 18.068085949714963, - 18.068086440072094, - 18.068086905745837, - 18.0680873202459, - 18.068087690782843, - 18.0680851429695, - 18.06808533571179, - 18.068085432808367, - 18.068085463500204, - 18.068085375016466, - 18.068085209980715, - 18.068085016082758, - 18.068084801842193, - 18.068084586663964, - 18.068084365153616, - 18.06808591416657, - 18.068085762768835, - 18.06808560367622, - 18.068085371816554, - 18.068085089767564, - 18.068084767139826, - 18.06808437828608, - 18.06808399226634, - 18.068083592490726, - 18.068083188311128, - 18.068084483898055, - 18.068084035253992, - 18.0680835700379, - 18.068083112721926, - 18.06808262636212, - 18.06808211802703, - 18.06808163956806, - 18.068081132628926, - 18.068080654051318, - 18.068082216060972, - 18.06808171884319, - 18.06808119259998, - 18.068080628510224, - 18.068080005462647, - 18.068079353395493, - 18.068078577434324, - 18.068077779591547, - 18.068076919598248, - 18.068076049309276, - 18.068075176393496, - 18.068078092014034, - 18.0680771890307, - 18.068076284677723, - 18.068075378237335, - 18.06807445581157, - 18.0680735152575, - 18.068072557338137, - 18.068071584848767, - 18.068070597031355, - 18.06806957763271, - 18.06807296326592, - 18.068071860907356, - 18.0680707352291, - 18.068069607855477, - 18.068068483669332, - 18.068067350026134, - 18.068066214961508, - 18.06806508219124, - 18.06806395313946, - 18.06806281952632, - 18.068067048444615, - 18.068065914389976, - 18.068064766533233, - 18.068063579760178, - 18.06806238430564, - 18.06806118096309, - 18.06805996485777, - 18.068058740395774, - 18.068057510113405, - 18.068056273857827, - 18.068060346524152, - 18.068059108810104, - 18.06805787263127, - 18.068056633551407, - 18.06805539071792, - 18.068054132423068, - 18.068052871457557, - 18.06805160197853, - 18.068050331020654, - 18.068049046299137, - 18.06805301916355, - 18.06805173201424, - 18.068050445696795, - 18.06804916179264, - 18.068047879392342, - 18.068046598968703, - 18.068045326955104, - 18.068044060356605, - 18.068042797477236, - 18.068041558628295, - 18.068045920449734, - 18.06804468956814, - 18.06804348884778, - 18.06804229640144, - 18.068041127220226, - 18.068039975153305, - 18.068038851672988, - 18.06803773459053, - 18.0680366790928, - 18.068035624293167, - 18.068040156818956, - 18.068039224905103, - 18.06803832371821, - 18.068037463175454, - 18.06803655552242, - 18.06803559913361, - 18.068034587472297, - 18.068033617951127, - 18.068032642992097, - 18.06803166856465, - 18.068036871518384, - 18.06803604589762, - 18.068035309083616, - 18.068035670111495, - 18.068036341922788, - 18.068037144960996, - 18.06803808702539, - 18.068039110113236, - 18.068040188024256, - 18.068041272077238, - 18.06803546206438, - 18.06803631344967, - 18.06803718342059, - 18.068038170750622, - 18.068039237665314, - 18.068040395538766, - 18.068041374520895, - 18.068042873152248, - 18.06804411772229, - 18.068045362785263, - 18.06803552264646, - 18.068036297431057, - 18.068037083405105, - 18.068037841918862, - 18.06803861604375, - 18.068039417114935, - 18.068040293226066, - 18.06804123742242, - 18.06804228256841, - 18.06804332227195, - 18.068035598654195, - 18.06803648330845, - 18.068037377805805, - 18.068038353228044, - 18.06803936822306, - 18.0680404317656, - 18.06804152448428, - 18.068042696775507, - 18.068043896858185, - 18.068045206043625, - 18.068039924284893, - 18.06804124178577, - 18.068042664684278, - 18.068044215361528, - 18.068045886661597, - 18.068047600550894, - 18.068049508925082, - 18.068051536674787, - 18.06805364821081, - 18.068055775993138, - 18.06804875954991, - 18.06805097133403, - 18.06805310762357, - 18.068055316257624, - 18.068057563253976, - 18.068059827479875, - 18.068062089648087, - 18.068064346322515, - 18.068066567299553, - 18.068068772597204, - 18.068060410854805, - 18.06806250991521, - 18.068064526006587, - 18.068065653547052, - 18.068066047057126, - 18.06806617311883, - 18.06806621113169, - 18.068066220684884, - 18.068066223993476, - 18.068066224656807, - 18.068070833554177, - 18.06807083380154, - 18.06807083381015, - 18.068070833815117, - 18.068070833808722, - 18.068070833807855, - 18.068070833807113, - 18.068070833806978, - 18.06807083380689, - 18.06807083380686, - 18.06807425036253, - 18.06807425040148, - 18.068074250416636, - 18.06807425040528, - 18.068074250400763, - 18.06807425039983, - 18.068074250399125, - 18.068074250399032, - 18.06807426143433, - 18.068074608525535, - 18.06807484802861, - 18.068075991571156, - 18.068077359620546, - 18.06807884528855, - 18.06808033067369, - 18.06808188966564, - 18.068083359348268, - 18.068084859189273, - 18.068086335804146, - 18.068087783079957, - 18.068075795004155, - 18.06807701676326, - 18.068078275867574, - 18.06807948577034, - 18.068080637712796, - 18.068081626858007, - 18.06808251762444, - 18.068083285989253, - 18.068083851413483, - 18.068084169692725, - 18.068080817757913, - 18.068080963361204, - 18.06808100365729, - 18.068080933007785, - 18.06808071877441, - 18.068080345632943, - 18.068079846558486, - 18.068079376370545, - 18.06807917297917, - 18.068079096674243, - 18.068085795428026, - 18.068085787024664, - 18.06808580386101, - 18.06808586725765, - 18.068085967656092, - 18.06808607681462, - 18.0680862045123, - 18.068086343856, - 18.068086476924602, - 18.068086581471565, - 18.068085915030448, - 18.068085917464472, - 18.068085871034302, - 18.06808577262936, - 18.06808562165416, - 18.068085451267567, - 18.068085247109508, - 18.06808499526458, - 18.06808470086693, - 18.068084371392068, - 18.06808624411338, - 18.068085901148685, - 18.068085507388325, - 18.068085075746474, - 18.068084614429516, - 18.068084160903837, - 18.0680837150523, - 18.06808327733901, - 18.068082837627145, - 18.068082405336426, - 18.06808422529473, - 18.068083810762673, - 18.068083420694716, - 18.06808302308487, - 18.068082637676508, - 18.06808225297017, - 18.068081870626976, - 18.068081492164655, - 18.06808112719857, - 18.06808076056516, - 18.068080751440128, - 18.06808028300427, - 18.06807982655154, - 18.068079371524156, - 18.068078892506442, - 18.06807836143864, - 18.068077781764032, - 18.06807711825425, - 18.06807630637, - 18.06807538851327, - 18.068077149003976, - 18.068076148659646, - 18.06807517345825, - 18.06807420521238, - 18.068073246241667, - 18.068072308567228, - 18.06807137876455, - 18.068070442022425, - 18.06806952762099, - 18.068068619633795, - 18.068074528508067, - 18.06807359511694, - 18.068072786356847, - 18.06807207877381, - 18.068071556688658, - 18.068071185952544, - 18.068070953223515, - 18.06807082716005, - 18.06807074009883, - 18.068070662539782, - 18.068073704289326, - 18.068073880415135, - 18.06807406020827, - 18.068074244685228, - 18.068074423443854, - 18.06807451300939, - 18.068074543632108, - 18.068074558321612, - 18.068074561317772, - 18.068074562429626, - 18.068064505230012, - 18.068064492405824, - 18.068064489061673, - 18.068064488603888, - 18.06806448854689, - 18.068064488542337, - 18.068064488541584, - 18.068064488541435, - 18.068064488541577, - 18.068064488541594, - 18.068065988544625, - 18.06806598854576, - 18.06806598854572, - 18.068065988545282, - 18.0680659885452, - 18.068065988545133, - 18.068065988545126, - 18.068065988545115, - 18.068065988545115, - 18.068065988545115, - 18.068070127564237, - 18.06807012756457, - 18.068070127564233, - 18.068070127564365, - 18.06807012756445, - 18.068070127564457, - 18.068070127564468, - 18.06807012756447, - 18.06807012756447, - 18.06807012756447, - 18.06807032891735 - ], - "marker": { - "size": 10 - }, - "mode": "markers", - "type": "scattermapbox" - }, - { - "lat": [ - 59.350791 - ], - "lon": [ - 18.067825 - ], - "marker": { - "size": 10 - }, - "mode": "markers", - "type": "scattermapbox" - } - ], - "layout": { - "mapbox": { - "center": { - "lat": 59.350791, - "lon": 18.067825 - }, - "style": "open-street-map", - "zoom": 18 - }, - "margin": { - "b": 10, - "l": 10, - "r": 10, - "t": 10 - }, - "template": { - "data": { - "bar": [ - { - "error_x": { - "color": "#2a3f5f" - }, - "error_y": { - "color": "#2a3f5f" - }, - "marker": { - "line": { - "color": "#E5ECF6", - "width": 0.5 - }, - "pattern": { - "fillmode": "overlay", - "size": 10, - "solidity": 0.2 - } - }, - "type": "bar" - } - ], - "barpolar": [ - { - "marker": { - "line": { - "color": "#E5ECF6", - "width": 0.5 - }, - "pattern": { - "fillmode": "overlay", - "size": 10, - "solidity": 0.2 - } - }, - "type": "barpolar" - } - ], - "carpet": [ - { - "aaxis": { - "endlinecolor": "#2a3f5f", - "gridcolor": "white", - "linecolor": "white", - "minorgridcolor": "white", - "startlinecolor": "#2a3f5f" - }, - "baxis": { - "endlinecolor": "#2a3f5f", - "gridcolor": "white", - "linecolor": "white", - "minorgridcolor": "white", - "startlinecolor": "#2a3f5f" - }, - "type": "carpet" - } - ], - "choropleth": [ - { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - }, - "type": "choropleth" - } - ], - "contour": [ - { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - }, - "colorscale": [ - [ - 0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1, - "#f0f921" - ] - ], - "type": "contour" - } - ], - "contourcarpet": [ - { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - }, - "type": "contourcarpet" - } - ], - "heatmap": [ - { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - }, - "colorscale": [ - [ - 0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1, - "#f0f921" - ] - ], - "type": "heatmap" - } - ], - "heatmapgl": [ - { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - }, - "colorscale": [ - [ - 0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1, - "#f0f921" - ] - ], - "type": "heatmapgl" - } - ], - "histogram": [ - { - "marker": { - "pattern": { - "fillmode": "overlay", - "size": 10, - "solidity": 0.2 - } - }, - "type": "histogram" - } - ], - "histogram2d": [ - { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - }, - "colorscale": [ - [ - 0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1, - "#f0f921" - ] - ], - "type": "histogram2d" - } - ], - "histogram2dcontour": [ - { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - }, - "colorscale": [ - [ - 0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1, - "#f0f921" - ] - ], - "type": "histogram2dcontour" - } - ], - "mesh3d": [ - { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - }, - "type": "mesh3d" - } - ], - "parcoords": [ - { - "line": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - }, - "type": "parcoords" - } - ], - "pie": [ - { - "automargin": true, - "type": "pie" - } - ], - "scatter": [ - { - "fillpattern": { - "fillmode": "overlay", - "size": 10, - "solidity": 0.2 - }, - "type": "scatter" - } - ], - "scatter3d": [ - { - "line": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - }, - "marker": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - }, - "type": "scatter3d" - } - ], - "scattercarpet": [ - { - "marker": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - }, - "type": "scattercarpet" - } - ], - "scattergeo": [ - { - "marker": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - }, - "type": "scattergeo" - } - ], - "scattergl": [ - { - "marker": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - }, - "type": "scattergl" - } - ], - "scattermapbox": [ - { - "marker": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - }, - "type": "scattermapbox" - } - ], - "scatterpolar": [ - { - "marker": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - }, - "type": "scatterpolar" - } - ], - "scatterpolargl": [ - { - "marker": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - }, - "type": "scatterpolargl" - } - ], - "scatterternary": [ - { - "marker": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - }, - "type": "scatterternary" - } - ], - "surface": [ - { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - }, - "colorscale": [ - [ - 0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1, - "#f0f921" - ] - ], - "type": "surface" - } - ], - "table": [ - { - "cells": { - "fill": { - "color": "#EBF0F8" - }, - "line": { - "color": "white" - } - }, - "header": { - "fill": { - "color": "#C8D4E3" - }, - "line": { - "color": "white" - } - }, - "type": "table" - } - ] - }, - "layout": { - "annotationdefaults": { - "arrowcolor": "#2a3f5f", - "arrowhead": 0, - "arrowwidth": 1 - }, - "autotypenumbers": "strict", - "coloraxis": { - "colorbar": { - "outlinewidth": 0, - "ticks": "" - } - }, - "colorscale": { - "diverging": [ - [ - 0, - "#8e0152" - ], - [ - 0.1, - "#c51b7d" - ], - [ - 0.2, - "#de77ae" - ], - [ - 0.3, - "#f1b6da" - ], - [ - 0.4, - "#fde0ef" - ], - [ - 0.5, - "#f7f7f7" - ], - [ - 0.6, - "#e6f5d0" - ], - [ - 0.7, - "#b8e186" - ], - [ - 0.8, - "#7fbc41" - ], - [ - 0.9, - "#4d9221" - ], - [ - 1, - "#276419" - ] - ], - "sequential": [ - [ - 0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1, - "#f0f921" - ] - ], - "sequentialminus": [ - [ - 0, - "#0d0887" - ], - [ - 0.1111111111111111, - "#46039f" - ], - [ - 0.2222222222222222, - "#7201a8" - ], - [ - 0.3333333333333333, - "#9c179e" - ], - [ - 0.4444444444444444, - "#bd3786" - ], - [ - 0.5555555555555556, - "#d8576b" - ], - [ - 0.6666666666666666, - "#ed7953" - ], - [ - 0.7777777777777778, - "#fb9f3a" - ], - [ - 0.8888888888888888, - "#fdca26" - ], - [ - 1, - "#f0f921" - ] - ] - }, - "colorway": [ - "#636efa", - "#EF553B", - "#00cc96", - "#ab63fa", - "#FFA15A", - "#19d3f3", - "#FF6692", - "#B6E880", - "#FF97FF", - "#FECB52" - ], - "font": { - "color": "#2a3f5f" - }, - "geo": { - "bgcolor": "white", - "lakecolor": "white", - "landcolor": "#E5ECF6", - "showlakes": true, - "showland": true, - "subunitcolor": "white" - }, - "hoverlabel": { - "align": "left" - }, - "hovermode": "closest", - "mapbox": { - "style": "light" - }, - "paper_bgcolor": "white", - "plot_bgcolor": "#E5ECF6", - "polar": { - "angularaxis": { - "gridcolor": "white", - "linecolor": "white", - "ticks": "" - }, - "bgcolor": "#E5ECF6", - "radialaxis": { - "gridcolor": "white", - "linecolor": "white", - "ticks": "" - } - }, - "scene": { - "xaxis": { - "backgroundcolor": "#E5ECF6", - "gridcolor": "white", - "gridwidth": 2, - "linecolor": "white", - "showbackground": true, - "ticks": "", - "zerolinecolor": "white" - }, - "yaxis": { - "backgroundcolor": "#E5ECF6", - "gridcolor": "white", - "gridwidth": 2, - "linecolor": "white", - "showbackground": true, - "ticks": "", - "zerolinecolor": "white" - }, - "zaxis": { - "backgroundcolor": "#E5ECF6", - "gridcolor": "white", - "gridwidth": 2, - "linecolor": "white", - "showbackground": true, - "ticks": "", - "zerolinecolor": "white" - } - }, - "shapedefaults": { - "line": { - "color": "#2a3f5f" - } - }, - "ternary": { - "aaxis": { - "gridcolor": "white", - "linecolor": "white", - "ticks": "" - }, - "baxis": { - "gridcolor": "white", - "linecolor": "white", - "ticks": "" - }, - "bgcolor": "#E5ECF6", - "caxis": { - "gridcolor": "white", - "linecolor": "white", - "ticks": "" - } - }, - "title": { - "x": 0.05 - }, - "xaxis": { - "automargin": true, - "gridcolor": "white", - "linecolor": "white", - "ticks": "", - "title": { - "standoff": 15 - }, - "zerolinecolor": "white", - "zerolinewidth": 2 - }, - "yaxis": { - "automargin": true, - "gridcolor": "white", - "linecolor": "white", - "ticks": "", - "title": { - "standoff": 15 - }, - "zerolinecolor": "white", - "zerolinewidth": 2 - } - } - } - } - }, - "text/html": [ - "
\n", - "
" - ], - "text/plain": [ - "Figure({\n", - " 'data': [{'lat': [59.35093418921517, 59.35093398436031, 59.350933935363415,\n", - " ..., 59.35092965639449, 59.35092965639449, 59.35092965639449],\n", - " 'lon': [18.068044270978096, 18.068044399069947, 18.068044429706774,\n", - " ..., 18.068060547339595, 18.0680605473396, 18.0680605473396],\n", - " 'marker': {'size': 10},\n", - " 'mode': 'markers',\n", - " 'type': 'scattermapbox'},\n", - " {'lat': [59.35089426416136, 59.35089481178939, 59.35089483355297,\n", - " ..., 59.35092447731162, 59.35092447731162, 59.35092473299392],\n", - " 'lon': [18.068049518147564, 18.06804963070863, 18.068049633812763,\n", - " ..., 18.06807012756447, 18.06807012756447, 18.06807032891735],\n", - " 'marker': {'size': 10},\n", - " 'mode': 'markers',\n", - " 'type': 'scattermapbox'},\n", - " {'lat': [59.350791], 'lon': [18.067825], 'marker': {'size': 10}, 'mode': 'markers', 'type': 'scattermapbox'}],\n", - " 'layout': {'mapbox': {'center': {'lat': 59.350791, 'lon': 18.067825}, 'style': 'open-street-map', 'zoom': 18},\n", - " 'margin': {'b': 10, 'l': 10, 'r': 10, 't': 10},\n", - " 'template': '...'}\n", - "})" - ] - }, - "execution_count": 6, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "import plotly.graph_objects as go\n", - "fig = go.Figure(go.Scattermapbox(\n", - " mode = \"markers\",\n", - " lon = Long1,\n", - " lat = Lat1,\n", - " marker = {'size': 10}))\n", - "fig.add_trace(go.Scattermapbox(\n", - " mode = \"markers\",\n", - " lon = Long2,\n", - " lat = Lat2,\n", - " marker = {'size': 10}))\n", - "fig.add_trace(go.Scattermapbox(\n", - " mode = \"markers\",\n", - " lon = [18.067825],\n", - " lat = [59.350791],\n", - " marker = {'size': 10}))\n", - "fig.update_layout(\n", - " margin ={'l':10,'t':10,'b':10,'r':10},\n", - " mapbox = {\n", - " 'center': {'lon': 18.067825, 'lat': 59.350791},\n", - " 'style': \"open-street-map\",\n", - " 'zoom': 18\n", - " })" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.8.10" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} From 71924a9082748c1c48a52466a2e49373c8d37f88 Mon Sep 17 00:00:00 2001 From: Annika-wyt Date: Tue, 30 Jan 2024 10:30:59 +0100 Subject: [PATCH 08/10] cleanup repo for pr --- .gitignore | 3 +-- src/svea_sensors/launch/localize.launch | 2 +- src/svea_sensors/launch/sensors_launch/rtk.launch | 8 ++------ .../params/robot_localization/global_ekf.yaml | 2 +- 4 files changed, 5 insertions(+), 10 deletions(-) diff --git a/.gitignore b/.gitignore index bbe812a6..946666c3 100644 --- a/.gitignore +++ b/.gitignore @@ -12,5 +12,4 @@ __pycache__/ src/.vscode/ venv/ -site/ -rosbag/ \ No newline at end of file +site/ \ No newline at end of file diff --git a/src/svea_sensors/launch/localize.launch b/src/svea_sensors/launch/localize.launch index f58971df..e5d34a73 100644 --- a/src/svea_sensors/launch/localize.launch +++ b/src/svea_sensors/launch/localize.launch @@ -89,7 +89,7 @@ - + diff --git a/src/svea_sensors/launch/sensors_launch/rtk.launch b/src/svea_sensors/launch/sensors_launch/rtk.launch index 8836f0a6..9fb8cdfd 100644 --- a/src/svea_sensors/launch/sensors_launch/rtk.launch +++ b/src/svea_sensors/launch/sensors_launch/rtk.launch @@ -16,12 +16,8 @@ - - - - - - + + diff --git a/src/svea_sensors/params/robot_localization/global_ekf.yaml b/src/svea_sensors/params/robot_localization/global_ekf.yaml index 983a829e..ad412183 100644 --- a/src/svea_sensors/params/robot_localization/global_ekf.yaml +++ b/src/svea_sensors/params/robot_localization/global_ekf.yaml @@ -48,7 +48,7 @@ odom0_queue_size: 8 odom0_nodelay: true odom0_relative: false odom0_differential: false -odom0_pose_rejection_threshold: 200 +odom0_pose_rejection_threshold: 5 ########################################## # BNO055 IMU ############################# From 08fb210fb206c5420fad3f6b846958e5b8b8a466 Mon Sep 17 00:00:00 2001 From: Annika-wyt Date: Tue, 30 Jan 2024 10:31:49 +0100 Subject: [PATCH 09/10] cleanup --- src/svea_sensors/launch/sensors_launch/rtk.launch | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/svea_sensors/launch/sensors_launch/rtk.launch b/src/svea_sensors/launch/sensors_launch/rtk.launch index 9fb8cdfd..3e47fc93 100644 --- a/src/svea_sensors/launch/sensors_launch/rtk.launch +++ b/src/svea_sensors/launch/sensors_launch/rtk.launch @@ -18,8 +18,6 @@ - - From 6f6e506a76b11c94fd43c7d1a895cda50b221e24 Mon Sep 17 00:00:00 2001 From: Annika-wyt Date: Tue, 30 Jan 2024 10:32:59 +0100 Subject: [PATCH 10/10] cleanup --- src/svea_sensors/launch/localize.launch | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/src/svea_sensors/launch/localize.launch b/src/svea_sensors/launch/localize.launch index e5d34a73..5888d2a0 100644 --- a/src/svea_sensors/launch/localize.launch +++ b/src/svea_sensors/launch/localize.launch @@ -160,14 +160,4 @@ - - - - reference_gps: [59.350791, 18.067825] - - - - - -