├── .gitignore ├── img └── example.png ├── .gitmodules ├── include ├── plot.h ├── ukf.h ├── ekf.h ├── state.h ├── filter.h ├── obj.h ├── Tracker.h └── Tracking.h ├── src ├── state.cpp ├── filter.cpp ├── obj.cpp ├── plot.cpp ├── Tracker.cpp ├── ekf.cpp ├── ukf.cpp └── Tracking.cpp ├── demo └── main.cpp ├── CMakeLists.txt ├── README.md ├── data ├── prova.txt ├── gt_000002.txt ├── test.txt ├── prova_pixel.txt └── test_ll.txt ├── cmake └── CompilerWarnings.cmake └── LICENSE /.gitignore: -------------------------------------------------------------------------------- 1 | *~ 2 | build 3 | *vscode* 4 | -------------------------------------------------------------------------------- /img/example.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mive93/class-tracker/HEAD/img/example.png -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- 1 | [submodule "geodetic_utils"] 2 | path = geodetic_utils 3 | url = https://github.com/ethz-asl/geodetic_utils 4 | [submodule "matplotlib-cpp"] 5 | path = matplotlib-cpp 6 | url = https://github.com/lava/matplotlib-cpp 7 | -------------------------------------------------------------------------------- /include/plot.h: -------------------------------------------------------------------------------- 1 | #ifdef USE_MATPLOTLIB 2 | 3 | #ifndef PLOT_H 4 | #define PLOT_H 5 | 6 | #include "matplotlibcpp.h" 7 | #include "ukf.h" 8 | #include "obj.h" 9 | #include 10 | 11 | void testMatplotlib(); 12 | void plotTrajectory(std::deque trajectory); 13 | void plotTruthvsPred(std::deque groudtruth, std::deque prediction); 14 | 15 | #endif /*PLOT_H*/ 16 | 17 | #endif /*USE_MATPLOTLIB*/ -------------------------------------------------------------------------------- /include/ukf.h: -------------------------------------------------------------------------------- 1 | #ifndef UKF_H 2 | #define UKF_H 3 | 4 | #include 5 | #include 6 | 7 | #include 8 | #include 9 | 10 | #include "filter.h" 11 | 12 | namespace tracking{ 13 | 14 | class UKF : public Filter 15 | { 16 | public: 17 | 18 | UKF(); 19 | UKF(const int n_states, const float dt_, const FMatrixF &Q_, const FMatrixF &R_, const state &in_state); 20 | ~UKF(); 21 | void step(const FMatrixF &H_, const Eigen::VectorXf &z); 22 | 23 | private: 24 | state stateTransition(const state &x); 25 | }; 26 | 27 | } 28 | 29 | #endif /*UKF_H*/ 30 | -------------------------------------------------------------------------------- /src/state.cpp: -------------------------------------------------------------------------------- 1 | #include "state.h" 2 | 3 | namespace tracking{ 4 | 5 | void state::print(){ 6 | std::cout << "x: " << x << "\ty: " << y << "\tyaw: " << yaw << "\tv: " << vel << "\tyaw rate: " << yawRate << std::endl; 7 | } 8 | 9 | Eigen::VectorXf StateIntoVector(const state &x, int n_states) 10 | { 11 | Eigen::VectorXf v(n_states); 12 | v(0) = x.x; 13 | v(1) = x.y; 14 | v(2) = x.yaw; 15 | v(3) = x.vel; 16 | v(4) = x.yawRate; 17 | return v; 18 | } 19 | 20 | state VectorIntoState(const Eigen::VectorXf &v) 21 | { 22 | state x(v(0), v(1), v(2), v(3), v(4)); 23 | return x; 24 | } 25 | 26 | } -------------------------------------------------------------------------------- /include/ekf.h: -------------------------------------------------------------------------------- 1 | #ifndef EKF_H 2 | #define EKF_H 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | 9 | #include 10 | 11 | #include "state.h" 12 | #include "filter.h" 13 | 14 | namespace tracking{ 15 | class EKF : public Filter 16 | { 17 | public: 18 | 19 | EKF(); 20 | EKF(const int n_states, const float dt_, const FMatrixF &Q_, const FMatrixF &R_, const state &in_state); 21 | ~EKF(); 22 | void step(const FMatrixF &H_, const Eigen::VectorXf &z); 23 | 24 | private: 25 | 26 | state stateTransition(); 27 | FMatrixF jacobian(const state &x); 28 | }; 29 | 30 | } 31 | 32 | #endif /*EKF_H*/ 33 | -------------------------------------------------------------------------------- /include/state.h: -------------------------------------------------------------------------------- 1 | #ifndef STATE_H 2 | #define STATE_H 3 | 4 | #include 5 | #include 6 | #include 7 | 8 | namespace tracking{ 9 | 10 | struct state 11 | { 12 | float x = 0.0f; 13 | float y = 0.0f; 14 | float yaw = 0.0f; 15 | float vel = 0.0f; 16 | float yawRate = 0.0f; 17 | 18 | state() {} 19 | state(const float x_, const float y_, const float yaw_, const float vel_, 20 | const float yaw_rate): x(x_), y(y_), yaw(yaw_), vel(vel_), 21 | yawRate(yaw_rate) {} 22 | void print(); 23 | }; 24 | 25 | Eigen::VectorXf StateIntoVector(const state &x, int n_states); 26 | state VectorIntoState(const Eigen::VectorXf &v); 27 | 28 | } 29 | 30 | #endif /*STATE_H*/ 31 | -------------------------------------------------------------------------------- /src/filter.cpp: -------------------------------------------------------------------------------- 1 | #include "filter.h" 2 | 3 | namespace tracking{ 4 | 5 | void Filter::printInternalState(){ 6 | std::cout << "***************Internal state*********************" << std::endl; 7 | std::cout << "n_states: " << nStates << std::endl; 8 | std::cout << "dt: " << dt << std::endl; 9 | std::cout << "P: \n" 10 | << P << std::endl; 11 | std::cout << "Q: \n" 12 | << Q << std::endl; 13 | std::cout << "R: \n" 14 | << R << std::endl; 15 | std::cout << "H: \n" 16 | << H << std::endl; 17 | xEst.print(); 18 | std::cout << "**************************************************" << std::endl; 19 | } 20 | 21 | state Filter::getEstimatedState(){ return xEst; } 22 | 23 | FMatrixF Filter::getCovarianceMatrix(){ return P;} 24 | 25 | } 26 | -------------------------------------------------------------------------------- /include/filter.h: -------------------------------------------------------------------------------- 1 | #ifndef FILTER_H 2 | #define FILTER_H 3 | 4 | #include 5 | #include 6 | #include 7 | 8 | #include "state.h" 9 | 10 | namespace tracking{ 11 | 12 | using FMatrixF = Eigen::Matrix; 13 | enum Filters_t {EKF_t, UKF_t}; 14 | 15 | class Filter{ 16 | 17 | public: 18 | 19 | Filter(){}; 20 | virtual ~Filter() = default; 21 | void printInternalState(); 22 | state getEstimatedState(); 23 | FMatrixF getCovarianceMatrix(); 24 | virtual void step(const FMatrixF &H_, const Eigen::VectorXf &z) = 0; 25 | 26 | protected: 27 | 28 | int nStates; 29 | float dt; 30 | state xEst; 31 | FMatrixF Q; 32 | FMatrixF R; 33 | FMatrixF P; 34 | FMatrixF H; 35 | 36 | }; 37 | } 38 | 39 | #endif /*FILTER_H*/ 40 | -------------------------------------------------------------------------------- /include/obj.h: -------------------------------------------------------------------------------- 1 | #ifndef TRACKUTILS_H 2 | #define TRACKUTILS_H 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include "geodetic_conv.hpp" 9 | 10 | namespace tracking{ 11 | /*Object in meters*/ 12 | struct obj_m{ 13 | float x = 0; 14 | float y = 0; 15 | int frame = -1; 16 | int cl = -1; 17 | int w = 0; 18 | int h = 0; 19 | float error = 0.0; 20 | 21 | obj_m(){} 22 | obj_m(const float x_, const float y_, const int frame_, const int cl_, const int width, const int height, const float error_) : x(x_), y(y_), frame(frame_), cl(cl_), w(width), h(height), error(error_){} 23 | void print(); 24 | }; 25 | } 26 | 27 | std::vector readDataFromFile(const std::string filename); 28 | 29 | #endif /*TRACKUTILS_H*/ 30 | -------------------------------------------------------------------------------- /include/Tracker.h: -------------------------------------------------------------------------------- 1 | #ifndef TRACKER_H 2 | #define TRACKER_H 3 | 4 | #include "ukf.h" 5 | #include "ekf.h" 6 | #include "obj.h" 7 | #include 8 | #include 9 | 10 | #define MAX_HISTORY 50 11 | 12 | namespace tracking { 13 | class Tracker 14 | { 15 | public: 16 | std::deque traj; 17 | std::deque trajFilter; 18 | std::deque zList; 19 | std::deque predList; 20 | Filter *filter = nullptr; 21 | int age; 22 | int r; 23 | int g; 24 | int b; 25 | int cl; 26 | int id; 27 | 28 | Tracker(const obj_m &first_point, const int initial_age, const float dt, const int n_states, const int id_, Filters_t filter_type); 29 | Tracker(const std::deque& traj_,const std::deque& zList_, const std::deque& predList_,Filter* filter_,const int age_, const int r_, const int g_, const int b_, const int cl_, const int id_); 30 | 31 | private: 32 | Tracker(); 33 | Filter* filterInitialize(const float dt, const int n_states, const obj_m &first_point, Filters_t filter_type); 34 | }; 35 | 36 | } 37 | 38 | #endif /*TRACKER_H*/ -------------------------------------------------------------------------------- /src/obj.cpp: -------------------------------------------------------------------------------- 1 | #include "obj.h" 2 | 3 | namespace tracking{ 4 | void obj_m::print(){ 5 | std::cout << std::setprecision(10) << "x: " << x << "\ty: " << y << "\tf: " << frame << "\tc: " << cl << std::endl; 6 | } 7 | } 8 | 9 | std::vector readDataFromFile(const std::string filename){ 10 | std::ifstream file; 11 | file.open(filename); 12 | 13 | tracking::obj_m d; 14 | long int timestamp; 15 | std::vector data; 16 | 17 | double east, north, up; 18 | 19 | geodetic_converter::GeodeticConverter gc; 20 | gc.initialiseReference(44.655540, 10.934315, 0); //set the origin (centre) 21 | 22 | if (file.is_open()){ 23 | std::string line; 24 | while (getline(file, line)){ 25 | std::istringstream iss(line); 26 | iss >> d.frame >> timestamp >> d.x >> d.y; 27 | 28 | //conversion from lat lon to distance(m) from centre 29 | gc.geodetic2Enu(d.x, d.y, 0, &east, &north, &up); 30 | 31 | d.x = float(east); 32 | d.y = float(north); 33 | 34 | data.push_back(d); 35 | } 36 | } 37 | 38 | file.close(); 39 | return data; 40 | } 41 | -------------------------------------------------------------------------------- /src/plot.cpp: -------------------------------------------------------------------------------- 1 | #ifdef USE_MATPLOTLIB 2 | #include "plot.h" 3 | 4 | void testMatplotlib(){ 5 | const std::string name = "ciao"; 6 | std::vector x, y; 7 | x.push_back(1); 8 | x.push_back(2); 9 | x.push_back(3); 10 | x.push_back(4); 11 | 12 | y.push_back(1); 13 | y.push_back(2); 14 | y.push_back(3); 15 | y.push_back(4); 16 | 17 | matplotlibcpp::named_plot(name, x, y); 18 | matplotlibcpp::annotate("1", 1, 1); 19 | matplotlibcpp::annotate("2", 2, 2); 20 | matplotlibcpp::annotate("3", 3, 3); 21 | matplotlibcpp::annotate("4", 4, 4); 22 | matplotlibcpp::legend(); 23 | matplotlibcpp::show(); 24 | } 25 | 26 | void plotTrajectory(std::deque trajectory){ 27 | std::vector x; 28 | std::vector y; 29 | for (auto d : trajectory){ 30 | x.push_back(d.x); 31 | y.push_back(d.y); 32 | } 33 | matplotlibcpp::plot(x, y); 34 | for (auto d : trajectory) 35 | matplotlibcpp::annotate(std::to_string(d.frame), d.x, d.y); 36 | matplotlibcpp::title("Trajectory"); 37 | 38 | matplotlibcpp::show(); 39 | } 40 | 41 | void plotTruthvsPred(std::deque groudtruth, std::deque prediction){ 42 | std::vector x_gt; 43 | std::vector y_gt; 44 | for (auto gt : groudtruth){ 45 | x_gt.push_back(gt.x); 46 | y_gt.push_back(gt.y); 47 | } 48 | 49 | std::vector x_pr; 50 | std::vector y_pr; 51 | for (auto pr : prediction){ 52 | x_pr.push_back(pr.x); 53 | y_pr.push_back(pr.y); 54 | } 55 | 56 | matplotlibcpp::named_plot("Groundtruth", x_gt, y_gt, "r--"); 57 | matplotlibcpp::named_plot("Prediction", x_pr, y_pr, "g"); 58 | matplotlibcpp::legend(); 59 | matplotlibcpp::show(); 60 | } 61 | 62 | #endif -------------------------------------------------------------------------------- /demo/main.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "ukf.h" 4 | #include "obj.h" 5 | #ifdef USE_MATPLOTLIB 6 | #include "plot.h" 7 | #endif 8 | #include "Tracking.h" 9 | #include "filter.h" 10 | 11 | void UKFtest() 12 | { 13 | std::cout << "This is a test" << std::endl; 14 | 15 | int n_states = 5; 16 | float dt = 0.03f; 17 | 18 | tracking::FMatrixF Q = tracking::FMatrixF::Zero(n_states, n_states); 19 | tracking::FMatrixF R = tracking::FMatrixF::Zero(n_states, n_states); 20 | float dt2 = dt * dt; 21 | Q.diagonal() << 1.0f*1.0f*dt2, 1.0f*1.0f*dt2, 1.0f*1.0f*dt2, 3.0f*3.0f*dt2, 0.1f*0.1f*dt2; 22 | R.diagonal() << 0.5f*0.5f, 0.5f*0.5f, 0.1f*0.1f, 0.5f*0.5f, 0.02f*0.02f; 23 | 24 | std::cout << Q << std::endl; 25 | std::cout << R << std::endl; 26 | 27 | tracking::state s(1.0f, 2.0f, 0.0f, 0.0f, 0.0f); 28 | 29 | tracking::UKF ukf(n_states, dt, Q, R, s); 30 | ukf.printInternalState(); 31 | 32 | tracking::FMatrixF H = tracking::FMatrixF::Zero(n_states, n_states); 33 | H(0, 0) = 1.0f; 34 | H(1, 1) = 1.0f; 35 | 36 | Eigen::VectorXf v(n_states); 37 | v << 3.0f, 4.0f, 0.0f, 0.0f, 0.0f; 38 | 39 | ukf.step(H, v); 40 | ukf.printInternalState(); 41 | } 42 | 43 | int main(/*int argc, char **argv*/) 44 | { 45 | 46 | std::vector data = readDataFromFile("../data/test_ll.txt"); 47 | for (auto d : data) 48 | d.print(); 49 | 50 | // #ifdef USE_MATPLOTLIB 51 | //testMatplotlib(); 52 | // #endif 53 | 54 | 55 | float dt = 0.03f; 56 | int n_states = 5; 57 | int initial_age = 5; 58 | bool verbose = true; 59 | tracking::Filters_t filter_type = tracking::Filters_t::EKF_t; 60 | 61 | tracking::Tracking t(n_states, dt, initial_age, filter_type); 62 | t.trackOnGivenData(data, verbose); 63 | 64 | return EXIT_SUCCESS; 65 | } 66 | -------------------------------------------------------------------------------- /src/Tracker.cpp: -------------------------------------------------------------------------------- 1 | #include "Tracker.h" 2 | 3 | namespace tracking{ 4 | Tracker::Tracker(const obj_m &first_point, const int initial_age, const float dt, const int n_states, const int id_, Filters_t filter_type) 5 | { 6 | traj.push_back(first_point); 7 | trajFilter.push_back(first_point); 8 | age = initial_age; 9 | filter = filterInitialize(dt, n_states, first_point, filter_type); 10 | 11 | r = rand() % 256; 12 | g = rand() % 256; 13 | b = rand() % 256; 14 | 15 | cl = first_point.cl; 16 | id = id_; 17 | } 18 | 19 | Tracker::Tracker(const std::deque& traj_,const std::deque& zList_, const std::deque& predList_,Filter* filter_,const int age_, const int r_, const int g_, const int b_, const int cl_, const int id_) 20 | { 21 | this->traj = traj_; 22 | this->trajFilter = traj_; 23 | this->zList = zList_; 24 | this->predList = predList_; 25 | this-> filter = filter_; 26 | this->age = age_; 27 | this->r = r_; 28 | this->g = g_; 29 | this->b = b_; 30 | this->cl = cl_; 31 | this->id = id_; 32 | } 33 | 34 | Filter* Tracker::filterInitialize(const float dt, const int n_states, const obj_m &first_point, Filters_t filter_type) 35 | { 36 | tracking::FMatrixF Q = tracking::FMatrixF::Zero(n_states, n_states); 37 | tracking::FMatrixF R = tracking::FMatrixF::Zero(n_states, n_states); 38 | float dt2 = dt * dt; 39 | Q.diagonal() << 3.0f*3.0f*dt2, 3.0f*3.0f*dt2, 1.0f*1.0f*dt2, 25.0f*25.0f*dt2, 0.1f*0.1f*dt2; 40 | R.diagonal() << 0.5f*0.5f, 0.5f*0.5f, 0.1f*0.1f, 0.8f*0.8f, 0.02f*0.02f; 41 | state s(first_point.x, first_point.y, 0, 0, 0); 42 | 43 | if(filter_type == Filters_t::EKF_t){ 44 | EKF * ekf = new EKF(n_states, dt, Q, R, s); 45 | return ekf; 46 | } 47 | 48 | UKF * ukf = new UKF(n_states, dt, Q, R, s); 49 | return ukf; 50 | } 51 | 52 | }//namespace tracking -------------------------------------------------------------------------------- /include/Tracking.h: -------------------------------------------------------------------------------- 1 | #ifndef TRACKING_H 2 | #define TRACKING_H 3 | 4 | #include "ukf.h" 5 | #include "obj.h" 6 | #ifdef USE_MATPLOTLIB 7 | #include "plot.h" 8 | #endif 9 | #include "Tracker.h" 10 | #include 11 | 12 | namespace tracking{ 13 | 14 | struct knn_infos 15 | { 16 | int objIdPrev = -1; 17 | int objIdCurr = -1; 18 | float dist = 0; //distance 19 | }; 20 | 21 | bool compareKnn_infos(const knn_infos & a, const knn_infos& b); 22 | 23 | /* For each object in the new frame this method computes the distance from 24 | * each object in the old frame and save the smallest one. 25 | 26 | * Input 27 | * @param old_points: old frame objects 28 | * @param new_points: new frame objects 29 | * 30 | * @return a vector of float vectors containing 31 | * , 32 | * ordered for old_frame_obj_index first(ascending), distance second(ascending). 33 | */ 34 | std::vector computeDistance(const std::vector &old_points, const std::vector &new_points); 35 | 36 | #define MAX_INDEX 32767 37 | 38 | class Tracking 39 | { 40 | bool * trackerIndexes = nullptr; 41 | int curIndex = 0; 42 | int ageThreshold = 0; 43 | int filterStates; 44 | int initialAge; 45 | float dt; 46 | Filters_t filterType; 47 | 48 | void deleteOldTrajectories(bool verbose=false); 49 | void addNewTrajectories(const std::vector &frame, const std::vector &used, const std::vector &knn_res, bool verbose=false); 50 | void nearestNeighbor(const std::vector &frame, std::vector& knn_res, std::vector& used, std::vector& new_trajs); 51 | void kalmanStep(const std::vector& new_trajs); 52 | int getTrackerIndex(); 53 | 54 | 55 | public: 56 | std::vector trackers; 57 | 58 | Tracking(const int n_states, const float dt_, const int initial_age, const Filters_t filter_type); 59 | ~Tracking(); 60 | void track(const std::vector &frame, bool verbose=false); 61 | void trackOnGivenData(const std::vector &data, bool verbose=false); 62 | std::vector getTrackers(); 63 | void setAgeThreshold(const int age_threshold); 64 | 65 | }; 66 | 67 | } 68 | 69 | #endif /*TRACKING_H*/ -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8) 2 | project (class-tracker) 3 | 4 | # Link this 'library' to use the warnings specified in CompilerWarnings.cmake 5 | add_library(project_warnings INTERFACE) 6 | # standard compiler warnings 7 | include(cmake/CompilerWarnings.cmake) 8 | set_project_warnings(project_warnings) 9 | 10 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -std=c++11") 11 | set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} ${CMAKE_CXX_FLAGS}") 12 | set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} ${CMAKE_CXX_FLAGS} -O3") 13 | 14 | #------------------------------------------------------------------------------- 15 | # Options 16 | #------------------------------------------------------------------------------- 17 | 18 | option(WITH_MATPLOTLIB "Compiling also matplotlib" ON) 19 | if(WITH_MATPLOTLIB) 20 | add_compile_definitions(USE_MATPLOTLIB) 21 | include_directories( SYSTEM ${CMAKE_CURRENT_SOURCE_DIR}/matplotlib-cpp ) 22 | endif() 23 | 24 | #------------------------------------------------------------------------------- 25 | # External Libraries 26 | #------------------------------------------------------------------------------- 27 | find_package(Eigen3 REQUIRED) 28 | find_package(Python3 COMPONENTS Interpreter Development) 29 | 30 | message("Python_FOUND:${Python3_FOUND}") 31 | message("Python_VERSION:${Python3_VERSION}") 32 | message("Python_Development_FOUND:${Python3_Development_FOUND}") 33 | message("Python_LIBRARIES:${Python3_LIBRARIES}") 34 | message("Python_INCLUDE_DIRS:${Python3_INCLUDE_DIRS}") 35 | 36 | include_directories( ${CMAKE_CURRENT_SOURCE_DIR}/include ) 37 | include_directories( SYSTEM ${CMAKE_CURRENT_SOURCE_DIR}/geodetic_utils/geodetic_utils/include/geodetic_utils 38 | ${EIGEN3_INCLUDE_DIR} 39 | ${Python3_INCLUDE_DIRS} 40 | ) 41 | 42 | file(GLOB class-tracker-SRC "src/*.cpp") 43 | set(class-tracker-LIBS ${Python3_LIBRARIES}) 44 | add_library(class-tracker SHARED ${class-tracker-SRC}) 45 | target_link_libraries(class-tracker ${class-tracker-LIBS} project_warnings ) 46 | 47 | #------------------------------------------------------------------------------- 48 | # Build executables 49 | #------------------------------------------------------------------------------- 50 | add_executable(tracker demo/main.cpp) 51 | target_link_libraries(tracker class-tracker) 52 | -------------------------------------------------------------------------------- /src/ekf.cpp: -------------------------------------------------------------------------------- 1 | #include "ekf.h" 2 | 3 | namespace tracking{ 4 | EKF::EKF() {} 5 | 6 | EKF::EKF(const int n_states, const float dt_, const FMatrixF &Q_, const FMatrixF &R_, const state &in_state) 7 | { 8 | nStates = n_states; 9 | dt = dt_; 10 | 11 | Q = Q_; 12 | R = R_; 13 | P = FMatrixF::Identity(nStates, nStates); 14 | H = FMatrixF::Identity(nStates, nStates); 15 | 16 | xEst = in_state; 17 | } 18 | 19 | EKF::~EKF() 20 | { 21 | //FIXME - undestand why segfault 22 | /* if (Q) 23 | delete Q; 24 | if (R) 25 | delete R; 26 | if (H) 27 | delete H; 28 | if (P) 29 | delete P; */ 30 | } 31 | 32 | 33 | void EKF::step(const FMatrixF &H_, const Eigen::VectorXf &z) 34 | { 35 | H = H_; 36 | 37 | //predict 38 | state x = stateTransition(); 39 | FMatrixF J = jacobian(x); 40 | FMatrixF PPred = J * P * J.transpose() + Q; 41 | 42 | //update 43 | 44 | FMatrixF Ht = H.transpose(); 45 | 46 | Eigen::VectorXf y = z - StateIntoVector(xEst, nStates); 47 | FMatrixF S = H * PPred * Ht + R; 48 | FMatrixF K = PPred * Ht * (S.inverse()); 49 | Eigen::VectorXf x_est_vec = StateIntoVector(x, nStates) + K * y; 50 | xEst = VectorIntoState(x_est_vec); 51 | P = PPred - K * H * PPred; 52 | } 53 | 54 | state EKF::stateTransition() 55 | { 56 | state x = xEst; 57 | state y; 58 | if (abs(x.yawRate) < 0.0001f){ 59 | y.x = x.x + x.vel * dt * float(cos(x.yaw)); 60 | y.y = x.y + x.vel * dt * float(sin(x.yaw)); 61 | y.yaw = x.yaw; 62 | y.vel = x.vel; 63 | y.yawRate = 0.0001f; 64 | } 65 | else{ 66 | y.x = x.x + (x.vel / x.yawRate) * (float(sin(x.yawRate * dt + x.yaw)) - float(sin(x.yaw))); 67 | y.y = x.y + (x.vel / x.yawRate) * (-float(cos(x.yawRate * dt + x.yaw)) + float(cos(x.yaw))); 68 | y.yaw = x.yaw + x.yawRate * dt; 69 | y.vel = x.vel; 70 | y.yawRate = x.yawRate; 71 | } 72 | 73 | return y; 74 | } 75 | 76 | FMatrixF EKF::jacobian(const state &x) 77 | { 78 | FMatrixF J(nStates, nStates); 79 | J.setIdentity(); 80 | 81 | J(0, 2) = (x.vel / x.yawRate) * (float(cos(x.yawRate * dt + x.yaw)) - float(cos(x.yaw))); 82 | J(0, 3) = (1.0f / x.yawRate) * (float(sin(x.yawRate * dt + x.yaw)) - float(sin(x.yaw))); 83 | J(0, 4) = (dt * x.vel / x.yawRate) * float(cos(x.yawRate * dt + x.yaw)) - (x.vel / (x.yawRate * x.yawRate)) * (float(sin(x.yawRate * dt + x.yaw)) - float(sin(x.yaw))); 84 | J(1, 2) = (x.vel / x.yawRate) * (float(sin(x.yawRate * dt + x.yaw)) - float(sin(x.yaw))); 85 | J(1, 3) = (1.0f / x.yawRate) * (-float(cos(x.yawRate * dt + x.yaw)) + float(cos(x.yaw))); 86 | J(1, 4) = (dt * x.vel / x.yawRate) * float(sin(x.yawRate * dt + x.yaw)) - (x.vel / (x.yawRate * x.yawRate)) * (-float(cos(x.yawRate * dt + x.yaw)) + float(cos(x.yaw))); 87 | J(2, 4) = dt; 88 | 89 | return J; 90 | } 91 | 92 | } //namespace tracking -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # class-tracker 2 | 3 | 4 | 5 | ```class-tracker``` is a C++ library that implements both an Extended Kalman Filter (EFK) and an Unscented Kalman Filter (UKF), based tracker. 6 | 7 | The tracker only works on the position of the object ```(x,y)``` to predict not only the new position ```(x’,y’)```, but also the velocity ```v``` the yaw ![equation](https://latex.codecogs.com/gif.latex?%5Cpsi), and the yaw-rate ![equation](https://latex.codecogs.com/gif.latex?%5Cdot%5Cpsi). Hence, the state of EKF is: 8 | 9 | ![equation](https://latex.codecogs.com/gif.latex?%5Cbegin%7Bbmatrix%7D%20x%20%5C%5C%20y%20%5C%5C%20%5Cpsi%20%5C%5C%20v%20%5C%5C%20%5Cdot%5Cpsi%20%5C%5C%20%5Cend%7Bbmatrix%7D) 10 | 11 | While the state transition adopted: 12 | 13 | ![equation](https://latex.codecogs.com/gif.latex?%5Cbegin%7Bbmatrix%7D%20x%20+%20%5Cfrac%7Bv%5Ccdot%28-sin%28%5Cpsi%29%20+%20sin%28T%5Ccdot%20%5Cdot%5Cpsi%20+%20%5Cpsi%29%29%7D%7B%5Cdot%5Cpsi%7D%20%5C%5C%20y+%20%5Cfrac%7Bv%5Ccdot%28cos%28%5Cpsi%29%20-%20cos%28T%5Ccdot%20%5Cdot%5Cpsi%20+%20%5Cpsi%29%29%7D%7B%5Cdot%5Cpsi%7D%20%5C%5C%20T%5Ccdot%20%5Cdot%5Cpsi%20+%20%5Cpsi%20%5C%5C%20v%20%5C%5C%20%5Cdot%5Cpsi%20%5C%5C%20%5Cend%7Bbmatrix%7D) 14 | 15 | 16 | It is important to know that the filter expects to receive data in meters and returns: 17 | - ```(x',y')``` in meters 18 | - ```v``` in m/s 19 | - ![equation](https://latex.codecogs.com/gif.latex?%5Cpsi) in radians 20 | - ![equation](https://latex.codecogs.com/gif.latex?%5Cdot%5Cpsi) in radians/second 21 | 22 | 23 | Moreover, it is important to set the correct ```delta t``` and the wanted age factor when using the tracker as a library. 24 | 25 | ## Dependencies 26 | 27 | ``` 28 | sudo apt-get install libeigen3-dev python3-matplotlib libpython3.6 29 | 30 | ``` 31 | 32 | This library also depends upon: 33 | - [matplotlib-cpp](https://github.com/lava/matplotlib-cpp) for visualization 34 | - [geotedic_utils](https://github.com/ethz-asl/geodetic_utils) for the convertion from GPS to meters 35 | 36 | ## Building this repo 37 | ``` 38 | git clone https://github.com/mive93/tracker_CLASS 39 | cd class-tracker 40 | git submodule update --init --recursive 41 | mkdir build 42 | cd build 43 | cmake -DCMAKE_BUILD_TYPE=Release .. 44 | make -j4 45 | ``` 46 | 47 | Optionally 48 | ``` 49 | cmake -DCMAKE_BUILD_TYPE=RelWithDebInfo .. 50 | cmake -DCMAKE_BUILD_TYPE=Debug .. 51 | ``` 52 | 53 | Matplotlib can be activated (resp. deactivated) with the cmake option -DWITH_MATPLOTLIB=True (resp. -DWITH_MATPLOTLIB=False ) 54 | 55 | ## Running the demo 56 | 57 | This repository offers a library to exploit the implemented filter, however, there is also a dummy example of the usage of the trackers given by the program ```tracker```. Once the project has been built, it can just be run with: 58 | ``` 59 | 60 | ./tracker 61 | ``` 62 | 63 | It exploits the file ```../data/test_ll.txt``` in which in each line there is 64 | 65 | - frame number 66 | - timestamp 67 | - latitude (GPS) 68 | - longitude (GPS) 69 | 70 | and it shows how to convert them into meters using the geodetic_converter. 71 | 72 | Once run, it will show the ground-truth (noisy positions) in red and the output of the filter (the prediction of EKF of UKF) in green as in this picture: 73 | 74 | ![example](img/example.png) 75 | 76 | 77 | 78 | 79 | 80 | # Acknowledgements 81 | 82 | This work has been supported by the EU H2020 project CLASS, contract #780622. 83 | -------------------------------------------------------------------------------- /data/prova.txt: -------------------------------------------------------------------------------- 1 | 1 56382 44.655540 10.934315 2 | 3 56479 44.655540 10.934313 3 | 4 56529 44.655540 10.934314 4 | 5 56589 44.655540 10.934312 5 | 6 56617 44.655540 10.934311 6 | 7 56651 44.655544 10.934305 7 | 8 56688 44.655540 10.934307 8 | 9 56746 44.655540 10.934308 9 | 10 56816 44.655537 10.934310 10 | 11 56849 44.655540 10.934305 11 | 12 56887 44.655537 10.934303 12 | 13 56922 44.655537 10.934302 13 | 14 56960 44.655537 10.934302 14 | 15 57033 44.655540 10.934299 15 | 16 57082 44.655540 10.934299 16 | 17 57117 44.655540 10.934299 17 | 18 57153 44.655544 10.934293 18 | 19 57187 44.655540 10.934292 19 | 20 57239 44.655540 10.934292 20 | 21 57293 44.655537 10.934299 21 | 22 57361 44.655540 10.934290 22 | 23 57396 44.655540 10.934290 23 | 24 57428 44.655540 10.934290 24 | 25 57467 44.655540 10.934290 25 | 26 57522 44.655540 10.934288 26 | 27 57578 44.655540 10.934285 27 | 28 57636 44.655540 10.934283 28 | 29 57674 44.655540 10.934283 29 | 30 57709 44.655544 10.934281 30 | 31 57766 44.655540 10.934284 31 | 32 57819 44.655540 10.934283 32 | 33 57869 44.655540 10.934283 33 | 34 57903 44.655540 10.934281 34 | 35 57934 44.655540 10.934279 35 | 36 57969 44.655540 10.934279 36 | 37 58005 44.655544 10.934278 37 | 38 58057 44.655544 10.934274 38 | 39 58107 44.655544 10.934274 39 | 40 58168 44.655544 10.934275 40 | 41 58206 44.655552 10.934265 41 | 42 58241 44.655544 10.934272 42 | 43 58433 44.655552 10.934266 43 | 44 58470 44.655544 10.934270 44 | 45 58520 44.655544 10.934271 45 | 46 58618 44.655544 10.934273 46 | 47 58672 44.655544 10.934271 47 | 48 58704 44.655544 10.934269 48 | 49 58746 44.655544 10.934269 49 | 50 58800 44.655552 10.934261 50 | 51 58856 44.655552 10.934259 51 | 52 58889 44.655548 10.934267 52 | 53 58927 44.655548 10.934262 53 | 54 58966 44.655548 10.934262 54 | 55 58999 44.655548 10.934262 55 | 56 59049 44.655548 10.934261 56 | 57 59104 44.655548 10.934260 57 | 58 59175 44.655548 10.934261 58 | 59 59216 44.655556 10.934255 59 | 60 59249 44.655556 10.934254 60 | 61 59302 44.655556 10.934253 61 | 62 59358 44.655556 10.934251 62 | 63 59409 44.655560 10.934249 63 | 64 59465 44.655556 10.934251 64 | 68 59658 44.655556 10.934249 65 | 69 59716 44.655556 10.934249 66 | 70 59749 44.655560 10.934247 67 | 71 59802 44.655560 10.934247 68 | 72 59860 44.655560 10.934246 69 | 73 59925 44.655560 10.934244 70 | 74 59967 44.655560 10.934244 71 | 75 60001 44.655560 10.934243 72 | 76 60053 44.655560 10.934242 73 | 77 60107 44.655560 10.934242 74 | 78 60175 44.655560 10.934242 75 | 79 60215 44.655560 10.934241 76 | 80 60250 44.655560 10.934241 77 | 81 60303 44.655560 10.934240 78 | 82 60447 44.655563 10.934238 79 | 83 60482 44.655563 10.934237 80 | 84 60516 44.655563 10.934237 81 | 85 60558 44.655563 10.934237 82 | 86 60632 44.655563 10.934237 83 | 87 60683 44.655560 10.934235 84 | 89 60753 44.655560 10.934236 85 | 90 60808 44.655560 10.934235 86 | 91 60848 44.655560 10.934233 87 | 92 60884 44.655560 10.934233 88 | 93 60918 44.655560 10.934232 89 | 94 60950 44.655563 10.934231 90 | 95 60981 44.655563 10.934230 91 | 96 61016 44.655560 10.934230 92 | 97 61056 44.655560 10.934229 93 | 98 61092 44.655560 10.934228 94 | 99 61129 44.655560 10.934227 95 | 100 61164 44.655560 10.934226 96 | 101 61194 44.655560 10.934226 97 | 102 61227 44.655560 10.934224 98 | 103 61259 44.655563 10.934224 99 | 104 61296 44.655560 10.934222 100 | 105 61330 44.655563 10.934221 101 | 106 61363 44.655563 10.934221 102 | 107 61398 44.655560 10.934220 103 | 108 61433 44.655563 10.934217 104 | 109 61468 44.655560 10.934218 105 | 110 61505 44.655563 10.934218 106 | 111 61537 44.655563 10.934215 107 | 112 61564 44.655563 10.934214 108 | 113 61597 44.655563 10.934215 109 | -------------------------------------------------------------------------------- /src/ukf.cpp: -------------------------------------------------------------------------------- 1 | #include "ukf.h" 2 | 3 | namespace tracking{ 4 | 5 | UKF::UKF() {} 6 | 7 | UKF::UKF(const int n_states, const float dt_, const FMatrixF &Q_, const FMatrixF &R_, const state &in_state) 8 | { 9 | nStates = n_states; 10 | dt = dt_; 11 | 12 | Q = Q_; 13 | R = R_; 14 | P = FMatrixF::Identity(nStates, nStates); 15 | H = FMatrixF::Identity(nStates, nStates); 16 | 17 | xEst = in_state; 18 | } 19 | 20 | UKF::~UKF(){} 21 | 22 | 23 | void UKF::step(const FMatrixF &H_, const Eigen::VectorXf &z) 24 | { 25 | H = H_; 26 | 27 | //predict 28 | // 1- compute sigma points 29 | float k = -2; //This is the hyper Parameter 30 | FMatrixF L(P.llt().matrixL()); //cholesky decomposition 31 | FMatrixF xhatsigmapoints(nStates, 2 * nStates + 1); 32 | 33 | FMatrixF xEstMatrix(nStates, 1); //converting xEst state to UKFMatrix type 34 | xEstMatrix << xEst.x, xEst.y, xEst.yaw, xEst.vel, xEst.yawRate; //converting xEst state to UKFMatrix type 35 | 36 | xhatsigmapoints.col(0) = xEstMatrix; 37 | int i; 38 | for (i = 1; i <= nStates; i++) { 39 | xhatsigmapoints.col(i) = xEstMatrix + std::sqrt(float(nStates) + k) * L.col(i-1); 40 | xhatsigmapoints.col(nStates + i) = xEstMatrix - sqrt(float(nStates) + k) * L.col(i-1); 41 | } 42 | //2-propagate sigma points 43 | FMatrixF xbrevesigmapoints(nStates, 2 * nStates + 1); 44 | for (i = 0; i < 2 * nStates + 1; i++) { 45 | state xinput(xhatsigmapoints(0, i), xhatsigmapoints(1, i), xhatsigmapoints(2, i), xhatsigmapoints(3, i), xhatsigmapoints(4, i)); 46 | state x = stateTransition(xinput); 47 | FMatrixF xMatrix(nStates, 1); 48 | xMatrix << x.x, x.y, x.yaw, x.vel, x.yawRate; 49 | xbrevesigmapoints.col(i) = xMatrix; 50 | } 51 | //3-prediction 52 | FMatrixF alpha(2 * nStates + 1, 1); 53 | alpha(0) = k / (float(nStates) + k); 54 | for (i = 1; i < 2 * nStates + 1; i++) { 55 | alpha(i) = 0.5f / (float(nStates) + k); 56 | } 57 | FMatrixF xbreve(nStates, 1); 58 | xbreve = xbrevesigmapoints * alpha; 59 | FMatrixF pbreve(nStates, nStates); 60 | pbreve = FMatrixF::Zero(nStates, nStates); 61 | for (i = 0; i < 2 * nStates + 1; i++) { 62 | pbreve += alpha(i) * (xbrevesigmapoints.col(i) - xbreve) * (xbrevesigmapoints.col(i) - xbreve).transpose(); 63 | } 64 | pbreve += Q; 65 | 66 | //update 67 | // 4.1 propagate sigma points for measurment function 68 | FMatrixF yhatsigmapoints(nStates, 2 * nStates + 1); 69 | yhatsigmapoints = H * xbrevesigmapoints; 70 | //4.2 mean and covariance of predicted measurment 71 | FMatrixF yhat(nStates, 1); 72 | yhat = yhatsigmapoints * alpha; 73 | FMatrixF py; 74 | py = FMatrixF::Zero(nStates, nStates); 75 | for (i = 0; i < 2 * nStates + 1; i++) { 76 | py += alpha(i) * (yhatsigmapoints.col(i) - yhat) * (yhatsigmapoints.col(i) - yhat).transpose(); 77 | } 78 | py += R; 79 | //4.3 cross covariance and Kalman gain 80 | FMatrixF pxy; 81 | pxy = FMatrixF::Zero(nStates, nStates); 82 | for (i = 0; i < 2 * nStates + 1; i++) { 83 | pxy += alpha(i) * (xbrevesigmapoints.col(i) - xbreve) * (yhatsigmapoints.col(i) - yhat).transpose(); 84 | } 85 | FMatrixF K; 86 | K = pxy * py.inverse(); 87 | FMatrixF xhat; 88 | xhat = xbreve + K * (z - yhat); 89 | xEst.x = xhat(0); 90 | xEst.y = xhat(1); 91 | xEst.yaw = xhat(2); 92 | xEst.vel = xhat(3); 93 | xEst.yawRate = xhat(4); 94 | P = pbreve - K * py * K.transpose(); 95 | 96 | //5 corrected mean and covariance 97 | } 98 | 99 | state UKF::stateTransition(const state &x) 100 | { 101 | state y; 102 | if (abs(x.yawRate) < 0.0001f){ 103 | y.x = x.x + x.vel * dt * float(cos(x.yaw)); 104 | y.y = x.y + x.vel * dt * float(sin(x.yaw)); 105 | y.yaw = x.yaw; 106 | y.vel = x.vel; 107 | y.yawRate = 0.0001f; 108 | } 109 | else{ 110 | y.x = x.x + (x.vel / x.yawRate) * (float(sin(x.yawRate * dt + x.yaw)) - float(sin(x.yaw))); 111 | y.y = x.y + (x.vel / x.yawRate) * (-float(cos(x.yawRate * dt + x.yaw)) + float(cos(x.yaw))); 112 | y.yaw = x.yaw + x.yawRate * dt; 113 | y.vel = x.vel; 114 | y.yawRate = x.yawRate; 115 | } 116 | 117 | return y; 118 | } 119 | 120 | 121 | } //namespace tracking 122 | -------------------------------------------------------------------------------- /cmake/CompilerWarnings.cmake: -------------------------------------------------------------------------------- 1 | # from here: 2 | # 3 | # https://github.com/lefticus/cppbestpractices/blob/master/02-Use_the_Tools_Available.md 4 | 5 | function(set_project_warnings project_name) 6 | option(WARNINGS_AS_ERRORS "Treat compiler warnings as errors" TRUE) 7 | 8 | set(MSVC_WARNINGS 9 | /W4 # Baseline reasonable warnings 10 | /w14242 # 'identifier': conversion from 'type1' to 'type1', possible loss of data 11 | /w14254 # 'operator': conversion from 'type1:field_bits' to 'type2:field_bits', possible loss of data 12 | /w14263 # 'function': member function does not override any base class virtual member function 13 | /w14265 # 'classname': class has virtual functions, but destructor is not virtual instances of this class may not 14 | # be destructed correctly 15 | /w14287 # 'operator': unsigned/negative constant mismatch 16 | /we4289 # nonstandard extension used: 'variable': loop control variable declared in the for-loop is used outside 17 | # the for-loop scope 18 | /w14296 # 'operator': expression is always 'boolean_value' 19 | /w14311 # 'variable': pointer truncation from 'type1' to 'type2' 20 | /w14545 # expression before comma evaluates to a function which is missing an argument list 21 | /w14546 # function call before comma missing argument list 22 | /w14547 # 'operator': operator before comma has no effect; expected operator with side-effect 23 | /w14549 # 'operator': operator before comma has no effect; did you intend 'operator'? 24 | /w14555 # expression has no effect; expected expression with side- effect 25 | /w14619 # pragma warning: there is no warning number 'number' 26 | /w14640 # Enable warning on thread un-safe static member initialization 27 | /w14826 # Conversion from 'type1' to 'type_2' is sign-extended. This may cause unexpected runtime behavior. 28 | /w14905 # wide string literal cast to 'LPSTR' 29 | /w14906 # string literal cast to 'LPWSTR' 30 | /w14928 # illegal copy-initialization; more than one user-defined conversion has been implicitly applied 31 | /permissive- # standards conformance mode for MSVC compiler. 32 | ) 33 | 34 | set(CLANG_WARNINGS 35 | -Wall 36 | -Wextra # reasonable and standard 37 | -Wshadow # warn the user if a variable declaration shadows one from a parent context 38 | -Wnon-virtual-dtor # warn the user if a class with virtual functions has a non-virtual destructor. This helps 39 | # catch hard to track down memory errors 40 | -Wold-style-cast # warn for c-style casts 41 | -Wcast-align # warn for potential performance problem casts 42 | -Wunused # warn on anything being unused 43 | -Woverloaded-virtual # warn if you overload (not override) a virtual function 44 | -Wpedantic # warn if non-standard C++ is used 45 | -Wconversion # warn on type conversions that may lose data 46 | -Wsign-conversion # warn on sign conversions 47 | -Wnull-dereference # warn if a null dereference is detected 48 | -Wdouble-promotion # warn if float is implicit promoted to double 49 | -Wformat=2 # warn on security issues around functions that format output (ie printf) 50 | ) 51 | 52 | if(WARNINGS_AS_ERRORS) 53 | set(CLANG_WARNINGS ${CLANG_WARNINGS} -Werror) 54 | set(MSVC_WARNINGS ${MSVC_WARNINGS} /WX) 55 | endif() 56 | 57 | set(GCC_WARNINGS 58 | ${CLANG_WARNINGS} 59 | -Wmisleading-indentation # warn if indentation implies blocks where blocks do not exist 60 | -Wduplicated-cond # warn if if / else chain has duplicated conditions 61 | -Wduplicated-branches # warn if if / else branches have duplicated code 62 | -Wlogical-op # warn about logical operations being used where bitwise were probably wanted 63 | -Wuseless-cast # warn if you perform a cast to the same type 64 | ) 65 | 66 | if(MSVC) 67 | set(PROJECT_WARNINGS ${MSVC_WARNINGS}) 68 | elseif(CMAKE_CXX_COMPILER_ID MATCHES ".*Clang") 69 | set(PROJECT_WARNINGS ${CLANG_WARNINGS}) 70 | elseif(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") 71 | set(PROJECT_WARNINGS ${GCC_WARNINGS}) 72 | else() 73 | message(AUTHOR_WARNING "No compiler warnings set for '${CMAKE_CXX_COMPILER_ID}' compiler.") 74 | endif() 75 | 76 | target_compile_options(${project_name} INTERFACE ${PROJECT_WARNINGS}) 77 | 78 | endfunction() 79 | -------------------------------------------------------------------------------- /data/gt_000002.txt: -------------------------------------------------------------------------------- 1 | 2953 116110570 1.24631 3.87682 2 | 2953 582303759 1.13875 3.43319 3 | 2954 116210130 1.20888 2.79945 4 | 2954 516691746 1.2596 2.33538 5 | 2954 983739984 1.41337 1.88298 6 | 2955 317435795 1.56108 1.58917 7 | 2955 717697094 1.81881 1.26165 8 | 2956 118081951 2.17597 1.2245 9 | 2956 585199073 2.60993 1.31644 10 | 2957 52335391 2.93873 1.61524 11 | 2957 519469476 3.11359 2.19998 12 | 2957 986707670 3.30518 2.67054 13 | 2958 453694609 3.28287 3.20218 14 | 2958 854089954 3.34668 3.68284 15 | 2959 321259205 3.44617 4.1486 16 | 2959 788361691 3.2813 4.57943 17 | 2960 255474489 2.98192 4.98055 18 | 2960 722588184 2.51798 5.02573 19 | 2961 190951858 2.11206 4.94023 20 | 2961 656810985 1.7513 4.64789 21 | 2962 124020100 1.52072 4.217 22 | 2962 524485288 1.36029 3.7603 23 | 2962 991541133 1.2955 3.23148 24 | 2963 391832589 1.32176 2.80811 25 | 2963 792302206 1.33791 2.3417 26 | 2964 192881200 1.46689 1.91858 27 | 2964 526448233 1.60431 1.60282 28 | 2964 926850955 1.87742 1.39377 29 | 2965 394118173 2.28809 1.42472 30 | 2965 862329362 2.63769 1.67228 31 | 2966 328075826 2.76357 2.03023 32 | 2966 795240359 2.75705 2.46027 33 | 2967 262273484 2.61014 3.01948 34 | 2967 729435281 2.29107 3.46392 35 | 2968 196567520 1.98582 3.96158 36 | 2968 596941675 1.69803 4.28386 37 | 2969 64026540 1.49149 4.60709 38 | 2969 397694409 1.63981 4.88459 39 | 2969 664566295 1.76542 5.02621 40 | 2969 931516216 1.97185 5.20309 41 | 2970 398664316 2.40261 5.16687 42 | 2970 865828700 2.84049 4.94817 43 | 2971 332890076 3.0818 4.53389 44 | 2971 800027107 3.03045 4.01094 45 | 2972 267212547 2.91991 3.49666 46 | 2972 667572185 2.65658 3.13327 47 | 2973 134654249 2.34593 2.75361 48 | 2973 601828733 1.99942 2.39255 49 | 2974 2154600 1.70541 2.07022 50 | 2974 469385520 1.5829 1.63619 51 | 2974 936449421 1.69179 1.34927 52 | 2975 270043048 1.92113 1.27885 53 | 2975 737203924 2.25091 1.47307 54 | 2976 204331310 2.58056 1.7708 55 | 2976 671463181 2.6408 2.24184 56 | 2977 138517260 2.50379 2.74432 57 | 2977 605695240 2.25788 3.16038 58 | 2978 6088572 1.93287 3.52894 59 | 2978 406408089 1.75061 3.93377 60 | 2978 806833034 1.51045 4.26113 61 | 2979 207208518 1.34542 4.61849 62 | 2979 540962920 1.4309 4.88779 63 | 2979 741088127 1.56463 5.00603 64 | 2979 941280381 1.72477 5.1174 65 | 2980 274910044 2.0317 5.30067 66 | 2980 742036589 2.47279 5.21396 67 | 2981 209215633 2.8331 5.00743 68 | 2981 676282706 3.07038 4.61283 69 | 2982 143430986 3.11825 4.09979 70 | 2982 610592311 3.0984 3.63005 71 | 2983 77722726 2.86928 3.17043 72 | 2983 544837971 2.5702 2.76003 73 | 2983 945164343 2.25321 2.51221 74 | 2984 412291212 1.86649 2.26574 75 | 2984 879473868 1.57359 1.80585 76 | 2985 346541193 1.43457 1.47939 77 | 2985 746962713 1.55808 1.24748 78 | 2986 214093180 1.8913 1.30199 79 | 2986 681224102 2.31008 1.36989 80 | 2987 148354917 2.58056 1.7708 81 | 2987 615468615 2.77694 2.25188 82 | 2988 82593479 2.97878 2.78668 83 | 2988 549664368 3.00952 3.36145 84 | 2989 16889771 3.09751 3.89332 85 | 2989 483948509 2.91783 4.38793 86 | 2989 884347805 2.77167 4.79279 87 | 2990 284675588 2.51317 5.10306 88 | 2990 751802685 2.10175 5.17274 89 | 2991 218930292 1.69871 5.12456 90 | 2991 619352571 1.42701 4.84366 91 | 2992 87028193 1.25627 4.37698 92 | 2992 553605330 1.19978 3.80063 93 | 2993 21871643 1.20692 3.29219 94 | 2993 421532850 1.14587 2.86386 95 | 2993 889258471 1.31034 2.3287 96 | 2994 290290615 1.42406 1.93497 97 | 2994 690624783 1.65846 1.56356 98 | 2995 22767362 1.95238 1.49194 99 | 2995 491119480 2.35439 1.51983 100 | 2995 956977404 2.73568 1.83682 101 | 2996 424106420 2.89355 2.27665 102 | 2996 891230931 3.08424 2.76121 103 | 2997 358365567 3.10873 3.28888 104 | 2997 825477279 3.02875 3.8224 105 | 2998 294007940 3.03932 4.31258 106 | 2998 759727075 2.80872 4.73278 107 | 2999 226866435 2.51458 5.19469 108 | 2999 695292278 2.1418 5.19659 109 | 3000 161113825 1.73508 5.10871 110 | 3000 629362312 1.36752 4.79795 111 | 3001 95240365 1.28568 4.35054 112 | 3001 495738978 1.14342 3.88988 113 | 3001 962869507 1.1061 3.36704 114 | 3002 363238089 1.1244 2.91727 115 | 3002 830369015 1.18672 2.43382 116 | 3003 297492955 1.34124 1.99341 117 | 3003 764619903 1.5293 1.5329 118 | 3004 165004870 1.88537 1.43859 119 | 3004 632376740 2.29612 1.45386 120 | 3005 99248487 2.69171 1.75272 121 | 3005 566370659 2.89033 2.20582 122 | 3006 33504554 3.1632 2.68698 123 | 3006 500625509 3.25966 3.22769 124 | 3006 968023506 3.34105 3.75923 125 | 3007 436267544 3.43208 4.18849 126 | 3007 902001632 3.2535 4.61063 127 | 3008 369561960 3.04574 5.03229 128 | 3008 836133343 2.56848 5.1053 129 | 3009 303257375 2.15842 5.12062 130 | 3009 770382227 1.77719 4.94828 131 | 3010 237465947 1.60355 4.50916 132 | 3010 638007826 1.50734 4.11311 133 | 3011 105005285 1.67757 3.64105 134 | 3011 505473717 1.91713 3.26707 135 | 3011 972638949 2.20817 2.82368 136 | 3012 439755715 2.52447 2.42541 137 | 3012 840133620 2.56232 2.00065 138 | 3013 307264206 2.52027 1.50023 139 | 3013 774386816 2.3666 1.12914 140 | 3014 241465430 1.99358 0.959883 141 | 3014 708585109 1.58572 0.96777 142 | 3015 109010133 1.41425 1.24543 143 | 3015 576086884 1.27604 1.67424 144 | 3016 43271883 1.15536 2.18702 145 | 3016 510400029 1.19582 2.79945 146 | 3016 977471158 1.07851 3.30391 147 | 3017 444601484 1.06149 3.80898 148 | 3017 911727588 1.19157 4.32829 149 | 3018 312101355 1.37982 4.73809 150 | 3018 846019106 1.93704 4.86621 151 | 3019 179594228 2.31553 4.84835 152 | 3019 646768641 2.75542 4.51916 153 | -------------------------------------------------------------------------------- /src/Tracking.cpp: -------------------------------------------------------------------------------- 1 | #include "Tracking.h" 2 | 3 | namespace tracking{ 4 | 5 | bool compareKnn_infos(const knn_infos & a, const knn_infos& b){ 6 | // use to order for old_frame_obj_index first(ascending), distance second(ascending). 7 | return (a.objIdPrev < b.objIdPrev || (a.objIdPrev == b.objIdPrev && a.dist < b.dist)); 8 | } 9 | 10 | std::vector computeDistance(const std::vector &old_points, const std::vector &new_points){ 11 | 12 | /* for(auto o: old_points) 13 | o.print(); 14 | 15 | for(auto n: new_points) 16 | n.print(); */ 17 | 18 | float dist; 19 | std::vector knn_res; 20 | for (size_t i = 0; i < new_points.size(); ++i){ 21 | knn_infos infos; 22 | infos.objIdCurr = int(i); 23 | 24 | for (size_t j = 0; j < old_points.size(); ++j){ 25 | dist = float(sqrt(pow(old_points[j].x - new_points[i].x, 2) + pow(old_points[j].y - new_points[i].y, 2))); 26 | if (j == 0){ 27 | infos.objIdPrev = int(j); 28 | infos.dist = dist; 29 | } 30 | else{ 31 | if (dist < infos.dist && old_points[j].cl == new_points[i].cl){ 32 | infos.objIdPrev = int(j); 33 | infos.dist = dist; 34 | } 35 | } 36 | } 37 | knn_res.push_back(infos); 38 | } 39 | 40 | std::sort(knn_res.begin(), knn_res.end(), compareKnn_infos); 41 | 42 | /* for(auto r: knn_res){ 43 | for(auto i: r) 44 | std::cout< valid_trackers; 64 | 65 | for (size_t i = 0; i < trackers.size(); ++i){ 66 | if (trackers[i].age > ageThreshold){ 67 | valid_trackers.push_back(trackers[i]); 68 | } 69 | else{ 70 | trackerIndexes[trackers[i].id] = false; 71 | if(verbose){ 72 | std::cout << "Deleting tracker " << trackers[i].id<< std::endl; 73 | #ifdef USE_MATPLOTLIB 74 | if (trackers[i].zList.size() > 10) 75 | plotTruthvsPred(trackers[i].zList, trackers[i].predList); 76 | #endif 77 | } 78 | } 79 | } 80 | trackers.swap(valid_trackers); 81 | } 82 | } 83 | 84 | void Tracking::addNewTrajectories(const std::vector &frame, const std::vector &used, const std::vector &knn_res, bool verbose){ 85 | for (size_t i = 0; i < knn_res.size(); ++i){ 86 | if (!used[i]){ 87 | trackers.push_back(Tracker(frame[size_t(knn_res[i].objIdCurr)], initialAge, dt, filterStates, this->getTrackerIndex(), filterType)); 88 | if(verbose) 89 | std::cout << "Adding tracker " << trackers[trackers.size()-1].id<< std::endl; 90 | } 91 | } 92 | } 93 | 94 | void Tracking::nearestNeighbor(const std::vector &frame, std::vector& knn_res, std::vector& used, std::vector& new_trajs){ 95 | 96 | std::vector prev_trajs; 97 | for (auto t : trackers) 98 | prev_trajs.push_back(t.trajFilter.back()); 99 | 100 | size_t n_cur_trajs = prev_trajs.size(); 101 | new_trajs.resize(n_cur_trajs); 102 | 103 | knn_res = computeDistance(prev_trajs, frame); 104 | used.resize(knn_res.size(), 0); 105 | std::vector max_distance(n_cur_trajs, 15); 106 | 107 | for (size_t i = 0; i < trackers.size(); i++) 108 | trackers[i].age--; 109 | 110 | size_t prev_i, cur_i; 111 | float dist; 112 | for (size_t i = 0; i < knn_res.size(); i++){ 113 | prev_i = size_t(knn_res[i].objIdPrev); 114 | dist = knn_res[i].dist; 115 | cur_i = size_t(knn_res[i].objIdCurr); 116 | 117 | if (n_cur_trajs > 0 && prev_i <= n_cur_trajs && dist < max_distance[prev_i]){ 118 | trackers[prev_i].traj.push_back(frame[cur_i]); 119 | if(trackers[prev_i].traj.size() > MAX_HISTORY) trackers[prev_i].traj.pop_front(); 120 | 121 | new_trajs[prev_i] = frame[cur_i]; 122 | max_distance[prev_i] = dist; 123 | trackers[prev_i].age = initialAge; 124 | used[i] = 1; 125 | } 126 | } 127 | } 128 | 129 | void Tracking::kalmanStep(const std::vector& new_trajs){ 130 | tracking::FMatrixF H = tracking::FMatrixF::Zero(filterStates, filterStates); 131 | Eigen::VectorXf z(filterStates); 132 | 133 | for (size_t i = 0; i < new_trajs.size(); i++){ 134 | z << new_trajs[i].x, new_trajs[i].y, 0.0f, 0.0f, 0.0f; 135 | 136 | if (new_trajs[i].x == 0.0f && new_trajs[i].y == 0.0f && new_trajs[i].frame == -1){ 137 | H(0, 0) = 0.0f; 138 | H(1, 1) = 0.0f; 139 | } 140 | else{ 141 | H(0, 0) = 1.0f; 142 | H(1, 1) = 1.0f; 143 | trackers[i].zList.push_back(state(new_trajs[i].x, new_trajs[i].y, 0.0f, 0.0f, 0.0f)); 144 | if(trackers[i].zList.size() > MAX_HISTORY) trackers[i].zList.pop_front(); 145 | } 146 | 147 | trackers[i].filter->step(H, z); 148 | 149 | trackers[i].predList.push_back(trackers[i].filter->getEstimatedState()); 150 | if(trackers[i].predList.size() > MAX_HISTORY) 151 | trackers[i].predList.pop_front(); 152 | 153 | trackers[i].trajFilter.push_back( obj_m( trackers[i].filter->getEstimatedState().x, 154 | trackers[i].filter->getEstimatedState().y, 155 | trackers[i].traj.back().frame, 156 | trackers[i].traj.back().cl, 157 | 0.0f, 158 | 0.0f, 159 | new_trajs[i].error ) ); 160 | if(trackers[i].trajFilter.size() > MAX_HISTORY) 161 | trackers[i].trajFilter.pop_front(); 162 | 163 | } 164 | } 165 | 166 | int Tracking::getTrackerIndex(){ 167 | for(int i = curIndex; i < curIndex + MAX_INDEX; ++i ){ 168 | int index = i % MAX_INDEX; 169 | if(!trackerIndexes[index]){ 170 | trackerIndexes[index] = true; 171 | curIndex = index+1; 172 | return index; 173 | } 174 | } 175 | std::cerr << "\nProblem with tracker indexes, aborting...\n"; 176 | exit(EXIT_FAILURE); 177 | } 178 | 179 | void Tracking::track(const std::vector &frame, bool verbose) 180 | { 181 | //delete trajectories not recently updated 182 | this->deleteOldTrajectories(verbose); 183 | 184 | //NN: associate new points with prevoius trajectories 185 | std::vector knn_res; 186 | std::vector used; 187 | std::vector new_trajs; 188 | this->nearestNeighbor(frame, knn_res, used, new_trajs); 189 | 190 | //Kalman step 191 | this->kalmanStep(new_trajs); 192 | 193 | //Add new trajectories from points from the current frame that were not associated 194 | this->addNewTrajectories(frame, used, knn_res, verbose); 195 | } 196 | 197 | void Tracking::trackOnGivenData(const std::vector &data, bool verbose) 198 | { 199 | int frame_id = 0; 200 | std::vector cur_frame; 201 | 202 | std::cout << "Start" << std::endl; 203 | 204 | for (auto d : data) 205 | { 206 | if (d.frame != frame_id){ 207 | track(cur_frame,verbose); 208 | cur_frame.clear(); 209 | frame_id = d.frame; 210 | } 211 | cur_frame.push_back(d); 212 | } 213 | 214 | if(verbose){ 215 | #ifdef USE_MATPLOTLIB 216 | for (size_t i = 0; i < trackers.size(); i++) 217 | if (trackers[i].zList.size() > 10) 218 | plotTruthvsPred(trackers[i].zList, trackers[i].predList); 219 | #endif 220 | } 221 | 222 | std::cout << "End." << std::endl; 223 | } 224 | 225 | std::vector Tracking::getTrackers(){ 226 | return trackers; 227 | } 228 | 229 | void Tracking::setAgeThreshold(const int age_threshold){ 230 | ageThreshold = age_threshold; 231 | } 232 | 233 | }//namespace tracking -------------------------------------------------------------------------------- /data/test.txt: -------------------------------------------------------------------------------- 1 | 0 96 1 262 65 103 276 2 | 0 94 2 258 65 110 281 3 | 0 96 3 259 69 109 271 4 | 0 98 4 264 69 100 271 5 | 0 98 5 266 68 97 272 6 | 0 97 6 267 61 98 286 7 | 0 97 7 267 59 101 285 8 | 0 98 8 268 55 102 294 9 | 0 98 9 276 50 87 303 10 | 0 97 10 275 51 88 304 11 | 0 94 11 279 65 79 224 12 | 0 99 12 273 58 78 223 13 | 0 99 13 272 53 81 229 14 | 0 99 14 272 46 79 233 15 | 0 99 15 270 43 80 234 16 | 0 98 16 271 44 77 233 17 | 0 99 17 270 44 79 235 18 | 0 99 18 271 44 76 231 19 | 0 99 19 274 47 71 223 20 | 0 99 20 278 47 69 211 21 | 0 99 21 280 45 67 213 22 | 0 99 22 282 45 67 210 23 | 0 98 23 282 45 68 211 24 | 0 99 24 283 44 68 214 25 | 0 98 25 284 45 68 212 26 | 0 99 26 285 44 66 213 27 | 0 94 27 284 49 67 200 28 | 0 94 28 283 42 68 216 29 | 0 96 29 285 38 66 193 30 | 0 94 30 287 38 61 190 31 | 0 94 31 287 39 61 187 32 | 0 97 32 286 35 63 195 33 | 0 96 33 288 31 62 194 34 | 0 96 34 299 45 51 172 35 | 0 98 35 289 30 64 194 36 | 0 97 36 291 30 63 191 37 | 0 97 37 300 46 54 164 38 | 0 95 38 294 32 63 186 39 | 0 91 39 302 49 53 150 40 | 0 93 40 303 47 52 156 41 | 0 79 41 297 39 61 163 42 | 0 78 42 295 38 62 164 43 | 0 89 43 293 34 65 176 44 | 0 89 44 291 31 69 180 45 | 0 92 45 292 29 68 183 46 | 0 85 46 298 38 64 154 47 | 0 89 47 299 31 61 164 48 | 0 85 48 299 35 61 154 49 | 0 88 49 301 28 57 170 50 | 0 87 50 297 33 67 156 51 | 0 90 51 303 31 59 160 52 | 0 96 52 306 31 54 157 53 | 0 90 53 307 32 54 154 54 | 0 70 54 312 28 57 158 55 | 0 82 55 314 28 58 156 56 | 0 93 56 316 30 56 149 57 | 0 69 57 317 35 56 140 58 | 0 57 58 317 35 58 140 59 | 0 61 59 319 35 57 140 60 | 0 77 60 318 33 56 143 61 | 0 50 61 320 38 56 130 62 | 0 29 62 323 38 53 131 63 | 0 48 63 323 34 53 138 64 | 0 65 64 325 35 49 133 65 | 0 83 65 326 32 49 138 66 | 0 90 66 328 33 47 135 67 | 0 82 67 328 32 47 137 68 | 0 60 68 328 31 50 143 69 | 0 83 69 329 27 50 146 70 | 0 44 70 327 17 55 142 71 | 0 40 72 329 15 52 142 72 | 0 32 73 330 18 52 135 73 | 0 47 74 330 19 51 138 74 | 0 64 75 331 20 57 140 75 | 0 87 76 332 18 56 144 76 | 0 31 77 328 16 54 141 77 | 0 89 78 329 16 52 145 78 | 0 87 79 329 17 52 141 79 | 0 93 80 330 15 50 139 80 | 0 92 81 331 15 50 137 81 | 0 94 82 334 16 51 131 82 | 0 97 83 334 18 51 128 83 | 0 97 84 335 19 51 129 84 | 0 92 85 338 19 48 131 85 | 0 84 86 339 19 46 128 86 | 0 80 87 340 21 46 123 87 | 0 82 88 340 22 47 123 88 | 0 73 89 341 22 46 120 89 | 0 85 90 343 23 44 119 90 | 0 87 91 342 23 46 118 91 | 0 87 92 341 21 48 122 92 | 0 56 93 276 21 29 86 93 | 0 91 94 343 21 47 117 94 | 0 93 95 342 20 48 122 95 | 0 93 96 344 21 46 120 96 | 0 93 97 344 20 46 120 97 | 0 95 98 344 17 47 124 98 | 0 94 99 347 20 42 113 99 | 0 80 100 347 22 43 110 100 | 0 84 101 347 20 43 114 101 | 0 95 102 347 17 44 117 102 | 0 94 103 348 18 44 117 103 | 0 97 104 350 18 42 115 104 | 0 86 105 350 21 42 110 105 | 0 91 106 351 21 40 109 106 | 0 92 107 351 17 45 116 107 | 0 88 108 350 11 46 112 108 | 0 94 109 350 10 45 115 109 | 0 74 110 351 11 45 111 110 | 0 47 111 350 12 47 107 111 | 0 82 112 351 11 45 110 112 | 0 92 113 351 11 44 110 113 | 0 89 114 352 11 43 109 114 | 0 89 115 351 10 44 110 115 | 0 87 116 352 10 43 112 116 | 0 91 117 352 7 43 113 117 | 0 95 118 357 8 44 113 118 | 0 93 119 357 9 45 113 119 | 0 91 120 353 6 42 115 120 | 0 81 121 356 11 47 105 121 | 0 55 122 359 14 42 100 122 | 0 73 123 361 13 40 99 123 | 0 91 124 362 13 40 99 124 | 0 96 125 362 12 40 100 125 | 0 97 126 362 12 40 100 126 | 0 41 127 364 11 39 94 127 | 0 42 128 364 11 39 93 128 | 0 45 129 365 11 39 92 129 | 0 48 130 364 12 40 91 130 | 0 95 131 363 12 41 93 131 | 0 66 132 365 11 37 91 132 | 0 87 133 365 11 38 92 133 | 0 91 134 365 11 39 92 134 | 0 93 135 365 10 39 93 135 | 0 94 136 365 9 37 93 136 | 0 91 137 366 9 37 94 137 | 0 91 138 366 9 36 95 138 | 0 96 139 366 9 36 93 139 | 0 97 140 367 9 35 95 140 | 0 96 141 368 10 33 93 141 | 0 55 142 370 9 32 95 142 | 0 82 143 370 9 32 95 143 | 0 96 144 371 8 32 97 144 | 0 97 145 370 7 32 98 145 | 0 97 146 371 6 33 98 146 | 0 96 147 371 6 33 99 147 | 0 93 148 371 6 32 99 148 | 0 85 149 372 7 31 98 149 | 0 92 150 372 7 33 96 150 | 0 97 151 374 7 30 93 151 | 0 97 152 375 8 29 96 152 | 0 90 153 376 7 27 93 153 | 0 89 154 377 6 27 93 154 | 0 88 155 376 5 28 93 155 | 0 58 156 376 5 31 95 156 | 0 88 157 377 2 29 100 157 | 0 96 158 377 3 29 100 158 | 0 96 159 377 4 30 97 159 | 0 93 160 383 4 30 98 160 | 0 95 161 382 4 31 97 161 | 0 96 162 383 4 30 97 162 | 0 96 163 384 4 30 97 163 | 0 96 164 383 4 32 98 164 | 0 81 165 383 5 32 92 165 | 0 75 166 384 6 31 90 166 | 0 76 167 384 7 32 93 167 | 0 70 168 384 7 31 89 168 | 0 74 169 384 7 32 89 169 | 0 70 170 384 7 32 89 170 | 0 87 171 384 5 32 96 171 | 0 90 172 384 5 31 93 172 | 0 95 173 385 5 30 90 173 | 0 95 174 384 5 31 92 174 | 0 90 175 386 6 30 91 175 | 0 86 176 385 6 30 88 176 | 0 89 177 383 2 33 85 177 | 0 92 178 383 1 33 87 178 | 0 93 179 383 1 35 86 179 | 0 93 180 385 3 31 95 180 | 0 91 181 385 3 33 83 181 | 0 90 182 387 3 30 84 182 | 0 94 183 389 3 28 96 183 | 0 93 184 389 0 28 88 184 | 0 96 185 389 1 29 82 185 | 0 90 186 389 0 30 80 186 | 0 86 187 389 0 29 80 187 | 0 93 188 389 1 31 78 188 | 0 85 189 388 0 31 79 189 | 0 94 190 389 1 30 78 190 | 0 92 191 389 0 30 78 191 | 0 94 192 388 0 30 78 192 | 0 94 193 388 0 29 81 193 | 0 96 194 389 0 28 84 194 | 0 95 195 388 0 30 85 195 | 0 95 196 388 0 30 84 196 | 0 97 197 389 0 29 82 197 | 0 98 198 389 0 29 81 198 | 0 98 199 389 0 28 83 199 | 0 98 200 390 0 28 83 200 | 0 98 201 390 0 28 80 201 | 0 97 202 391 0 28 78 202 | 0 97 203 392 0 28 78 203 | 0 96 204 393 0 28 78 204 | 0 80 205 394 0 29 75 205 | 0 63 206 393 0 29 74 206 | 0 57 207 393 0 30 74 207 | 0 84 208 393 0 30 74 208 | 0 78 209 393 0 30 74 209 | 0 88 210 393 0 30 74 210 | 0 88 211 393 0 30 74 211 | 0 92 212 393 0 30 76 212 | 0 96 213 394 0 29 76 213 | 0 95 214 394 0 28 77 214 | 0 97 215 395 0 28 76 215 | 0 98 216 395 0 28 76 216 | 0 98 217 395 0 28 77 217 | 0 98 218 395 0 28 76 218 | 0 98 219 395 0 29 76 219 | 0 96 220 396 0 28 74 220 | 0 97 221 397 0 27 73 221 | 0 96 222 398 0 27 74 222 | 0 97 223 398 0 27 75 223 | 0 96 224 398 0 26 75 224 | 0 87 225 399 0 26 74 225 | 0 90 226 398 0 27 74 226 | 0 85 227 399 0 27 74 227 | 0 95 228 398 0 27 75 228 | 0 95 229 398 0 27 75 229 | 0 98 230 398 0 27 75 230 | 0 98 231 398 0 26 75 231 | 0 98 232 398 0 27 76 232 | 0 98 233 398 0 27 76 233 | 0 97 234 398 0 28 75 234 | 0 97 235 397 0 28 72 235 | 0 97 236 397 0 28 73 236 | 0 95 237 397 0 28 74 237 | 0 93 238 396 0 28 74 238 | 0 94 239 397 0 28 73 239 | 0 95 240 398 0 27 71 240 | 0 95 241 398 0 27 72 241 | 0 92 242 398 0 27 71 242 | 0 92 243 399 0 27 72 243 | 0 92 244 403 0 25 70 244 | 0 90 245 403 0 25 69 245 | 0 90 246 403 0 25 69 246 | 0 69 247 404 0 23 69 247 | 0 64 248 404 0 24 71 248 | 0 67 249 404 0 24 72 249 | 0 71 250 404 0 24 72 250 | 0 75 251 403 0 27 58 251 | 0 69 252 403 0 25 72 252 | 0 48 253 404 0 24 72 253 | 0 59 254 404 0 25 76 254 | 0 79 255 404 0 26 73 255 | 0 62 256 405 0 25 74 256 | 0 82 257 403 0 28 59 257 | 0 93 258 403 0 27 62 258 | 0 95 259 403 0 28 62 259 | 0 95 260 407 0 25 65 260 | 0 90 261 407 0 24 63 261 | 0 90 262 408 0 26 70 262 | 0 91 263 408 0 27 71 263 | 0 92 264 408 0 28 70 264 | 0 90 265 409 0 27 70 265 | 0 92 266 409 0 27 69 266 | 0 71 267 410 0 26 66 267 | 0 67 268 411 0 26 66 268 | 0 51 269 411 0 25 66 269 | 0 52 270 411 0 25 65 270 | 0 48 271 411 0 25 65 271 | 0 61 272 412 0 24 67 272 | 0 57 273 412 0 21 59 273 | 0 42 274 415 0 19 65 274 | 0 61 275 414 0 23 66 275 | 0 80 276 415 0 19 67 276 | 0 72 277 415 0 18 65 277 | 0 54 278 414 0 24 65 278 | 0 41 279 414 0 23 65 279 | 0 30 280 414 0 24 65 280 | 0 27 281 415 0 23 66 281 | 0 71 282 414 0 26 67 282 | 0 65 283 414 0 26 69 283 | 0 71 284 414 0 26 68 284 | 0 65 285 414 0 26 67 285 | 0 26 286 414 0 26 64 286 | 0 35 287 414 0 26 66 287 | 0 71 288 414 0 27 68 288 | 0 66 289 414 0 27 67 289 | 0 51 290 414 0 28 66 290 | 0 89 291 414 0 30 69 291 | 0 93 292 414 0 29 62 292 | 0 92 293 415 0 31 73 293 | 0 89 294 416 0 31 72 294 | 0 85 295 417 0 29 69 295 | 0 86 296 417 0 29 69 296 | 0 83 297 419 0 30 62 297 | 0 72 298 420 0 29 66 298 | 0 78 299 421 0 28 61 299 | 0 50 300 422 0 28 59 300 | 0 44 305 428 0 25 59 301 | 0 41 306 426 1 30 65 302 | 0 48 307 426 1 30 65 303 | 0 65 308 432 0 23 63 304 | 0 75 309 431 0 24 62 305 | 0 35 310 429 0 29 58 306 | 0 75 314 431 0 30 67 307 | 0 68 315 432 0 31 66 308 | 0 70 316 433 0 32 71 309 | 0 77 317 434 0 31 70 310 | 0 77 318 435 0 30 68 311 | 0 82 319 439 0 27 71 312 | 0 82 320 439 0 28 70 313 | 0 78 321 439 0 28 69 314 | 0 79 322 441 0 27 69 315 | 0 87 323 442 0 27 69 316 | 0 87 324 442 0 27 70 317 | 0 78 325 443 0 27 71 318 | 0 37 326 442 0 29 73 319 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | GNU GENERAL PUBLIC LICENSE 2 | Version 2, June 1991 3 | 4 | Copyright (C) 1989, 1991 Free Software Foundation, Inc., 5 | 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA 6 | Everyone is permitted to copy and distribute verbatim copies 7 | of this license document, but changing it is not allowed. 8 | 9 | Preamble 10 | 11 | The licenses for most software are designed to take away your 12 | freedom to share and change it. By contrast, the GNU General Public 13 | License is intended to guarantee your freedom to share and change free 14 | software--to make sure the software is free for all its users. This 15 | General Public License applies to most of the Free Software 16 | Foundation's software and to any other program whose authors commit to 17 | using it. (Some other Free Software Foundation software is covered by 18 | the GNU Lesser General Public License instead.) You can apply it to 19 | your programs, too. 20 | 21 | When we speak of free software, we are referring to freedom, not 22 | price. Our General Public Licenses are designed to make sure that you 23 | have the freedom to distribute copies of free software (and charge for 24 | this service if you wish), that you receive source code or can get it 25 | if you want it, that you can change the software or use pieces of it 26 | in new free programs; and that you know you can do these things. 27 | 28 | To protect your rights, we need to make restrictions that forbid 29 | anyone to deny you these rights or to ask you to surrender the rights. 30 | These restrictions translate to certain responsibilities for you if you 31 | distribute copies of the software, or if you modify it. 32 | 33 | For example, if you distribute copies of such a program, whether 34 | gratis or for a fee, you must give the recipients all the rights that 35 | you have. You must make sure that they, too, receive or can get the 36 | source code. And you must show them these terms so they know their 37 | rights. 38 | 39 | We protect your rights with two steps: (1) copyright the software, and 40 | (2) offer you this license which gives you legal permission to copy, 41 | distribute and/or modify the software. 42 | 43 | Also, for each author's protection and ours, we want to make certain 44 | that everyone understands that there is no warranty for this free 45 | software. If the software is modified by someone else and passed on, we 46 | want its recipients to know that what they have is not the original, so 47 | that any problems introduced by others will not reflect on the original 48 | authors' reputations. 49 | 50 | Finally, any free program is threatened constantly by software 51 | patents. We wish to avoid the danger that redistributors of a free 52 | program will individually obtain patent licenses, in effect making the 53 | program proprietary. To prevent this, we have made it clear that any 54 | patent must be licensed for everyone's free use or not licensed at all. 55 | 56 | The precise terms and conditions for copying, distribution and 57 | modification follow. 58 | 59 | GNU GENERAL PUBLIC LICENSE 60 | TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION 61 | 62 | 0. This License applies to any program or other work which contains 63 | a notice placed by the copyright holder saying it may be distributed 64 | under the terms of this General Public License. The "Program", below, 65 | refers to any such program or work, and a "work based on the Program" 66 | means either the Program or any derivative work under copyright law: 67 | that is to say, a work containing the Program or a portion of it, 68 | either verbatim or with modifications and/or translated into another 69 | language. (Hereinafter, translation is included without limitation in 70 | the term "modification".) Each licensee is addressed as "you". 71 | 72 | Activities other than copying, distribution and modification are not 73 | covered by this License; they are outside its scope. The act of 74 | running the Program is not restricted, and the output from the Program 75 | is covered only if its contents constitute a work based on the 76 | Program (independent of having been made by running the Program). 77 | Whether that is true depends on what the Program does. 78 | 79 | 1. You may copy and distribute verbatim copies of the Program's 80 | source code as you receive it, in any medium, provided that you 81 | conspicuously and appropriately publish on each copy an appropriate 82 | copyright notice and disclaimer of warranty; keep intact all the 83 | notices that refer to this License and to the absence of any warranty; 84 | and give any other recipients of the Program a copy of this License 85 | along with the Program. 86 | 87 | You may charge a fee for the physical act of transferring a copy, and 88 | you may at your option offer warranty protection in exchange for a fee. 89 | 90 | 2. You may modify your copy or copies of the Program or any portion 91 | of it, thus forming a work based on the Program, and copy and 92 | distribute such modifications or work under the terms of Section 1 93 | above, provided that you also meet all of these conditions: 94 | 95 | a) You must cause the modified files to carry prominent notices 96 | stating that you changed the files and the date of any change. 97 | 98 | b) You must cause any work that you distribute or publish, that in 99 | whole or in part contains or is derived from the Program or any 100 | part thereof, to be licensed as a whole at no charge to all third 101 | parties under the terms of this License. 102 | 103 | c) If the modified program normally reads commands interactively 104 | when run, you must cause it, when started running for such 105 | interactive use in the most ordinary way, to print or display an 106 | announcement including an appropriate copyright notice and a 107 | notice that there is no warranty (or else, saying that you provide 108 | a warranty) and that users may redistribute the program under 109 | these conditions, and telling the user how to view a copy of this 110 | License. (Exception: if the Program itself is interactive but 111 | does not normally print such an announcement, your work based on 112 | the Program is not required to print an announcement.) 113 | 114 | These requirements apply to the modified work as a whole. If 115 | identifiable sections of that work are not derived from the Program, 116 | and can be reasonably considered independent and separate works in 117 | themselves, then this License, and its terms, do not apply to those 118 | sections when you distribute them as separate works. But when you 119 | distribute the same sections as part of a whole which is a work based 120 | on the Program, the distribution of the whole must be on the terms of 121 | this License, whose permissions for other licensees extend to the 122 | entire whole, and thus to each and every part regardless of who wrote it. 123 | 124 | Thus, it is not the intent of this section to claim rights or contest 125 | your rights to work written entirely by you; rather, the intent is to 126 | exercise the right to control the distribution of derivative or 127 | collective works based on the Program. 128 | 129 | In addition, mere aggregation of another work not based on the Program 130 | with the Program (or with a work based on the Program) on a volume of 131 | a storage or distribution medium does not bring the other work under 132 | the scope of this License. 133 | 134 | 3. You may copy and distribute the Program (or a work based on it, 135 | under Section 2) in object code or executable form under the terms of 136 | Sections 1 and 2 above provided that you also do one of the following: 137 | 138 | a) Accompany it with the complete corresponding machine-readable 139 | source code, which must be distributed under the terms of Sections 140 | 1 and 2 above on a medium customarily used for software interchange; or, 141 | 142 | b) Accompany it with a written offer, valid for at least three 143 | years, to give any third party, for a charge no more than your 144 | cost of physically performing source distribution, a complete 145 | machine-readable copy of the corresponding source code, to be 146 | distributed under the terms of Sections 1 and 2 above on a medium 147 | customarily used for software interchange; or, 148 | 149 | c) Accompany it with the information you received as to the offer 150 | to distribute corresponding source code. (This alternative is 151 | allowed only for noncommercial distribution and only if you 152 | received the program in object code or executable form with such 153 | an offer, in accord with Subsection b above.) 154 | 155 | The source code for a work means the preferred form of the work for 156 | making modifications to it. For an executable work, complete source 157 | code means all the source code for all modules it contains, plus any 158 | associated interface definition files, plus the scripts used to 159 | control compilation and installation of the executable. However, as a 160 | special exception, the source code distributed need not include 161 | anything that is normally distributed (in either source or binary 162 | form) with the major components (compiler, kernel, and so on) of the 163 | operating system on which the executable runs, unless that component 164 | itself accompanies the executable. 165 | 166 | If distribution of executable or object code is made by offering 167 | access to copy from a designated place, then offering equivalent 168 | access to copy the source code from the same place counts as 169 | distribution of the source code, even though third parties are not 170 | compelled to copy the source along with the object code. 171 | 172 | 4. You may not copy, modify, sublicense, or distribute the Program 173 | except as expressly provided under this License. Any attempt 174 | otherwise to copy, modify, sublicense or distribute the Program is 175 | void, and will automatically terminate your rights under this License. 176 | However, parties who have received copies, or rights, from you under 177 | this License will not have their licenses terminated so long as such 178 | parties remain in full compliance. 179 | 180 | 5. You are not required to accept this License, since you have not 181 | signed it. However, nothing else grants you permission to modify or 182 | distribute the Program or its derivative works. These actions are 183 | prohibited by law if you do not accept this License. Therefore, by 184 | modifying or distributing the Program (or any work based on the 185 | Program), you indicate your acceptance of this License to do so, and 186 | all its terms and conditions for copying, distributing or modifying 187 | the Program or works based on it. 188 | 189 | 6. Each time you redistribute the Program (or any work based on the 190 | Program), the recipient automatically receives a license from the 191 | original licensor to copy, distribute or modify the Program subject to 192 | these terms and conditions. You may not impose any further 193 | restrictions on the recipients' exercise of the rights granted herein. 194 | You are not responsible for enforcing compliance by third parties to 195 | this License. 196 | 197 | 7. If, as a consequence of a court judgment or allegation of patent 198 | infringement or for any other reason (not limited to patent issues), 199 | conditions are imposed on you (whether by court order, agreement or 200 | otherwise) that contradict the conditions of this License, they do not 201 | excuse you from the conditions of this License. If you cannot 202 | distribute so as to satisfy simultaneously your obligations under this 203 | License and any other pertinent obligations, then as a consequence you 204 | may not distribute the Program at all. For example, if a patent 205 | license would not permit royalty-free redistribution of the Program by 206 | all those who receive copies directly or indirectly through you, then 207 | the only way you could satisfy both it and this License would be to 208 | refrain entirely from distribution of the Program. 209 | 210 | If any portion of this section is held invalid or unenforceable under 211 | any particular circumstance, the balance of the section is intended to 212 | apply and the section as a whole is intended to apply in other 213 | circumstances. 214 | 215 | It is not the purpose of this section to induce you to infringe any 216 | patents or other property right claims or to contest validity of any 217 | such claims; this section has the sole purpose of protecting the 218 | integrity of the free software distribution system, which is 219 | implemented by public license practices. Many people have made 220 | generous contributions to the wide range of software distributed 221 | through that system in reliance on consistent application of that 222 | system; it is up to the author/donor to decide if he or she is willing 223 | to distribute software through any other system and a licensee cannot 224 | impose that choice. 225 | 226 | This section is intended to make thoroughly clear what is believed to 227 | be a consequence of the rest of this License. 228 | 229 | 8. If the distribution and/or use of the Program is restricted in 230 | certain countries either by patents or by copyrighted interfaces, the 231 | original copyright holder who places the Program under this License 232 | may add an explicit geographical distribution limitation excluding 233 | those countries, so that distribution is permitted only in or among 234 | countries not thus excluded. In such case, this License incorporates 235 | the limitation as if written in the body of this License. 236 | 237 | 9. The Free Software Foundation may publish revised and/or new versions 238 | of the General Public License from time to time. Such new versions will 239 | be similar in spirit to the present version, but may differ in detail to 240 | address new problems or concerns. 241 | 242 | Each version is given a distinguishing version number. If the Program 243 | specifies a version number of this License which applies to it and "any 244 | later version", you have the option of following the terms and conditions 245 | either of that version or of any later version published by the Free 246 | Software Foundation. If the Program does not specify a version number of 247 | this License, you may choose any version ever published by the Free Software 248 | Foundation. 249 | 250 | 10. If you wish to incorporate parts of the Program into other free 251 | programs whose distribution conditions are different, write to the author 252 | to ask for permission. For software which is copyrighted by the Free 253 | Software Foundation, write to the Free Software Foundation; we sometimes 254 | make exceptions for this. Our decision will be guided by the two goals 255 | of preserving the free status of all derivatives of our free software and 256 | of promoting the sharing and reuse of software generally. 257 | 258 | NO WARRANTY 259 | 260 | 11. BECAUSE THE PROGRAM IS LICENSED FREE OF CHARGE, THERE IS NO WARRANTY 261 | FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN 262 | OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES 263 | PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED 264 | OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF 265 | MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS 266 | TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE 267 | PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING, 268 | REPAIR OR CORRECTION. 269 | 270 | 12. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING 271 | WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY AND/OR 272 | REDISTRIBUTE THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, 273 | INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING 274 | OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED 275 | TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY 276 | YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER 277 | PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE 278 | POSSIBILITY OF SUCH DAMAGES. 279 | 280 | END OF TERMS AND CONDITIONS 281 | 282 | How to Apply These Terms to Your New Programs 283 | 284 | If you develop a new program, and you want it to be of the greatest 285 | possible use to the public, the best way to achieve this is to make it 286 | free software which everyone can redistribute and change under these terms. 287 | 288 | To do so, attach the following notices to the program. It is safest 289 | to attach them to the start of each source file to most effectively 290 | convey the exclusion of warranty; and each file should have at least 291 | the "copyright" line and a pointer to where the full notice is found. 292 | 293 | Copyright (C) 2019 Micaela Verucchi 294 | 295 | This program is free software; you can redistribute it and/or modify 296 | it under the terms of the GNU General Public License as published by 297 | the Free Software Foundation; either version 2 of the License, or 298 | (at your option) any later version. 299 | 300 | This program is distributed in the hope that it will be useful, 301 | but WITHOUT ANY WARRANTY; without even the implied warranty of 302 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 303 | GNU General Public License for more details. 304 | 305 | You should have received a copy of the GNU General Public License along 306 | with this program; if not, write to the Free Software Foundation, Inc., 307 | 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. 308 | 309 | Also add information on how to contact you by electronic and paper mail. 310 | 311 | If the program is interactive, make it output a short notice like this 312 | when it starts in an interactive mode: 313 | 314 | Gnomovision version 69, Copyright (C) year name of author 315 | Gnomovision comes with ABSOLUTELY NO WARRANTY; for details type `show w'. 316 | This is free software, and you are welcome to redistribute it 317 | under certain conditions; type `show c' for details. 318 | 319 | The hypothetical commands `show w' and `show c' should show the appropriate 320 | parts of the General Public License. Of course, the commands you use may 321 | be called something other than `show w' and `show c'; they could even be 322 | mouse-clicks or menu items--whatever suits your program. 323 | 324 | You should also get your employer (if you work as a programmer) or your 325 | school, if any, to sign a "copyright disclaimer" for the program, if 326 | necessary. Here is a sample; alter the names: 327 | 328 | Yoyodyne, Inc., hereby disclaims all copyright interest in the program 329 | `Gnomovision' (which makes passes at compilers) written by James Hacker. 330 | 331 | , 1 April 1989 332 | Ty Coon, President of Vice 333 | 334 | This General Public License does not permit incorporating your program into 335 | proprietary programs. If your program is a subroutine library, you may 336 | consider it more useful to permit linking proprietary applications with the 337 | library. If this is what you want to do, use the GNU Lesser General 338 | Public License instead of this License. 339 | -------------------------------------------------------------------------------- /data/prova_pixel.txt: -------------------------------------------------------------------------------- 1 | 0 1552037227036 1890 1010 2 | 0 1552037227036 2172 970 3 | 0 1552037227036 2108 1052 4 | 0 1552037227036 2055 986 5 | 1 1552037227066 1879 997 6 | 1 1552037227066 2108 1052 7 | 1 1552037227066 2175 969 8 | 1 1552037227066 2055 986 9 | 1 1552037227066 2187 1203 10 | 2 1552037227096 1878 996 11 | 2 1552037227096 2108 1052 12 | 2 1552037227096 2147 961 13 | 2 1552037227096 2055 986 14 | 2 1552037227096 2188 1202 15 | 3 1552037227134 1880 995 16 | 3 1552037227134 2108 1052 17 | 3 1552037227134 2151 961 18 | 3 1552037227134 2055 986 19 | 3 1552037227134 2186 1203 20 | 4 1552037227167 1882 996 21 | 4 1552037227167 2108 1052 22 | 4 1552037227167 2055 986 23 | 5 1552037227202 1890 1006 24 | 5 1552037227202 2108 1052 25 | 5 1552037227202 2055 986 26 | 6 1552037227232 1897 1013 27 | 6 1552037227232 2108 1052 28 | 6 1552037227232 2055 986 29 | 6 1552037227232 2155 956 30 | 7 1552037227264 1898 1014 31 | 7 1552037227264 2108 1052 32 | 7 1552037227264 2147 953 33 | 7 1552037227264 2055 986 34 | 7 1552037227264 2188 1202 35 | 8 1552037227298 1899 1013 36 | 8 1552037227298 2108 1052 37 | 8 1552037227298 2055 986 38 | 8 1552037227298 2151 951 39 | 8 1552037227298 2189 1202 40 | 9 1552037227323 1899 1013 41 | 9 1552037227323 2108 1052 42 | 9 1552037227323 2055 986 43 | 10 1552037227352 1900 1013 44 | 10 1552037227352 2108 1052 45 | 10 1552037227352 2055 986 46 | 11 1552037227383 1900 1012 47 | 11 1552037227383 2108 1052 48 | 11 1552037227383 2055 986 49 | 11 1552037227383 2195 1208 50 | 12 1552037227411 1901 1012 51 | 12 1552037227411 2108 1052 52 | 12 1552037227411 2194 1209 53 | 12 1552037227411 2055 986 54 | 12 1552037227411 2220 1231 55 | 13 1552037227449 1902 1014 56 | 13 1552037227449 2108 1052 57 | 13 1552037227449 2152 943 58 | 13 1552037227449 2194 1209 59 | 13 1552037227449 2055 986 60 | 14 1552037227479 1905 1015 61 | 14 1552037227479 2108 1052 62 | 14 1552037227479 2153 942 63 | 14 1552037227479 2055 986 64 | 14 1552037227479 2194 1209 65 | 15 1552037227511 1907 1017 66 | 15 1552037227511 2108 1052 67 | 15 1552037227511 2055 986 68 | 15 1552037227511 2194 1209 69 | 16 1552037227544 1877 985 70 | 16 1552037227544 2112 1055 71 | 16 1552037227544 2055 986 72 | 16 1552037227544 2194 1209 73 | 17 1552037227572 1879 987 74 | 17 1552037227572 1905 1014 75 | 17 1552037227572 2108 1052 76 | 17 1552037227572 2194 1209 77 | 17 1552037227572 2055 986 78 | 18 1552037227597 1880 987 79 | 18 1552037227597 2108 1052 80 | 18 1552037227597 2193 1209 81 | 18 1552037227597 2055 986 82 | 18 1552037227597 2119 930 83 | 19 1552037227627 1903 1009 84 | 19 1552037227627 2108 1052 85 | 19 1552037227627 2193 1209 86 | 19 1552037227627 2055 986 87 | 19 1552037227627 2113 928 88 | 20 1552037227656 1882 988 89 | 20 1552037227656 2108 1052 90 | 20 1552037227656 2055 986 91 | 20 1552037227656 2114 928 92 | 20 1552037227656 2193 1209 93 | 21 1552037227691 1906 1011 94 | 21 1552037227691 2108 1052 95 | 21 1552037227691 2055 986 96 | 21 1552037227691 2194 1209 97 | 22 1552037227721 1909 1013 98 | 22 1552037227721 2108 1052 99 | 22 1552037227721 2055 986 100 | 22 1552037227721 2193 1209 101 | 23 1552037227759 1907 1010 102 | 23 1552037227759 2108 1052 103 | 23 1552037227759 2055 986 104 | 23 1552037227759 2193 1209 105 | 24 1552037227789 2112 1055 106 | 24 1552037227789 1910 1011 107 | 24 1552037227789 2055 986 108 | 24 1552037227789 2193 1209 109 | 25 1552037227825 2112 1055 110 | 25 1552037227825 2055 986 111 | 25 1552037227825 2193 1209 112 | 25 1552037227825 1914 1014 113 | 26 1552037227852 2112 1055 114 | 26 1552037227852 1886 986 115 | 26 1552037227852 2055 986 116 | 26 1552037227852 2193 1209 117 | 27 1552037227877 1884 985 118 | 27 1552037227877 2112 1055 119 | 27 1552037227877 2055 986 120 | 27 1552037227877 2193 1209 121 | 28 1552037227905 1887 986 122 | 28 1552037227905 2108 1052 123 | 28 1552037227905 2193 1209 124 | 28 1552037227905 2055 986 125 | 29 1552037227936 1890 987 126 | 29 1552037227936 2108 1052 127 | 29 1552037227936 2193 1209 128 | 29 1552037227936 2055 986 129 | 30 1552037227967 1916 1012 130 | 30 1552037227967 2112 1055 131 | 30 1552037227967 2193 1209 132 | 30 1552037227967 2055 986 133 | 31 1552037227997 1915 1010 134 | 31 1552037227997 2108 1052 135 | 31 1552037227997 2193 1209 136 | 31 1552037227997 2055 986 137 | 32 1552037228028 1932 1023 138 | 32 1552037228028 2108 1052 139 | 32 1552037228028 2055 986 140 | 33 1552037228063 1930 1022 141 | 33 1552037228063 2108 1052 142 | 33 1552037228063 2055 986 143 | 33 1552037228063 2193 1209 144 | 34 1552037228092 1919 1011 145 | 34 1552037228092 2126 1064 146 | 34 1552037228092 2055 986 147 | 34 1552037228092 2193 1209 148 | 35 1552037228126 1919 1009 149 | 35 1552037228126 2126 1064 150 | 35 1552037228126 2055 986 151 | 35 1552037228126 2193 1209 152 | 36 1552037228154 1921 1010 153 | 36 1552037228154 2126 1064 154 | 36 1552037228154 2055 986 155 | 36 1552037228154 2193 1209 156 | 37 1552037228182 1922 1009 157 | 37 1552037228182 2126 1064 158 | 37 1552037228182 2193 1209 159 | 37 1552037228182 2055 986 160 | 38 1552037228212 1929 1016 161 | 38 1552037228212 2108 1052 162 | 38 1552037228212 2193 1209 163 | 38 1552037228212 2055 986 164 | 39 1552037228248 1924 1010 165 | 39 1552037228248 2126 1064 166 | 39 1552037228248 2055 986 167 | 39 1552037228248 2193 1209 168 | 40 1552037228278 1936 1018 169 | 40 1552037228278 2126 1064 170 | 40 1552037228278 2193 1209 171 | 40 1552037228278 2055 986 172 | 41 1552037228314 1923 1007 173 | 41 1552037228314 2126 1064 174 | 41 1552037228314 2055 986 175 | 41 1552037228314 2193 1209 176 | 42 1552037228343 1934 1015 177 | 42 1552037228343 2126 1064 178 | 42 1552037228343 2193 1209 179 | 42 1552037228343 2055 986 180 | 43 1552037228380 1935 1014 181 | 43 1552037228380 2126 1064 182 | 43 1552037228380 2055 986 183 | 43 1552037228380 2193 1209 184 | 44 1552037228408 1934 1012 185 | 44 1552037228408 2126 1064 186 | 44 1552037228408 2056 986 187 | 44 1552037228408 2193 1209 188 | 45 1552037228433 1936 1014 189 | 45 1552037228433 2126 1064 190 | 45 1552037228433 2056 986 191 | 45 1552037228433 2193 1209 192 | 46 1552037228461 1940 1016 193 | 46 1552037228461 2126 1064 194 | 46 1552037228461 2193 1209 195 | 46 1552037228461 2056 986 196 | 47 1552037228492 1939 1015 197 | 47 1552037228492 2126 1064 198 | 48 1552037228526 1940 1014 199 | 48 1552037228526 2126 1064 200 | 48 1552037228526 2056 986 201 | 48 1552037228526 2193 1209 202 | 49 1552037228555 2126 1064 203 | 49 1552037228555 1939 1012 204 | 49 1552037228555 1905 982 205 | 49 1552037228555 2056 986 206 | 49 1552037228555 2193 1209 207 | 50 1552037228587 1906 981 208 | 50 1552037228587 2126 1064 209 | 50 1552037228587 1945 1016 210 | 50 1552037228587 2193 1209 211 | 50 1552037228587 2056 986 212 | 51 1552037228621 2126 1064 213 | 52 1552037228650 1906 980 214 | 52 1552037228650 2126 1064 215 | 52 1552037228650 2056 986 216 | 52 1552037228650 2193 1209 217 | 53 1552037228686 1943 1012 218 | 53 1552037228686 2126 1064 219 | 53 1552037228686 2056 986 220 | 53 1552037228686 1908 982 221 | 53 1552037228686 2193 1209 222 | 54 1552037228709 1942 1010 223 | 54 1552037228709 2126 1064 224 | 54 1552037228709 2056 986 225 | 54 1552037228709 2193 1209 226 | 54 1552037228709 1909 983 227 | 55 1552037228738 1942 1010 228 | 55 1552037228738 2126 1064 229 | 55 1552037228738 2056 986 230 | 55 1552037228738 2193 1209 231 | 56 1552037228766 1942 1008 232 | 56 1552037228766 2126 1064 233 | 56 1552037228766 2056 986 234 | 56 1552037228766 2193 1209 235 | 57 1552037228796 1944 1009 236 | 57 1552037228796 2126 1064 237 | 57 1552037228796 2056 986 238 | 57 1552037228796 2193 1209 239 | 58 1552037228832 1948 1011 240 | 58 1552037228832 2126 1064 241 | 58 1552037228832 2056 986 242 | 58 1552037228832 2193 1209 243 | 59 1552037228862 1950 1012 244 | 59 1552037228862 2126 1064 245 | 59 1552037228862 2194 1209 246 | 59 1552037228862 2059 987 247 | 60 1552037228893 1951 1012 248 | 60 1552037228893 2126 1064 249 | 60 1552037228893 2056 986 250 | 60 1552037228893 2194 1209 251 | 61 1552037228925 1949 1009 252 | 61 1552037228925 2126 1064 253 | 61 1552037228925 2056 986 254 | 61 1552037228925 2194 1209 255 | 62 1552037228954 1946 1005 256 | 62 1552037228954 2125 1064 257 | 62 1552037228954 2194 1209 258 | 63 1552037228983 1956 1013 259 | 63 1552037228983 2126 1064 260 | 63 1552037228983 2194 1209 261 | 63 1552037228983 2059 987 262 | 64 1552037229010 1956 1012 263 | 65 1552037229040 1930 989 264 | 65 1552037229040 2126 1064 265 | 65 1552037229040 2059 987 266 | 66 1552037229071 2126 1064 267 | 67 1552037229231 1933 989 268 | 67 1552037229231 1879 1330 269 | 67 1552037229231 2126 1064 270 | 68 1552037229259 1935 990 271 | 68 1552037229259 2126 1064 272 | 69 1552037229289 1930 987 273 | 69 1552037229289 2126 1064 274 | 69 1552037229289 2058 988 275 | 70 1552037229324 1956 1006 276 | 70 1552037229324 2126 1064 277 | 70 1552037229324 2058 988 278 | 70 1552037229324 2194 1209 279 | 71 1552037229358 1956 1006 280 | 71 1552037229358 2126 1064 281 | 71 1552037229358 2058 988 282 | 71 1552037229358 2194 1209 283 | 72 1552037229390 1959 1007 284 | 72 1552037229390 2126 1064 285 | 72 1552037229390 2058 988 286 | 73 1552037229420 1956 1004 287 | 74 1552037229456 1974 1016 288 | 74 1552037229456 2126 1064 289 | 74 1552037229456 2058 988 290 | 75 1552037229486 1975 1016 291 | 76 1552037229507 1924 977 292 | 76 1552037229507 1975 1015 293 | 76 1552037229507 2058 988 294 | 77 1552037229539 1927 978 295 | 77 1552037229539 2059 987 296 | 77 1552037229539 2126 1064 297 | 78 1552037229568 1955 998 298 | 78 1552037229568 2058 988 299 | 78 1552037229568 2126 1064 300 | 78 1552037229568 1885 1327 301 | 79 1552037229598 1953 997 302 | 79 1552037229598 2058 988 303 | 79 1552037229598 2126 1064 304 | 80 1552037229634 1976 1012 305 | 80 1552037229634 2058 988 306 | 80 1552037229634 2126 1064 307 | 81 1552037229664 1957 999 308 | 81 1552037229664 2058 988 309 | 81 1552037229664 2126 1064 310 | 82 1552037229700 1975 1010 311 | 82 1552037229700 2058 988 312 | 83 1552037229729 1975 1010 313 | 83 1552037229729 2058 988 314 | 84 1552037229762 1960 999 315 | 85 1552037229789 1973 1008 316 | 86 1552037229820 1979 1011 317 | 86 1552037229820 2372 993 318 | 86 1552037229820 2058 988 319 | 87 1552037229847 1982 1011 320 | 88 1552037229877 1982 1011 321 | 88 1552037229878 2058 988 322 | 88 1552037229878 2126 1064 323 | 89 1552037229912 1982 1011 324 | 90 1552037229944 1985 1012 325 | 91 1552037229971 1984 1010 326 | 91 1552037229971 2059 987 327 | 92 1552037230007 1984 1010 328 | 93 1552037230037 1985 1010 329 | 93 1552037230037 2059 987 330 | 94 1552037230064 1984 1008 331 | 94 1552037230064 2059 987 332 | 95 1552037230094 1984 1008 333 | 95 1552037230094 2058 988 334 | 96 1552037230122 1984 1008 335 | 97 1552037230151 1988 1008 336 | 97 1552037230151 2055 986 337 | 97 1552037230151 2194 1209 338 | 98 1552037230188 1986 1007 339 | 98 1552037230188 2055 986 340 | 98 1552037230188 2108 1052 341 | 98 1552037230188 2194 1209 342 | 99 1552037230217 1989 1007 343 | 99 1552037230217 2055 986 344 | 99 1552037230217 2108 1052 345 | 100 1552037230249 1987 1006 346 | 100 1552037230249 2055 986 347 | 100 1552037230249 2108 1052 348 | 101 1552037230283 1990 1006 349 | 101 1552037230283 2108 1052 350 | 101 1552037230283 2055 986 351 | 102 1552037230316 1991 1006 352 | 102 1552037230316 2055 986 353 | 102 1552037230316 2108 1052 354 | 103 1552037230343 1994 1007 355 | 103 1552037230343 2055 986 356 | 104 1552037230366 2002 1011 357 | 105 1552037230396 2004 1013 358 | 105 1552037230396 2055 986 359 | 105 1552037230396 2126 1064 360 | 106 1552037230427 1958 981 361 | 106 1552037230427 1997 1008 362 | 106 1552037230427 2055 986 363 | 107 1552037230458 1994 1004 364 | 107 1552037230458 1957 980 365 | 107 1552037230458 2055 986 366 | 112 1552037230620 2001 1005 367 | 114 1552037230673 1988 987 368 | 115 1552037230702 1986 988 369 | 115 1552037230702 2004 1004 370 | 116 1552037230737 1990 989 371 | 116 1552037230737 2007 1005 372 | 116 1552037230737 2193 1209 373 | 117 1552037230769 1993 990 374 | 118 1552037230803 1990 988 375 | 118 1552037230803 2007 1002 376 | 118 1552037230803 2193 1209 377 | 119 1552037230832 1987 986 378 | 119 1552037230832 2001 998 379 | 119 1552037230832 2193 1209 380 | 119 1552037230832 2535 1113 381 | 120 1552037230864 1989 987 382 | 120 1552037230864 2194 1209 383 | 121 1552037230901 1992 988 384 | 121 1552037230901 2194 1209 385 | 122 1552037230931 1991 986 386 | 122 1552037230931 2193 1209 387 | 123 1552037230958 1991 986 388 | 123 1552037230958 2194 1209 389 | 124 1552037230989 1994 986 390 | 124 1552037230989 2194 1209 391 | 125 1552037231022 1994 986 392 | 125 1552037231022 2194 1209 393 | 126 1552037231055 1996 988 394 | 126 1552037231055 2194 1209 395 | 127 1552037231087 1993 987 396 | 128 1552037231123 2018 1002 397 | 129 1552037231155 2021 1003 398 | 130 1552037231182 2026 1006 399 | 132 1552037231232 2030 1007 400 | 133 1552037231266 2034 1008 401 | 135 1552037231459 2038 1009 402 | 136 1552037231488 2033 1005 403 | 137 1552037231522 2033 1005 404 | 138 1552037231552 2033 1005 405 | 139 1552037231582 2034 1004 406 | 140 1552037231618 2684 1232 407 | 140 1552037231618 2038 1006 408 | 141 1552037231649 2032 1003 409 | 141 1552037231649 2645 1224 410 | 142 1552037231677 2041 1007 411 | 143 1552037231709 2035 1004 412 | 144 1552037231740 2039 1005 413 | 145 1552037231773 2042 1006 414 | 146 1552037231804 2040 1005 415 | 147 1552037231837 2040 1005 416 | 148 1552037231870 2044 1005 417 | 149 1552037231898 2047 1007 418 | 150 1552037231937 2046 1008 419 | 151 1552037231968 2048 1007 420 | 158 1552037232184 2052 1004 421 | 158 1552037232184 2059 987 422 | 159 1552037232219 2053 1004 423 | 160 1552037232247 2057 1005 424 | 161 1552037232273 2060 1007 425 | 164 1552037232366 2056 986 426 | 164 1552037232366 2062 1005 427 | 166 1552037232428 2067 1006 428 | 166 1552037232428 2055 986 429 | 167 1552037232462 2063 1005 430 | 167 1552037232462 2056 986 431 | 168 1552037232494 2064 1004 432 | 168 1552037232494 2058 988 433 | 169 1552037232522 2061 1003 434 | 169 1552037232522 2059 987 435 | 170 1552037232546 2063 1002 436 | 170 1552037232546 2109 1052 437 | 170 1552037232546 2058 988 438 | 170 1552037232546 2194 1209 439 | 171 1552037232576 2063 1001 440 | 171 1552037232576 2194 1209 441 | 171 1552037232577 2103 1049 442 | 171 1552037232577 2058 988 443 | 172 1552037232604 2067 1002 444 | 172 1552037232604 2193 1209 445 | 174 1552037232671 2065 1000 446 | 174 1552037232671 2103 1049 447 | 175 1552037232702 2065 1001 448 | 175 1552037232702 2071 994 449 | 175 1552037232702 2103 1050 450 | 175 1552037232702 2194 1209 451 | 176 1552037232738 2067 1002 452 | 176 1552037232738 2071 994 453 | 176 1552037232738 2108 1052 454 | 177 1552037232770 2068 1001 455 | 177 1552037232770 2075 995 456 | 177 1552037232770 2103 1050 457 | 178 1552037232799 2069 1001 458 | 178 1552037232799 2071 993 459 | 178 1552037232799 2409 1283 460 | 178 1552037232799 2103 1050 461 | 178 1552037232799 2193 1209 462 | 178 1552037232799 2220 1231 463 | 179 1552037232828 2071 993 464 | 179 1552037232828 2103 1050 465 | 179 1552037232828 2073 1003 466 | 179 1552037232828 2193 1209 467 | 179 1552037232828 2406 1284 468 | 180 1552037232880 2071 994 469 | 180 1552037232880 2102 1050 470 | 180 1552037232880 2073 1003 471 | 180 1552037232880 2408 1299 472 | 180 1552037232880 2193 1209 473 | 180 1552037232880 2220 1231 474 | 181 1552037232909 2071 994 475 | 181 1552037232909 2103 1050 476 | 181 1552037232909 2194 1209 477 | 182 1552037232942 2074 995 478 | 182 1552037232942 2103 1050 479 | 182 1552037232942 2194 1209 480 | 182 1552037232942 2220 1231 481 | 183 1552037232975 2070 994 482 | 183 1552037232975 2103 1050 483 | 183 1552037232976 2194 1209 484 | 183 1552037232976 2220 1231 485 | 184 1552037233005 2071 994 486 | 184 1552037233005 2102 1050 487 | 184 1552037233005 2194 1209 488 | 184 1552037233005 2220 1231 489 | 185 1552037233034 2069 994 490 | 185 1552037233034 2107 1053 491 | 185 1552037233034 2194 1209 492 | 186 1552037233071 2069 994 493 | 186 1552037233071 2107 1053 494 | 186 1552037233071 2194 1209 495 | 186 1552037233071 2381 1310 496 | 187 1552037233096 2067 992 497 | 187 1552037233096 2107 1053 498 | 187 1552037233096 2364 1301 499 | 187 1552037233096 2194 1209 500 | 188 1552037233125 2038 978 501 | 188 1552037233125 2108 1052 502 | 188 1552037233125 2195 1208 503 | 189 1552037233152 2067 992 504 | 189 1552037233153 2108 1052 505 | 189 1552037233153 2194 1209 506 | 190 1552037233186 2071 993 507 | 190 1552037233186 2102 1050 508 | 190 1552037233186 2193 1209 509 | 190 1552037233186 2218 1232 510 | 191 1552037233219 2068 992 511 | 191 1552037233219 2103 1050 512 | 191 1552037233219 2193 1209 513 | 192 1552037233252 2071 993 514 | 192 1552037233252 2103 1050 515 | 192 1552037233252 2194 1209 516 | 193 1552037233284 2066 990 517 | 193 1552037233284 2108 1052 518 | 193 1552037233284 2195 1208 519 | 194 1552037233317 2066 990 520 | 194 1552037233317 2108 1052 521 | 195 1552037233349 2063 988 522 | 195 1552037233349 2108 1052 523 | 195 1552037233349 2194 1209 524 | 196 1552037233375 2108 1052 525 | 196 1552037233375 2062 988 526 | 197 1552037233405 2108 1052 527 | 197 1552037233405 2063 988 528 | 198 1552037233435 2063 988 529 | 198 1552037233435 2108 1052 530 | 198 1552037233435 2194 1209 531 | 198 1552037233435 2219 1232 532 | 199 1552037233600 2069 991 533 | 199 1552037233600 2108 1052 534 | 199 1552037233600 2194 1209 535 | 200 1552037233629 2108 1052 536 | 200 1552037233630 2062 986 537 | 200 1552037233630 2194 1209 538 | 201 1552037233657 2041 976 539 | 201 1552037233657 2108 1052 540 | 201 1552037233657 2193 1209 541 | 202 1552037233691 2042 976 542 | 202 1552037233691 2108 1052 543 | 202 1552037233691 2193 1209 544 | 202 1552037233691 2067 989 545 | 203 1552037233721 2046 977 546 | 203 1552037233721 2108 1052 547 | 203 1552037233721 2194 1209 548 | 204 1552037233757 2043 975 549 | 204 1552037233757 2108 1052 550 | 204 1552037233757 2194 1209 551 | 205 1552037233788 2070 987 552 | 205 1552037233789 2108 1052 553 | 205 1552037233789 2194 1209 554 | 206 1552037233815 2108 1052 555 | 206 1552037233815 2070 987 556 | 206 1552037233815 2193 1209 557 | 207 1552037233852 2108 1052 558 | 207 1552037233852 2071 987 559 | 207 1552037233852 2193 1209 560 | 207 1552037233852 2056 985 561 | 208 1552037233874 2108 1052 562 | 208 1552037233874 2046 977 563 | 208 1552037233874 2193 1209 564 | 209 1552037233903 2108 1052 565 | 209 1552037233903 2047 976 566 | 209 1552037233903 2194 1209 567 | 210 1552037233933 2105 996 568 | 210 1552037233933 2108 1052 569 | 210 1552037233933 2194 1209 570 | 210 1552037233933 2071 987 571 | 211 1552037233967 2105 996 572 | 211 1552037233967 2108 1052 573 | 211 1552037233967 2193 1209 574 | 211 1552037233967 2044 975 575 | 212 1552037233997 2109 997 576 | 212 1552037233997 2108 1052 577 | 212 1552037233997 2193 1209 578 | 212 1552037233997 2069 991 579 | 213 1552037234029 2110 997 580 | 213 1552037234029 2108 1052 581 | 213 1552037234029 2193 1209 582 | 213 1552037234030 2069 991 583 | 214 1552037234063 2109 997 584 | 214 1552037234063 2108 1052 585 | 214 1552037234063 2194 1209 586 | 214 1552037234063 2040 972 587 | 215 1552037234092 2110 996 588 | 215 1552037234092 2108 1052 589 | 215 1552037234092 2069 991 590 | 215 1552037234092 2193 1209 591 | 215 1552037234092 2345 1451 592 | 216 1552037234122 2110 997 593 | 216 1552037234122 2108 1052 594 | 216 1552037234122 2072 993 595 | 216 1552037234122 2194 1209 596 | 217 1552037234152 2116 998 597 | 217 1552037234152 2108 1052 598 | 217 1552037234152 2193 1209 599 | 217 1552037234152 2069 991 600 | 218 1552037234183 2112 996 601 | 218 1552037234183 2108 1052 602 | 218 1552037234183 2193 1209 603 | 218 1552037234183 2072 993 604 | 219 1552037234211 2109 993 605 | 219 1552037234211 2108 1052 606 | 219 1552037234211 2193 1209 607 | 219 1552037234211 2072 992 608 | 220 1552037234242 2109 994 609 | 220 1552037234242 2108 1052 610 | 220 1552037234242 2072 993 611 | 220 1552037234242 2194 1209 612 | 221 1552037234277 2110 993 613 | 221 1552037234277 2108 1052 614 | 221 1552037234277 2072 992 615 | 221 1552037234277 2193 1209 616 | 222 1552037234307 2110 993 617 | 222 1552037234307 2108 1052 618 | 222 1552037234307 2193 1209 619 | 222 1552037234307 2068 991 620 | 223 1552037234345 2114 994 621 | 223 1552037234345 2108 1052 622 | 223 1552037234345 2193 1209 623 | 223 1552037234345 2072 993 624 | 224 1552037234374 2115 994 625 | 224 1552037234374 2108 1052 626 | 224 1552037234374 2069 991 627 | 224 1552037234374 2193 1209 628 | 224 1552037234374 2220 1231 629 | 225 1552037234406 2117 993 630 | 225 1552037234406 2108 1052 631 | 225 1552037234406 2193 1209 632 | 225 1552037234406 2068 991 633 | 225 1552037234406 2220 1231 634 | 226 1552037234436 2126 996 635 | 226 1552037234436 2107 1053 636 | 226 1552037234437 2193 1209 637 | 226 1552037234437 2059 987 638 | 226 1552037234437 2220 1231 639 | 227 1552037234464 2122 994 640 | 227 1552037234464 2108 1052 641 | 227 1552037234464 2193 1209 642 | 227 1552037234464 2059 987 643 | 227 1552037234464 2220 1231 644 | 228 1552037234494 2122 994 645 | 228 1552037234494 2108 1052 646 | 228 1552037234494 2193 1209 647 | 228 1552037234494 2059 987 648 | 228 1552037234494 2219 1232 649 | 229 1552037234531 2117 992 650 | 229 1552037234531 2108 1052 651 | 229 1552037234531 2193 1209 652 | 229 1552037234531 2059 987 653 | 229 1552037234531 2219 1232 654 | 230 1552037234561 2123 994 655 | 230 1552037234561 2108 1052 656 | 230 1552037234561 2193 1209 657 | 230 1552037234561 2059 987 658 | 230 1552037234561 2220 1231 659 | 231 1552037234593 2123 993 660 | 231 1552037234593 2108 1052 661 | 231 1552037234593 2193 1209 662 | 231 1552037234593 2059 987 663 | 231 1552037234593 2220 1231 664 | 232 1552037234628 2119 991 665 | 232 1552037234628 2108 1052 666 | 232 1552037234628 2193 1209 667 | 232 1552037234628 2059 987 668 | 232 1552037234628 2220 1231 669 | 233 1552037234660 2125 992 670 | 233 1552037234660 2108 1052 671 | 233 1552037234660 2193 1209 672 | 233 1552037234660 2055 986 673 | 233 1552037234660 2219 1232 674 | 234 1552037234688 2121 990 675 | 234 1552037234688 2108 1052 676 | 234 1552037234688 2193 1209 677 | 234 1552037234688 2086 921 678 | 234 1552037234688 2072 993 679 | 234 1552037234688 2307 1491 680 | 234 1552037234688 2220 1231 681 | 235 1552037234715 2121 990 682 | 235 1552037234715 2108 1052 683 | 235 1552037234715 2193 1209 684 | 235 1552037234715 2056 986 685 | 235 1552037234715 2304 1492 686 | 235 1552037234715 2219 1232 687 | 236 1552037234743 2122 990 688 | 236 1552037234743 2108 1052 689 | 236 1552037234743 2193 1209 690 | 236 1552037234743 2055 986 691 | 236 1552037234743 2219 1232 692 | 237 1552037234775 2128 991 693 | 237 1552037234775 2108 1052 694 | 237 1552037234775 2301 1493 695 | 237 1552037234775 2193 1209 696 | 237 1552037234775 2055 986 697 | 237 1552037234775 2220 1231 698 | 238 1552037234807 2132 993 699 | 238 1552037234807 2108 1052 700 | 238 1552037234807 2193 1209 701 | 238 1552037234807 2056 986 702 | 238 1552037234807 2311 1511 703 | 238 1552037234807 2220 1231 704 | 239 1552037234836 2129 990 705 | 239 1552037234836 2108 1052 706 | 239 1552037234836 2193 1209 707 | 239 1552037234836 2295 1495 708 | 239 1552037234836 2056 986 709 | 239 1552037234836 2220 1231 710 | 240 1552037234872 2125 988 711 | 240 1552037234872 2108 1052 712 | 240 1552037234872 2193 1209 713 | 240 1552037234872 2308 1512 714 | 240 1552037234872 2056 986 715 | 240 1552037234872 2220 1231 716 | 241 1552037234902 2130 990 717 | 241 1552037234902 2108 1052 718 | 241 1552037234902 2294 1495 719 | 241 1552037234902 2193 1209 720 | 241 1552037234902 2056 986 721 | 241 1552037234902 2220 1231 722 | 242 1552037234935 2130 990 723 | 242 1552037234935 2108 1052 724 | 242 1552037234935 2292 1496 725 | 242 1552037234935 2193 1209 726 | 242 1552037234935 2056 986 727 | 242 1552037234935 2220 1231 728 | 243 1552037234963 2130 989 729 | 243 1552037234963 2277 1476 730 | 243 1552037234963 2108 1052 731 | 243 1552037234963 2193 1209 732 | 243 1552037234963 2056 986 733 | 243 1552037234963 2219 1231 734 | 244 1552037234989 2125 988 735 | 244 1552037234989 2276 1476 736 | 244 1552037234989 2112 1055 737 | 244 1552037234989 2193 1209 738 | 244 1552037234989 2056 986 739 | 245 1552037235017 2131 989 740 | 245 1552037235017 2291 1497 741 | 245 1552037235017 2108 1052 742 | 245 1552037235017 2193 1209 743 | 245 1552037235017 2056 986 744 | 246 1552037235048 2132 988 745 | 246 1552037235048 2108 1052 746 | 246 1552037235048 2305 1513 747 | 246 1552037235048 2193 1209 748 | 246 1552037235048 2056 986 749 | 246 1552037235048 2297 1516 750 | 247 1552037235079 2137 990 751 | 247 1552037235079 2108 1052 752 | 247 1552037235079 2305 1513 753 | 247 1552037235079 2283 1499 754 | 247 1552037235079 2193 1209 755 | 247 1552037235079 2056 986 756 | 248 1552037235109 2137 990 757 | 248 1552037235109 2108 1052 758 | 248 1552037235109 2283 1499 759 | 248 1552037235109 2193 1209 760 | 248 1552037235109 2305 1513 761 | 248 1552037235109 2056 986 762 | 249 1552037235145 2138 990 763 | 249 1552037235145 2108 1052 764 | 249 1552037235145 2269 1479 765 | 249 1552037235145 2193 1209 766 | 249 1552037235145 2056 986 767 | 249 1552037235145 2322 1536 768 | 250 1552037235174 2134 987 769 | 250 1552037235174 2108 1052 770 | 250 1552037235174 2285 1499 771 | 250 1552037235174 2193 1209 772 | 250 1552037235174 2056 986 773 | 251 1552037235208 2139 989 774 | 251 1552037235208 2108 1052 775 | 251 1552037235208 2193 1209 776 | 251 1552037235208 2297 1516 777 | 251 1552037235208 2056 986 778 | 252 1552037235240 2143 990 779 | 252 1552037235240 2108 1052 780 | 252 1552037235240 2297 1516 781 | 252 1552037235240 2193 1209 782 | 252 1552037235240 2056 986 783 | 253 1552037235268 2140 988 784 | 253 1552037235268 2108 1052 785 | 253 1552037235268 2193 1209 786 | 253 1552037235268 2296 1517 787 | 253 1552037235268 2056 986 788 | 253 1552037235268 2138 990 789 | 254 1552037235296 2145 989 790 | 254 1552037235296 2108 1052 791 | 254 1552037235296 2295 1517 792 | 254 1552037235296 2193 1209 793 | 254 1552037235296 2056 986 794 | 255 1552037235326 2150 991 795 | 255 1552037235326 2108 1052 796 | 255 1552037235326 2295 1517 797 | 255 1552037235326 2193 1209 798 | 255 1552037235326 2056 986 799 | 256 1552037235360 2154 992 800 | 256 1552037235360 2112 1055 801 | 256 1552037235360 2193 1209 802 | 256 1552037235360 2309 1540 803 | 256 1552037235360 2055 986 804 | 257 1552037235389 2151 991 805 | 257 1552037235389 2112 1055 806 | 257 1552037235389 2193 1209 807 | 257 1552037235389 2309 1540 808 | 257 1552037235389 2055 986 809 | 258 1552037235425 2143 987 810 | 258 1552037235425 2112 1055 811 | 258 1552037235425 2193 1209 812 | 258 1552037235425 2055 986 813 | 259 1552037235455 2143 987 814 | 259 1552037235455 2112 1055 815 | 259 1552037235455 2193 1209 816 | 259 1552037235455 2055 986 817 | 260 1552037235485 2148 988 818 | 260 1552037235485 2108 1052 819 | 260 1552037235485 2193 1209 820 | 260 1552037235485 2055 986 821 | 261 1552037235521 2148 988 822 | 261 1552037235521 2108 1052 823 | 261 1552037235521 2193 1209 824 | 261 1552037235521 2055 986 825 | 262 1552037235546 2149 987 826 | 262 1552037235546 2108 1052 827 | 262 1552037235546 2194 1209 828 | 262 1552037235546 2055 986 829 | 263 1552037235574 2149 987 830 | 263 1552037235574 2108 1052 831 | 263 1552037235574 2193 1209 832 | 263 1552037235574 2055 986 833 | 264 1552037235605 2149 987 834 | 264 1552037235605 2112 1055 835 | 264 1552037235605 2193 1209 836 | 264 1552037235605 2055 986 837 | 265 1552037235776 2149 987 838 | 265 1552037235776 2108 1052 839 | 265 1552037235776 2194 1209 840 | 265 1552037235776 2055 986 841 | 266 1552037235806 2150 987 842 | 266 1552037235806 2112 1055 843 | 266 1552037235806 2194 1209 844 | 266 1552037235806 2055 986 845 | 267 1552037235836 2150 986 846 | 267 1552037235836 2108 1052 847 | 267 1552037235836 2193 1209 848 | 267 1552037235836 2055 986 849 | 268 1552037235867 2150 987 850 | 268 1552037235868 2108 1052 851 | 268 1552037235868 2193 1209 852 | 268 1552037235868 2055 986 853 | 269 1552037235901 2150 986 854 | 269 1552037235901 2108 1052 855 | 269 1552037235901 2193 1209 856 | 269 1552037235901 2055 986 857 | 270 1552037235932 2151 986 858 | 270 1552037235932 2112 1055 859 | 270 1552037235932 2193 1209 860 | 270 1552037235932 2055 986 861 | 271 1552037235964 2151 986 862 | 271 1552037235964 2112 1055 863 | 271 1552037235964 2193 1209 864 | 271 1552037235964 2055 986 865 | 272 1552037235998 2156 988 866 | 272 1552037235998 2108 1052 867 | 272 1552037235998 2193 1209 868 | 272 1552037235998 2055 986 869 | 273 1552037236028 2156 988 870 | 273 1552037236028 2112 1055 871 | 273 1552037236028 2193 1209 872 | 273 1552037236028 2055 986 873 | 274 1552037236051 2160 989 874 | 274 1552037236051 2108 1052 875 | 274 1552037236051 2193 1209 876 | 274 1552037236051 2055 986 877 | 275 1552037236080 2161 989 878 | 275 1552037236080 2108 1052 879 | 275 1552037236080 2193 1209 880 | 275 1552037236080 2055 986 881 | 276 1552037236110 2157 987 882 | 276 1552037236110 2112 1055 883 | 276 1552037236110 2193 1209 884 | 277 1552037236138 2161 989 885 | 277 1552037236138 2112 1055 886 | 277 1552037236138 2193 1209 887 | 277 1552037236138 2055 986 888 | 278 1552037236174 2161 989 889 | 278 1552037236174 2112 1055 890 | 278 1552037236174 2193 1209 891 | 278 1552037236174 2055 986 892 | 279 1552037236204 2161 989 893 | 279 1552037236204 2112 1055 894 | 279 1552037236204 2193 1209 895 | 279 1552037236204 2055 986 896 | 280 1552037236236 2167 990 897 | 280 1552037236236 2112 1055 898 | 280 1552037236236 2193 1209 899 | 280 1552037236236 2055 986 900 | 281 1552037236269 2167 990 901 | 281 1552037236269 2112 1055 902 | 281 1552037236269 2193 1209 903 | 281 1552037236269 2055 986 904 | 282 1552037236299 2167 990 905 | 282 1552037236299 2112 1055 906 | 282 1552037236299 2193 1209 907 | 282 1552037236299 2055 986 908 | 283 1552037236327 2167 990 909 | 283 1552037236327 2112 1055 910 | 283 1552037236327 2193 1209 911 | 283 1552037236327 2055 986 912 | 284 1552037236358 2162 988 913 | 284 1552037236358 2112 1055 914 | 284 1552037236358 2193 1209 915 | 284 1552037236358 2055 986 916 | 285 1552037236386 2167 990 917 | 285 1552037236386 2108 1052 918 | 285 1552037236386 2193 1209 919 | 285 1552037236386 2055 986 920 | 286 1552037236416 2162 988 921 | 286 1552037236416 2112 1055 922 | 286 1552037236416 2193 1209 923 | 286 1552037236416 2055 986 924 | 287 1552037236450 2162 988 925 | 287 1552037236450 2112 1055 926 | 287 1552037236450 2193 1209 927 | 287 1552037236450 2055 986 928 | 288 1552037236479 2162 988 929 | 288 1552037236479 2108 1052 930 | 288 1552037236479 2194 1209 931 | 288 1552037236479 2055 986 932 | 289 1552037236509 2163 988 933 | 289 1552037236509 2108 1052 934 | 289 1552037236509 2194 1209 935 | 289 1552037236509 2055 986 936 | 290 1552037236545 2163 988 937 | 290 1552037236545 2108 1052 938 | 290 1552037236545 2194 1209 939 | 290 1552037236545 2055 986 940 | 291 1552037236573 2163 988 941 | 291 1552037236573 2108 1052 942 | 291 1552037236573 2194 1209 943 | 291 1552037236573 2055 986 944 | 292 1552037236602 2168 990 945 | 292 1552037236602 2108 1052 946 | 292 1552037236602 2194 1209 947 | 292 1552037236602 2055 986 948 | 293 1552037236629 2168 990 949 | 293 1552037236629 2108 1052 950 | 293 1552037236629 2194 1209 951 | 293 1552037236629 2055 986 952 | 294 1552037236656 2164 987 953 | 294 1552037236656 2108 1052 954 | 294 1552037236656 2194 1209 955 | 294 1552037236656 2055 986 956 | 295 1552037236686 2164 987 957 | 295 1552037236686 2108 1052 958 | 295 1552037236686 2194 1209 959 | 295 1552037236686 2055 986 960 | 296 1552037236722 2186 994 961 | 296 1552037236722 2108 1052 962 | 296 1552037236722 2194 1209 963 | 296 1552037236722 2055 986 964 | 297 1552037236753 2180 993 965 | 297 1552037236753 2108 1052 966 | 297 1552037236753 2194 1209 967 | 297 1552037236753 2055 986 968 | 298 1552037236785 2186 994 969 | 298 1552037236785 2108 1052 970 | 298 1552037236785 2194 1209 971 | 298 1552037236785 2055 986 972 | 299 1552037236820 2186 994 973 | 299 1552037236820 2108 1052 974 | 299 1552037236820 2194 1209 975 | 299 1552037236820 2055 986 976 | 300 1552037236850 2108 1052 977 | 300 1552037236850 2182 991 978 | 300 1552037236850 2194 1209 979 | 300 1552037236850 2185 995 980 | 300 1552037236850 2055 986 981 | 301 1552037236881 2182 991 982 | 301 1552037236881 2108 1052 983 | 301 1552037236881 2194 1209 984 | 301 1552037236881 2055 986 985 | 302 1552037236900 2181 992 986 | 302 1552037236900 2108 1052 987 | 302 1552037236900 2194 1209 988 | 302 1552037236900 2055 986 989 | 303 1552037236930 2181 992 990 | 303 1552037236930 2108 1052 991 | 303 1552037236930 2194 1209 992 | 303 1552037236930 2055 986 993 | 304 1552037236958 2183 991 994 | 304 1552037236958 2108 1052 995 | 304 1552037236958 2194 1209 996 | 304 1552037236958 2055 986 997 | 305 1552037236992 2189 993 998 | 305 1552037236992 2108 1052 999 | 305 1552037236992 2194 1209 1000 | 305 1552037236992 2055 986 1001 | 306 1552037237022 2188 993 1002 | 306 1552037237022 2108 1052 1003 | 306 1552037237022 2194 1209 1004 | 306 1552037237022 2055 986 1005 | 307 1552037237052 2189 993 1006 | 307 1552037237052 2108 1052 1007 | 307 1552037237052 2194 1209 1008 | 307 1552037237052 2055 986 1009 | 308 1552037237087 2194 994 1010 | 308 1552037237087 2108 1052 1011 | 308 1552037237087 2194 1209 1012 | 308 1552037237087 2055 986 1013 | 309 1552037237116 2189 993 1014 | 309 1552037237116 2108 1052 1015 | 309 1552037237116 2194 1209 1016 | 309 1552037237116 2055 986 1017 | 310 1552037237149 2189 993 1018 | 310 1552037237149 2108 1052 1019 | 310 1552037237149 2194 1209 1020 | 310 1552037237149 2055 986 1021 | 311 1552037237177 2189 993 1022 | 311 1552037237177 2108 1052 1023 | 311 1552037237177 2194 1209 1024 | 311 1552037237177 2055 986 1025 | 312 1552037237206 2189 993 1026 | 312 1552037237206 2108 1052 1027 | 312 1552037237206 2194 1209 1028 | 312 1552037237206 2055 986 1029 | 313 1552037237234 2183 991 1030 | 313 1552037237234 2108 1052 1031 | 313 1552037237234 2194 1209 1032 | 313 1552037237234 2055 986 1033 | 314 1552037237266 2189 993 1034 | 314 1552037237266 2108 1052 1035 | 314 1552037237266 2194 1209 1036 | 315 1552037237302 2194 994 1037 | 315 1552037237302 2112 1055 1038 | 315 1552037237302 2194 1209 1039 | 316 1552037237332 2194 994 1040 | 316 1552037237332 2108 1052 1041 | 316 1552037237332 2194 1209 1042 | 316 1552037237332 2055 986 1043 | 317 1552037237366 2188 993 1044 | 317 1552037237366 2108 1052 1045 | 317 1552037237366 2194 1209 1046 | 317 1552037237366 2055 986 1047 | 318 1552037237395 2189 992 1048 | 318 1552037237395 2194 1209 1049 | 318 1552037237395 2126 1064 1050 | 318 1552037237395 2055 986 1051 | 319 1552037237431 2190 992 1052 | 319 1552037237431 2126 1064 1053 | 319 1552037237431 2194 1209 1054 | 319 1552037237431 2055 986 1055 | 320 1552037237458 2195 994 1056 | 320 1552037237458 2112 1055 1057 | 320 1552037237458 2194 1209 1058 | 321 1552037237486 2196 993 1059 | 321 1552037237486 2112 1055 1060 | 321 1552037237486 2194 1209 1061 | 322 1552037237516 2196 993 1062 | 322 1552037237516 2112 1055 1063 | 322 1552037237516 2193 1209 1064 | 323 1552037237550 2196 993 1065 | 323 1552037237550 2112 1055 1066 | 323 1552037237550 2193 1209 1067 | 324 1552037237580 2196 993 1068 | 324 1552037237580 2112 1055 1069 | 324 1552037237580 2193 1209 1070 | 325 1552037237611 2203 995 1071 | 325 1552037237611 2112 1055 1072 | 326 1552037237646 2210 997 1073 | 326 1552037237646 2112 1055 1074 | 326 1552037237646 2193 1209 1075 | 327 1552037237676 2210 997 1076 | 327 1552037237676 2112 1055 1077 | 327 1552037237676 2193 1209 1078 | 328 1552037237708 2210 997 1079 | 328 1552037237708 2112 1055 1080 | 329 1552037237734 2210 997 1081 | 329 1552037237734 2112 1055 1082 | 330 1552037237764 2203 995 1083 | 330 1552037237764 2112 1055 1084 | 330 1552037237764 2193 1209 1085 | 331 1552037237794 2210 997 1086 | 331 1552037237794 2108 1052 1087 | 332 1552037237957 2210 997 1088 | 332 1552037237957 2108 1052 1089 | 333 1552037237986 2210 997 1090 | 333 1552037237987 2108 1052 1091 | 334 1552037238014 2211 996 1092 | 334 1552037238014 2112 1055 1093 | 335 1552037238048 2211 996 1094 | 335 1552037238048 2112 1055 1095 | 336 1552037238082 2211 996 1096 | 336 1552037238082 2108 1052 1097 | 337 1552037238114 2210 997 1098 | 337 1552037238114 2108 1052 1099 | 338 1552037238148 2215 998 1100 | 338 1552037238148 2108 1052 1101 | 338 1552037238148 2193 1209 1102 | 339 1552037238177 2215 998 1103 | 339 1552037238177 2126 1064 1104 | 339 1552037238177 2202 1217 1105 | 340 1552037238205 2215 998 1106 | 340 1552037238205 2108 1052 1107 | 340 1552037238205 2193 1209 1108 | 341 1552037238237 2216 998 1109 | 341 1552037238238 2108 1052 1110 | 341 1552037238238 2193 1209 1111 | 342 1552037238268 2210 997 1112 | 342 1552037238268 2108 1052 1113 | 342 1552037238268 2194 1209 1114 | 343 1552037238296 2236 1004 1115 | 343 1552037238296 2108 1052 1116 | 343 1552037238296 2193 1209 1117 | 344 1552037238332 2243 1007 1118 | 344 1552037238332 2126 1064 1119 | 345 1552037238366 2235 1005 1120 | 345 1552037238366 2126 1064 1121 | 345 1552037238366 2193 1209 1122 | 346 1552037238395 2235 1005 1123 | 346 1552037238395 2126 1064 1124 | 347 1552037238430 2235 1005 1125 | 347 1552037238430 2126 1064 1126 | 348 1552037238461 2235 1005 1127 | 351 1552037238551 2125 1064 1128 | 351 1552037238551 2236 1004 1129 | 352 1552037238578 2132 1067 1130 | 352 1552037238578 2242 1007 1131 | 353 1552037238612 2242 1007 1132 | 353 1552037238612 2125 1064 1133 | 353 1552037238612 2202 1217 1134 | 354 1552037238644 2236 1004 1135 | 354 1552037238644 2125 1064 1136 | 354 1552037238644 2193 1209 1137 | 355 1552037238677 2236 1004 1138 | 355 1552037238677 2132 1067 1139 | 355 1552037238677 2193 1209 1140 | 356 1552037238710 2243 1007 1141 | 356 1552037238710 2131 1067 1142 | 356 1552037238710 2202 1217 1143 | 357 1552037238747 2243 1007 1144 | 357 1552037238747 2125 1064 1145 | 357 1552037238747 2202 1217 1146 | 358 1552037238774 2249 1009 1147 | 358 1552037238774 2203 1216 1148 | 359 1552037238806 2202 1217 1149 | 359 1552037238806 2249 1009 1150 | 360 1552037238833 1791 1083 1151 | 360 1552037238833 2202 1217 1152 | 360 1552037238833 2249 1009 1153 | 361 1552037238865 1792 1086 1154 | 361 1552037238865 2202 1217 1155 | 362 1552037238897 1792 1086 1156 | 362 1552037238897 2202 1217 1157 | 363 1552037238927 1792 1086 1158 | 363 1552037238927 2202 1217 1159 | 364 1552037238962 1793 1086 1160 | 364 1552037238962 2202 1217 1161 | 365 1552037238992 1793 1086 1162 | 365 1552037238992 2202 1217 1163 | 366 1552037239021 1793 1087 1164 | 366 1552037239021 2202 1217 1165 | 367 1552037239051 1793 1078 1166 | 367 1552037239051 2202 1217 1167 | 368 1552037239118 1793 1079 1168 | 368 1552037239118 2202 1217 1169 | 369 1552037239185 1795 1088 1170 | 369 1552037239185 2271 1017 1171 | 369 1552037239185 2202 1217 1172 | 370 1552037239225 1795 1090 1173 | 370 1552037239225 2202 1217 1174 | 371 1552037239258 1795 1081 1175 | 371 1552037239258 2271 1017 1176 | 371 1552037239258 2202 1217 1177 | -------------------------------------------------------------------------------- /data/test_ll.txt: -------------------------------------------------------------------------------- 1 | 0 1555343392058 44.655556 10.934241 2 | 0 1555343392058 44.655582 10.934417 3 | 0 1555343392058 44.655533 10.934377 4 | 0 1555343392058 44.655571 10.934344 5 | 1 1555343392083 44.655567 10.934235 6 | 1 1555343392083 44.655533 10.934377 7 | 1 1555343392083 44.655582 10.934419 8 | 1 1555343392083 44.655571 10.934344 9 | 1 1555343392083 44.655437 10.934426 10 | 2 1555343392103 44.655567 10.934234 11 | 2 1555343392103 44.655533 10.934377 12 | 2 1555343392103 44.655586 10.934402 13 | 2 1555343392103 44.655571 10.934344 14 | 2 1555343392103 44.655437 10.934426 15 | 3 1555343392123 44.655567 10.934235 16 | 3 1555343392123 44.655533 10.934377 17 | 3 1555343392123 44.655586 10.934403 18 | 3 1555343392123 44.655571 10.934344 19 | 3 1555343392123 44.655437 10.934425 20 | 4 1555343392141 44.655567 10.934237 21 | 4 1555343392142 44.655533 10.934377 22 | 4 1555343392142 44.655571 10.934344 23 | 5 1555343392160 44.655560 10.934241 24 | 5 1555343392160 44.655533 10.934377 25 | 5 1555343392160 44.655571 10.934344 26 | 6 1555343392179 44.655556 10.934245 27 | 6 1555343392179 44.655533 10.934377 28 | 6 1555343392179 44.655571 10.934344 29 | 6 1555343392179 44.655590 10.934406 30 | 7 1555343392198 44.655556 10.934246 31 | 7 1555343392199 44.655533 10.934377 32 | 7 1555343392199 44.655594 10.934402 33 | 7 1555343392199 44.655571 10.934344 34 | 7 1555343392199 44.655437 10.934426 35 | 8 1555343392219 44.655556 10.934247 36 | 8 1555343392219 44.655533 10.934377 37 | 8 1555343392219 44.655571 10.934344 38 | 8 1555343392220 44.655594 10.934403 39 | 8 1555343392220 44.655437 10.934427 40 | 9 1555343392239 44.655556 10.934247 41 | 9 1555343392239 44.655533 10.934377 42 | 9 1555343392239 44.655571 10.934344 43 | 10 1555343392258 44.655556 10.934247 44 | 10 1555343392258 44.655533 10.934377 45 | 10 1555343392258 44.655571 10.934344 46 | 11 1555343392277 44.655556 10.934247 47 | 11 1555343392277 44.655533 10.934377 48 | 11 1555343392277 44.655571 10.934344 49 | 11 1555343392277 44.655434 10.934431 50 | 12 1555343392297 44.655556 10.934248 51 | 12 1555343392297 44.655533 10.934377 52 | 12 1555343392297 44.655434 10.934430 53 | 12 1555343392297 44.655571 10.934344 54 | 12 1555343392297 44.655418 10.934446 55 | 13 1555343392318 44.655556 10.934249 56 | 13 1555343392318 44.655533 10.934377 57 | 13 1555343392318 44.655598 10.934404 58 | 13 1555343392318 44.655434 10.934430 59 | 13 1555343392318 44.655571 10.934344 60 | 14 1555343392337 44.655556 10.934251 61 | 14 1555343392337 44.655533 10.934377 62 | 14 1555343392337 44.655598 10.934404 63 | 14 1555343392337 44.655571 10.934344 64 | 14 1555343392337 44.655434 10.934430 65 | 15 1555343392357 44.655552 10.934252 66 | 15 1555343392357 44.655533 10.934377 67 | 15 1555343392357 44.655571 10.934344 68 | 15 1555343392357 44.655434 10.934430 69 | 16 1555343392377 44.655571 10.934233 70 | 16 1555343392377 44.655529 10.934380 71 | 16 1555343392377 44.655571 10.934344 72 | 16 1555343392377 44.655434 10.934430 73 | 17 1555343392397 44.655571 10.934235 74 | 17 1555343392397 44.655556 10.934251 75 | 17 1555343392397 44.655533 10.934377 76 | 17 1555343392397 44.655434 10.934430 77 | 17 1555343392397 44.655571 10.934344 78 | 18 1555343392417 44.655571 10.934235 79 | 18 1555343392417 44.655533 10.934377 80 | 18 1555343392417 44.655434 10.934430 81 | 18 1555343392417 44.655571 10.934344 82 | 18 1555343392417 44.655605 10.934383 83 | 19 1555343392437 44.655560 10.934249 84 | 19 1555343392437 44.655533 10.934377 85 | 19 1555343392437 44.655434 10.934430 86 | 19 1555343392437 44.655571 10.934344 87 | 19 1555343392437 44.655609 10.934380 88 | 20 1555343392457 44.655571 10.934237 89 | 20 1555343392457 44.655533 10.934377 90 | 20 1555343392457 44.655571 10.934344 91 | 20 1555343392457 44.655609 10.934381 92 | 20 1555343392457 44.655434 10.934430 93 | 21 1555343392485 44.655556 10.934251 94 | 21 1555343392485 44.655533 10.934377 95 | 21 1555343392485 44.655571 10.934344 96 | 21 1555343392485 44.655434 10.934430 97 | 22 1555343392507 44.655556 10.934253 98 | 22 1555343392507 44.655533 10.934377 99 | 22 1555343392507 44.655571 10.934344 100 | 22 1555343392507 44.655434 10.934430 101 | 23 1555343392527 44.655556 10.934252 102 | 23 1555343392527 44.655533 10.934377 103 | 23 1555343392527 44.655571 10.934344 104 | 23 1555343392527 44.655434 10.934430 105 | 24 1555343392548 44.655529 10.934380 106 | 24 1555343392548 44.655556 10.934254 107 | 24 1555343392548 44.655571 10.934344 108 | 24 1555343392548 44.655434 10.934430 109 | 25 1555343392568 44.655529 10.934380 110 | 25 1555343392568 44.655571 10.934344 111 | 25 1555343392568 44.655434 10.934430 112 | 25 1555343392568 44.655556 10.934257 113 | 26 1555343392589 44.655529 10.934380 114 | 26 1555343392589 44.655571 10.934238 115 | 26 1555343392589 44.655571 10.934344 116 | 26 1555343392589 44.655434 10.934430 117 | 27 1555343392610 44.655571 10.934237 118 | 27 1555343392610 44.655529 10.934380 119 | 27 1555343392610 44.655571 10.934344 120 | 27 1555343392610 44.655434 10.934430 121 | 28 1555343392630 44.655571 10.934239 122 | 28 1555343392630 44.655533 10.934377 123 | 28 1555343392630 44.655434 10.934430 124 | 28 1555343392630 44.655571 10.934344 125 | 29 1555343392650 44.655571 10.934241 126 | 29 1555343392650 44.655533 10.934377 127 | 29 1555343392650 44.655434 10.934430 128 | 29 1555343392650 44.655571 10.934344 129 | 30 1555343392668 44.655556 10.934258 130 | 30 1555343392668 44.655529 10.934380 131 | 30 1555343392668 44.655434 10.934430 132 | 30 1555343392668 44.655571 10.934344 133 | 31 1555343392690 44.655556 10.934257 134 | 31 1555343392690 44.655533 10.934377 135 | 31 1555343392690 44.655434 10.934430 136 | 31 1555343392690 44.655571 10.934344 137 | 32 1555343392710 44.655548 10.934267 138 | 32 1555343392710 44.655533 10.934377 139 | 32 1555343392710 44.655571 10.934344 140 | 33 1555343392729 44.655548 10.934266 141 | 33 1555343392729 44.655533 10.934377 142 | 33 1555343392729 44.655571 10.934344 143 | 33 1555343392730 44.655434 10.934430 144 | 34 1555343392750 44.655556 10.934259 145 | 34 1555343392750 44.655525 10.934388 146 | 34 1555343392750 44.655571 10.934344 147 | 34 1555343392750 44.655434 10.934430 148 | 35 1555343392769 44.655560 10.934259 149 | 35 1555343392769 44.655525 10.934388 150 | 35 1555343392769 44.655571 10.934344 151 | 35 1555343392769 44.655434 10.934430 152 | 36 1555343392788 44.655556 10.934260 153 | 36 1555343392788 44.655525 10.934388 154 | 36 1555343392788 44.655571 10.934344 155 | 36 1555343392789 44.655434 10.934430 156 | 37 1555343392808 44.655560 10.934261 157 | 37 1555343392808 44.655525 10.934388 158 | 37 1555343392808 44.655434 10.934430 159 | 37 1555343392808 44.655571 10.934344 160 | 38 1555343392828 44.655552 10.934265 161 | 38 1555343392828 44.655533 10.934377 162 | 38 1555343392828 44.655434 10.934430 163 | 38 1555343392828 44.655571 10.934344 164 | 39 1555343392849 44.655556 10.934262 165 | 39 1555343392849 44.655525 10.934388 166 | 39 1555343392849 44.655571 10.934344 167 | 39 1555343392849 44.655434 10.934430 168 | 40 1555343392868 44.655552 10.934270 169 | 40 1555343392868 44.655525 10.934388 170 | 40 1555343392868 44.655434 10.934430 171 | 40 1555343392868 44.655571 10.934344 172 | 41 1555343392888 44.655560 10.934261 173 | 41 1555343392888 44.655525 10.934388 174 | 41 1555343392888 44.655571 10.934344 175 | 41 1555343392888 44.655434 10.934430 176 | 42 1555343392907 44.655556 10.934269 177 | 42 1555343392907 44.655525 10.934388 178 | 42 1555343392907 44.655434 10.934430 179 | 42 1555343392907 44.655571 10.934344 180 | 43 1555343392926 44.655556 10.934269 181 | 43 1555343392926 44.655525 10.934388 182 | 43 1555343392926 44.655571 10.934344 183 | 43 1555343392926 44.655434 10.934430 184 | 44 1555343392947 44.655556 10.934269 185 | 44 1555343392947 44.655525 10.934388 186 | 44 1555343392947 44.655571 10.934344 187 | 44 1555343392947 44.655434 10.934430 188 | 45 1555343392966 44.655556 10.934270 189 | 45 1555343392966 44.655525 10.934388 190 | 45 1555343392966 44.655571 10.934344 191 | 45 1555343392966 44.655434 10.934430 192 | 46 1555343392987 44.655552 10.934273 193 | 46 1555343392987 44.655525 10.934388 194 | 46 1555343392987 44.655434 10.934430 195 | 46 1555343392987 44.655571 10.934344 196 | 47 1555343393006 44.655556 10.934272 197 | 47 1555343393006 44.655525 10.934388 198 | 48 1555343393025 44.655556 10.934273 199 | 48 1555343393026 44.655525 10.934388 200 | 48 1555343393026 44.655571 10.934344 201 | 48 1555343393026 44.655434 10.934430 202 | 49 1555343393044 44.655525 10.934388 203 | 49 1555343393045 44.655556 10.934272 204 | 49 1555343393045 44.655575 10.934251 205 | 49 1555343393045 44.655571 10.934344 206 | 49 1555343393045 44.655434 10.934430 207 | 50 1555343393064 44.655575 10.934251 208 | 50 1555343393064 44.655525 10.934388 209 | 50 1555343393064 44.655552 10.934276 210 | 50 1555343393064 44.655434 10.934430 211 | 50 1555343393064 44.655571 10.934344 212 | 51 1555343393084 44.655525 10.934388 213 | 52 1555343393103 44.655575 10.934251 214 | 52 1555343393103 44.655525 10.934388 215 | 52 1555343393103 44.655571 10.934344 216 | 52 1555343393103 44.655434 10.934430 217 | 53 1555343393122 44.655556 10.934274 218 | 53 1555343393122 44.655525 10.934388 219 | 53 1555343393122 44.655571 10.934344 220 | 53 1555343393122 44.655575 10.934253 221 | 53 1555343393122 44.655434 10.934430 222 | 54 1555343393142 44.655556 10.934274 223 | 54 1555343393142 44.655525 10.934388 224 | 54 1555343393142 44.655571 10.934344 225 | 54 1555343393142 44.655434 10.934430 226 | 54 1555343393142 44.655575 10.934253 227 | 55 1555343393162 44.655556 10.934274 228 | 55 1555343393162 44.655525 10.934388 229 | 55 1555343393162 44.655571 10.934344 230 | 55 1555343393162 44.655434 10.934430 231 | 56 1555343393183 44.655560 10.934274 232 | 56 1555343393183 44.655525 10.934388 233 | 56 1555343393183 44.655571 10.934344 234 | 56 1555343393183 44.655434 10.934430 235 | 57 1555343393202 44.655560 10.934275 236 | 57 1555343393202 44.655525 10.934388 237 | 57 1555343393202 44.655571 10.934344 238 | 57 1555343393202 44.655434 10.934430 239 | 58 1555343393222 44.655556 10.934278 240 | 58 1555343393222 44.655525 10.934388 241 | 58 1555343393222 44.655571 10.934344 242 | 58 1555343393222 44.655434 10.934430 243 | 59 1555343393241 44.655556 10.934278 244 | 59 1555343393241 44.655525 10.934388 245 | 59 1555343393241 44.655434 10.934430 246 | 59 1555343393241 44.655571 10.934346 247 | 60 1555343393260 44.655556 10.934279 248 | 60 1555343393260 44.655525 10.934388 249 | 60 1555343393260 44.655571 10.934344 250 | 60 1555343393260 44.655434 10.934430 251 | 61 1555343393282 44.655560 10.934278 252 | 61 1555343393282 44.655525 10.934388 253 | 61 1555343393282 44.655571 10.934344 254 | 61 1555343393282 44.655434 10.934430 255 | 62 1555343393300 44.655560 10.934276 256 | 62 1555343393300 44.655525 10.934387 257 | 62 1555343393301 44.655434 10.934430 258 | 63 1555343393320 44.655556 10.934282 259 | 63 1555343393320 44.655525 10.934388 260 | 63 1555343393320 44.655434 10.934430 261 | 63 1555343393320 44.655571 10.934346 262 | 64 1555343393339 44.655556 10.934282 263 | 65 1555343393359 44.655571 10.934266 264 | 65 1555343393359 44.655525 10.934388 265 | 65 1555343393359 44.655571 10.934346 266 | 66 1555343393380 44.655525 10.934388 267 | 67 1555343393398 44.655571 10.934268 268 | 67 1555343393398 44.655357 10.934235 269 | 67 1555343393399 44.655525 10.934388 270 | 68 1555343393417 44.655571 10.934269 271 | 68 1555343393417 44.655525 10.934388 272 | 69 1555343393436 44.655571 10.934266 273 | 69 1555343393436 44.655525 10.934388 274 | 69 1555343393436 44.655571 10.934345 275 | 70 1555343393456 44.655560 10.934282 276 | 70 1555343393456 44.655525 10.934388 277 | 70 1555343393456 44.655571 10.934345 278 | 70 1555343393456 44.655434 10.934430 279 | 71 1555343393476 44.655560 10.934282 280 | 71 1555343393476 44.655525 10.934388 281 | 71 1555343393477 44.655571 10.934345 282 | 71 1555343393477 44.655434 10.934430 283 | 72 1555343393496 44.655560 10.934284 284 | 72 1555343393496 44.655525 10.934388 285 | 72 1555343393496 44.655571 10.934345 286 | 73 1555343393515 44.655560 10.934282 287 | 74 1555343393534 44.655552 10.934294 288 | 74 1555343393534 44.655525 10.934388 289 | 74 1555343393534 44.655571 10.934345 290 | 75 1555343393553 44.655552 10.934294 291 | 76 1555343393573 44.655579 10.934262 292 | 76 1555343393573 44.655556 10.934294 293 | 76 1555343393573 44.655571 10.934345 294 | 77 1555343393593 44.655579 10.934264 295 | 77 1555343393593 44.655571 10.934346 296 | 77 1555343393593 44.655525 10.934388 297 | 78 1555343393613 44.655563 10.934281 298 | 78 1555343393613 44.655571 10.934345 299 | 78 1555343393613 44.655525 10.934388 300 | 78 1555343393613 44.655361 10.934238 301 | 79 1555343393632 44.655567 10.934280 302 | 79 1555343393632 44.655571 10.934345 303 | 79 1555343393632 44.655525 10.934388 304 | 80 1555343393652 44.655556 10.934295 305 | 80 1555343393652 44.655571 10.934345 306 | 80 1555343393652 44.655525 10.934388 307 | 81 1555343393671 44.655563 10.934283 308 | 81 1555343393671 44.655571 10.934345 309 | 81 1555343393671 44.655525 10.934388 310 | 82 1555343393690 44.655556 10.934294 311 | 82 1555343393690 44.655571 10.934345 312 | 83 1555343393711 44.655556 10.934294 313 | 83 1555343393711 44.655571 10.934345 314 | 84 1555343393730 44.655563 10.934285 315 | 85 1555343393749 44.655560 10.934293 316 | 86 1555343393768 44.655556 10.934297 317 | 86 1555343393768 44.655567 10.934541 318 | 86 1555343393768 44.655571 10.934345 319 | 87 1555343393787 44.655556 10.934299 320 | 88 1555343393807 44.655556 10.934299 321 | 88 1555343393808 44.655571 10.934345 322 | 88 1555343393808 44.655525 10.934388 323 | 89 1555343393827 44.655556 10.934299 324 | 90 1555343393847 44.655556 10.934300 325 | 91 1555343393866 44.655556 10.934299 326 | 91 1555343393866 44.655571 10.934346 327 | 92 1555343393885 44.655556 10.934299 328 | 93 1555343393904 44.655556 10.934300 329 | 93 1555343393904 44.655571 10.934346 330 | 94 1555343393923 44.655560 10.934299 331 | 94 1555343393923 44.655571 10.934346 332 | 95 1555343393944 44.655560 10.934299 333 | 95 1555343393944 44.655571 10.934345 334 | 96 1555343393963 44.655560 10.934299 335 | 97 1555343393982 44.655560 10.934302 336 | 97 1555343393982 44.655571 10.934344 337 | 97 1555343393982 44.655434 10.934430 338 | 98 1555343394001 44.655560 10.934301 339 | 98 1555343394001 44.655571 10.934344 340 | 98 1555343394001 44.655533 10.934377 341 | 98 1555343394001 44.655434 10.934430 342 | 99 1555343394020 44.655560 10.934302 343 | 99 1555343394020 44.655571 10.934344 344 | 99 1555343394020 44.655533 10.934377 345 | 100 1555343394040 44.655560 10.934301 346 | 100 1555343394040 44.655571 10.934344 347 | 100 1555343394040 44.655533 10.934377 348 | 101 1555343394060 44.655560 10.934303 349 | 101 1555343394060 44.655533 10.934377 350 | 101 1555343394060 44.655571 10.934344 351 | 102 1555343394081 44.655560 10.934304 352 | 102 1555343394081 44.655571 10.934344 353 | 102 1555343394081 44.655533 10.934377 354 | 103 1555343394099 44.655560 10.934306 355 | 103 1555343394099 44.655571 10.934344 356 | 104 1555343394118 44.655556 10.934311 357 | 105 1555343394136 44.655556 10.934312 358 | 105 1555343394136 44.655571 10.934344 359 | 105 1555343394136 44.655525 10.934388 360 | 106 1555343394155 44.655575 10.934283 361 | 106 1555343394155 44.655560 10.934308 362 | 106 1555343394155 44.655571 10.934344 363 | 107 1555343394175 44.655560 10.934306 364 | 107 1555343394175 44.655575 10.934283 365 | 107 1555343394175 44.655571 10.934344 366 | 112 1555343394284 44.655560 10.934310 367 | 114 1555343394322 44.655571 10.934302 368 | 115 1555343394341 44.655571 10.934301 369 | 115 1555343394341 44.655560 10.934312 370 | 116 1555343394361 44.655571 10.934303 371 | 116 1555343394361 44.655560 10.934314 372 | 116 1555343394361 44.655434 10.934430 373 | 117 1555343394382 44.655571 10.934305 374 | 118 1555343394401 44.655571 10.934303 375 | 118 1555343394401 44.655563 10.934314 376 | 118 1555343394401 44.655434 10.934430 377 | 119 1555343394420 44.655571 10.934301 378 | 119 1555343394420 44.655563 10.934310 379 | 119 1555343394420 44.655434 10.934430 380 | 119 1555343394420 44.655495 10.934643 381 | 120 1555343394440 44.655571 10.934302 382 | 120 1555343394440 44.655434 10.934430 383 | 121 1555343394460 44.655571 10.934304 384 | 121 1555343394460 44.655434 10.934430 385 | 122 1555343394481 44.655571 10.934304 386 | 122 1555343394481 44.655434 10.934430 387 | 123 1555343394500 44.655571 10.934304 388 | 123 1555343394500 44.655434 10.934430 389 | 124 1555343394520 44.655571 10.934306 390 | 124 1555343394520 44.655434 10.934430 391 | 125 1555343394539 44.655571 10.934306 392 | 125 1555343394539 44.655434 10.934430 393 | 126 1555343394557 44.655571 10.934307 394 | 126 1555343394557 44.655434 10.934430 395 | 127 1555343394577 44.655571 10.934305 396 | 128 1555343394597 44.655563 10.934320 397 | 129 1555343394617 44.655563 10.934322 398 | 130 1555343394637 44.655560 10.934326 399 | 132 1555343394675 44.655560 10.934328 400 | 133 1555343394694 44.655560 10.934331 401 | 135 1555343394733 44.655560 10.934333 402 | 136 1555343394753 44.655560 10.934330 403 | 137 1555343394771 44.655560 10.934330 404 | 138 1555343394790 44.655560 10.934330 405 | 139 1555343394811 44.655560 10.934331 406 | 140 1555343394831 44.655418 10.934735 407 | 140 1555343394831 44.655560 10.934333 408 | 141 1555343394852 44.655563 10.934330 409 | 141 1555343394852 44.655422 10.934711 410 | 142 1555343394870 44.655560 10.934335 411 | 143 1555343394889 44.655560 10.934331 412 | 144 1555343394909 44.655560 10.934334 413 | 145 1555343394928 44.655560 10.934336 414 | 146 1555343394949 44.655560 10.934335 415 | 147 1555343394969 44.655560 10.934335 416 | 148 1555343394987 44.655560 10.934337 417 | 149 1555343395008 44.655560 10.934339 418 | 150 1555343395027 44.655560 10.934339 419 | 151 1555343395048 44.655560 10.934340 420 | 158 1555343395184 44.655560 10.934342 421 | 158 1555343395185 44.655571 10.934346 422 | 159 1555343395205 44.655560 10.934342 423 | 160 1555343395224 44.655560 10.934345 424 | 161 1555343395245 44.655560 10.934347 425 | 164 1555343395303 44.655571 10.934344 426 | 164 1555343395303 44.655560 10.934348 427 | 166 1555343395343 44.655560 10.934351 428 | 166 1555343395343 44.655571 10.934344 429 | 167 1555343395362 44.655560 10.934349 430 | 167 1555343395362 44.655571 10.934344 431 | 168 1555343395381 44.655560 10.934349 432 | 168 1555343395381 44.655571 10.934345 433 | 169 1555343395409 44.655563 10.934347 434 | 169 1555343395409 44.655571 10.934346 435 | 170 1555343395430 44.655563 10.934349 436 | 170 1555343395430 44.655533 10.934378 437 | 170 1555343395430 44.655571 10.934345 438 | 170 1555343395430 44.655434 10.934430 439 | 171 1555343395450 44.655563 10.934349 440 | 171 1555343395450 44.655434 10.934430 441 | 171 1555343395450 44.655533 10.934374 442 | 171 1555343395450 44.655571 10.934345 443 | 172 1555343395468 44.655563 10.934351 444 | 172 1555343395468 44.655434 10.934430 445 | 174 1555343395514 44.655563 10.934350 446 | 174 1555343395514 44.655533 10.934374 447 | 175 1555343395535 44.655563 10.934350 448 | 175 1555343395535 44.655567 10.934354 449 | 175 1555343395535 44.655533 10.934374 450 | 175 1555343395535 44.655434 10.934430 451 | 176 1555343395555 44.655563 10.934351 452 | 176 1555343395555 44.655567 10.934354 453 | 176 1555343395555 44.655533 10.934377 454 | 177 1555343395576 44.655563 10.934352 455 | 177 1555343395576 44.655567 10.934357 456 | 177 1555343395576 44.655533 10.934374 457 | 178 1555343395595 44.655563 10.934353 458 | 178 1555343395595 44.655567 10.934354 459 | 178 1555343395595 44.655388 10.934564 460 | 178 1555343395595 44.655533 10.934374 461 | 178 1555343395595 44.655434 10.934430 462 | 178 1555343395595 44.655418 10.934446 463 | 179 1555343395614 44.655567 10.934354 464 | 179 1555343395614 44.655533 10.934374 465 | 179 1555343395614 44.655563 10.934355 466 | 179 1555343395614 44.655434 10.934430 467 | 179 1555343395614 44.655388 10.934562 468 | 180 1555343395649 44.655567 10.934354 469 | 180 1555343395649 44.655533 10.934373 470 | 180 1555343395649 44.655563 10.934355 471 | 180 1555343395649 44.655376 10.934564 472 | 180 1555343395649 44.655434 10.934430 473 | 180 1555343395649 44.655418 10.934446 474 | 181 1555343395668 44.655567 10.934354 475 | 181 1555343395668 44.655533 10.934374 476 | 181 1555343395668 44.655434 10.934430 477 | 182 1555343395687 44.655567 10.934356 478 | 182 1555343395687 44.655533 10.934374 479 | 182 1555343395687 44.655434 10.934430 480 | 182 1555343395687 44.655418 10.934446 481 | 183 1555343395708 44.655567 10.934353 482 | 183 1555343395708 44.655533 10.934374 483 | 183 1555343395708 44.655434 10.934430 484 | 183 1555343395708 44.655418 10.934446 485 | 184 1555343395728 44.655567 10.934354 486 | 184 1555343395728 44.655533 10.934373 487 | 184 1555343395728 44.655434 10.934430 488 | 184 1555343395728 44.655418 10.934446 489 | 185 1555343395748 44.655567 10.934353 490 | 185 1555343395748 44.655529 10.934376 491 | 185 1555343395748 44.655434 10.934430 492 | 186 1555343395768 44.655567 10.934353 493 | 186 1555343395768 44.655529 10.934376 494 | 186 1555343395768 44.655434 10.934430 495 | 186 1555343395768 44.655369 10.934546 496 | 187 1555343395788 44.655567 10.934351 497 | 187 1555343395788 44.655529 10.934376 498 | 187 1555343395788 44.655376 10.934536 499 | 187 1555343395788 44.655434 10.934430 500 | 188 1555343395809 44.655579 10.934333 501 | 188 1555343395809 44.655533 10.934377 502 | 188 1555343395809 44.655434 10.934431 503 | 189 1555343395828 44.655567 10.934351 504 | 189 1555343395828 44.655533 10.934377 505 | 189 1555343395828 44.655434 10.934430 506 | 190 1555343395848 44.655567 10.934354 507 | 190 1555343395848 44.655533 10.934373 508 | 190 1555343395848 44.655434 10.934430 509 | 190 1555343395848 44.655418 10.934445 510 | 191 1555343395868 44.655567 10.934352 511 | 191 1555343395868 44.655533 10.934374 512 | 191 1555343395868 44.655434 10.934430 513 | 192 1555343395887 44.655567 10.934354 514 | 192 1555343395887 44.655533 10.934374 515 | 192 1555343395887 44.655434 10.934430 516 | 193 1555343395907 44.655571 10.934351 517 | 193 1555343395907 44.655533 10.934377 518 | 193 1555343395908 44.655434 10.934431 519 | 194 1555343395927 44.655571 10.934351 520 | 194 1555343395927 44.655533 10.934377 521 | 195 1555343395946 44.655571 10.934349 522 | 195 1555343395946 44.655533 10.934377 523 | 195 1555343395946 44.655434 10.934430 524 | 196 1555343395966 44.655533 10.934377 525 | 196 1555343395966 44.655571 10.934348 526 | 197 1555343395985 44.655533 10.934377 527 | 197 1555343395985 44.655571 10.934349 528 | 198 1555343396006 44.655571 10.934349 529 | 198 1555343396006 44.655533 10.934377 530 | 198 1555343396006 44.655434 10.934430 531 | 198 1555343396006 44.655418 10.934445 532 | 199 1555343396026 44.655567 10.934353 533 | 199 1555343396026 44.655533 10.934377 534 | 199 1555343396026 44.655434 10.934430 535 | 200 1555343396045 44.655533 10.934377 536 | 200 1555343396045 44.655571 10.934348 537 | 200 1555343396045 44.655434 10.934430 538 | 201 1555343396065 44.655579 10.934335 539 | 201 1555343396065 44.655533 10.934377 540 | 201 1555343396065 44.655434 10.934430 541 | 202 1555343396084 44.655579 10.934336 542 | 202 1555343396084 44.655533 10.934377 543 | 202 1555343396084 44.655434 10.934430 544 | 202 1555343396084 44.655571 10.934351 545 | 203 1555343396105 44.655579 10.934339 546 | 203 1555343396105 44.655533 10.934377 547 | 203 1555343396105 44.655434 10.934430 548 | 204 1555343396124 44.655579 10.934337 549 | 204 1555343396124 44.655533 10.934377 550 | 204 1555343396124 44.655434 10.934430 551 | 205 1555343396143 44.655571 10.934353 552 | 205 1555343396143 44.655533 10.934377 553 | 205 1555343396143 44.655434 10.934430 554 | 206 1555343396163 44.655533 10.934377 555 | 206 1555343396163 44.655571 10.934353 556 | 206 1555343396163 44.655434 10.934430 557 | 207 1555343396183 44.655533 10.934377 558 | 207 1555343396183 44.655571 10.934354 559 | 207 1555343396183 44.655434 10.934430 560 | 207 1555343396183 44.655571 10.934344 561 | 208 1555343396204 44.655533 10.934377 562 | 208 1555343396204 44.655579 10.934339 563 | 208 1555343396204 44.655434 10.934430 564 | 209 1555343396223 44.655533 10.934377 565 | 209 1555343396223 44.655579 10.934339 566 | 209 1555343396223 44.655434 10.934430 567 | 210 1555343396244 44.655567 10.934375 568 | 210 1555343396244 44.655533 10.934377 569 | 210 1555343396244 44.655434 10.934430 570 | 210 1555343396244 44.655571 10.934354 571 | 211 1555343396263 44.655567 10.934375 572 | 211 1555343396263 44.655533 10.934377 573 | 211 1555343396263 44.655434 10.934430 574 | 211 1555343396263 44.655579 10.934337 575 | 212 1555343396283 44.655567 10.934378 576 | 212 1555343396283 44.655533 10.934377 577 | 212 1555343396283 44.655434 10.934430 578 | 212 1555343396283 44.655567 10.934353 579 | 213 1555343396304 44.655567 10.934378 580 | 213 1555343396304 44.655533 10.934377 581 | 213 1555343396304 44.655434 10.934430 582 | 213 1555343396304 44.655567 10.934353 583 | 214 1555343396324 44.655567 10.934378 584 | 214 1555343396324 44.655533 10.934377 585 | 214 1555343396324 44.655434 10.934430 586 | 214 1555343396324 44.655582 10.934335 587 | 215 1555343396344 44.655567 10.934378 588 | 215 1555343396344 44.655533 10.934377 589 | 215 1555343396344 44.655567 10.934353 590 | 215 1555343396344 44.655434 10.934430 591 | 215 1555343396344 44.655281 10.934525 592 | 216 1555343396363 44.655567 10.934378 593 | 216 1555343396363 44.655533 10.934377 594 | 216 1555343396363 44.655567 10.934355 595 | 216 1555343396363 44.655434 10.934430 596 | 217 1555343396385 44.655563 10.934381 597 | 217 1555343396385 44.655533 10.934377 598 | 217 1555343396385 44.655434 10.934430 599 | 217 1555343396385 44.655567 10.934353 600 | 218 1555343396406 44.655567 10.934380 601 | 218 1555343396406 44.655533 10.934377 602 | 218 1555343396406 44.655434 10.934430 603 | 218 1555343396406 44.655567 10.934355 604 | 219 1555343396425 44.655567 10.934378 605 | 219 1555343396425 44.655533 10.934377 606 | 219 1555343396425 44.655434 10.934430 607 | 219 1555343396425 44.655567 10.934355 608 | 220 1555343396446 44.655567 10.934378 609 | 220 1555343396446 44.655533 10.934377 610 | 220 1555343396446 44.655567 10.934355 611 | 220 1555343396446 44.655434 10.934430 612 | 221 1555343396466 44.655567 10.934378 613 | 221 1555343396466 44.655533 10.934377 614 | 221 1555343396466 44.655567 10.934355 615 | 221 1555343396467 44.655434 10.934430 616 | 222 1555343396486 44.655567 10.934378 617 | 222 1555343396486 44.655533 10.934377 618 | 222 1555343396486 44.655434 10.934430 619 | 222 1555343396486 44.655567 10.934352 620 | 223 1555343396506 44.655567 10.934381 621 | 223 1555343396506 44.655533 10.934377 622 | 223 1555343396506 44.655434 10.934430 623 | 223 1555343396506 44.655567 10.934355 624 | 224 1555343396525 44.655567 10.934381 625 | 224 1555343396525 44.655533 10.934377 626 | 224 1555343396525 44.655567 10.934353 627 | 224 1555343396525 44.655434 10.934430 628 | 224 1555343396526 44.655418 10.934446 629 | 225 1555343396544 44.655567 10.934382 630 | 225 1555343396544 44.655533 10.934377 631 | 225 1555343396544 44.655434 10.934430 632 | 225 1555343396544 44.655567 10.934352 633 | 225 1555343396544 44.655418 10.934446 634 | 226 1555343396563 44.655567 10.934388 635 | 226 1555343396563 44.655529 10.934376 636 | 226 1555343396563 44.655434 10.934430 637 | 226 1555343396563 44.655571 10.934346 638 | 226 1555343396564 44.655418 10.934446 639 | 227 1555343396584 44.655567 10.934385 640 | 227 1555343396584 44.655533 10.934377 641 | 227 1555343396584 44.655434 10.934430 642 | 227 1555343396584 44.655571 10.934346 643 | 227 1555343396584 44.655418 10.934446 644 | 228 1555343396604 44.655567 10.934385 645 | 228 1555343396604 44.655533 10.934377 646 | 228 1555343396604 44.655434 10.934430 647 | 228 1555343396604 44.655571 10.934346 648 | 228 1555343396604 44.655418 10.934445 649 | 229 1555343396623 44.655567 10.934382 650 | 229 1555343396623 44.655533 10.934377 651 | 229 1555343396623 44.655434 10.934430 652 | 229 1555343396623 44.655571 10.934346 653 | 229 1555343396623 44.655418 10.934445 654 | 230 1555343396642 44.655567 10.934386 655 | 230 1555343396642 44.655533 10.934377 656 | 230 1555343396642 44.655434 10.934430 657 | 230 1555343396642 44.655571 10.934346 658 | 230 1555343396642 44.655418 10.934446 659 | 231 1555343396661 44.655567 10.934386 660 | 231 1555343396661 44.655533 10.934377 661 | 231 1555343396661 44.655434 10.934430 662 | 231 1555343396661 44.655571 10.934346 663 | 231 1555343396661 44.655418 10.934446 664 | 232 1555343396681 44.655567 10.934383 665 | 232 1555343396681 44.655533 10.934377 666 | 232 1555343396681 44.655434 10.934430 667 | 232 1555343396681 44.655571 10.934346 668 | 232 1555343396681 44.655418 10.934446 669 | 233 1555343396702 44.655567 10.934387 670 | 233 1555343396702 44.655533 10.934377 671 | 233 1555343396702 44.655434 10.934430 672 | 233 1555343396702 44.655571 10.934344 673 | 233 1555343396702 44.655418 10.934445 674 | 234 1555343396720 44.655571 10.934385 675 | 234 1555343396720 44.655533 10.934377 676 | 234 1555343396720 44.655434 10.934430 677 | 234 1555343396720 44.655613 10.934363 678 | 234 1555343396720 44.655567 10.934355 679 | 234 1555343396720 44.655258 10.934501 680 | 234 1555343396720 44.655418 10.934446 681 | 235 1555343396739 44.655571 10.934385 682 | 235 1555343396739 44.655533 10.934377 683 | 235 1555343396739 44.655434 10.934430 684 | 235 1555343396739 44.655571 10.934344 685 | 235 1555343396739 44.655258 10.934499 686 | 235 1555343396739 44.655418 10.934445 687 | 236 1555343396758 44.655571 10.934385 688 | 236 1555343396758 44.655533 10.934377 689 | 236 1555343396758 44.655434 10.934430 690 | 236 1555343396758 44.655571 10.934344 691 | 236 1555343396758 44.655418 10.934445 692 | 237 1555343396779 44.655567 10.934389 693 | 237 1555343396779 44.655533 10.934377 694 | 237 1555343396779 44.655258 10.934497 695 | 237 1555343396779 44.655434 10.934430 696 | 237 1555343396779 44.655571 10.934344 697 | 237 1555343396779 44.655418 10.934446 698 | 238 1555343396799 44.655567 10.934392 699 | 238 1555343396799 44.655533 10.934377 700 | 238 1555343396799 44.655434 10.934430 701 | 238 1555343396799 44.655571 10.934344 702 | 238 1555343396799 44.655247 10.934503 703 | 238 1555343396800 44.655418 10.934446 704 | 239 1555343396819 44.655571 10.934390 705 | 239 1555343396819 44.655533 10.934377 706 | 239 1555343396819 44.655434 10.934430 707 | 239 1555343396819 44.655254 10.934493 708 | 239 1555343396819 44.655571 10.934344 709 | 239 1555343396819 44.655418 10.934446 710 | 240 1555343396838 44.655571 10.934387 711 | 240 1555343396838 44.655533 10.934377 712 | 240 1555343396838 44.655434 10.934430 713 | 240 1555343396838 44.655247 10.934502 714 | 240 1555343396838 44.655571 10.934344 715 | 240 1555343396838 44.655418 10.934446 716 | 241 1555343396857 44.655571 10.934390 717 | 241 1555343396857 44.655533 10.934377 718 | 241 1555343396857 44.655254 10.934492 719 | 241 1555343396857 44.655434 10.934430 720 | 241 1555343396857 44.655571 10.934344 721 | 241 1555343396857 44.655418 10.934446 722 | 242 1555343396876 44.655571 10.934390 723 | 242 1555343396876 44.655533 10.934377 724 | 242 1555343396876 44.655254 10.934491 725 | 242 1555343396876 44.655434 10.934430 726 | 242 1555343396876 44.655571 10.934344 727 | 242 1555343396876 44.655418 10.934446 728 | 243 1555343396897 44.655571 10.934390 729 | 243 1555343396897 44.655266 10.934482 730 | 243 1555343396897 44.655533 10.934377 731 | 243 1555343396897 44.655434 10.934430 732 | 243 1555343396897 44.655571 10.934344 733 | 243 1555343396897 44.655418 10.934445 734 | 244 1555343396916 44.655571 10.934387 735 | 244 1555343396916 44.655266 10.934482 736 | 244 1555343396916 44.655529 10.934380 737 | 244 1555343396916 44.655434 10.934430 738 | 244 1555343396916 44.655571 10.934344 739 | 245 1555343396936 44.655571 10.934391 740 | 245 1555343396936 44.655254 10.934490 741 | 245 1555343396936 44.655533 10.934377 742 | 245 1555343396936 44.655434 10.934430 743 | 245 1555343396936 44.655571 10.934344 744 | 246 1555343396955 44.655571 10.934392 745 | 246 1555343396955 44.655533 10.934377 746 | 246 1555343396955 44.655243 10.934500 747 | 246 1555343396955 44.655434 10.934430 748 | 246 1555343396955 44.655571 10.934344 749 | 246 1555343396955 44.655243 10.934494 750 | 247 1555343396974 44.655571 10.934395 751 | 247 1555343396974 44.655533 10.934377 752 | 247 1555343396974 44.655243 10.934500 753 | 247 1555343396974 44.655254 10.934485 754 | 247 1555343396974 44.655434 10.934430 755 | 247 1555343396974 44.655571 10.934344 756 | 248 1555343396993 44.655571 10.934395 757 | 248 1555343396993 44.655533 10.934377 758 | 248 1555343396993 44.655254 10.934485 759 | 248 1555343396993 44.655434 10.934430 760 | 248 1555343396993 44.655243 10.934500 761 | 248 1555343396993 44.655571 10.934344 762 | 249 1555343397013 44.655571 10.934396 763 | 249 1555343397013 44.655533 10.934377 764 | 249 1555343397013 44.655266 10.934477 765 | 249 1555343397013 44.655434 10.934430 766 | 249 1555343397013 44.655571 10.934344 767 | 249 1555343397013 44.655231 10.934510 768 | 250 1555343397035 44.655571 10.934393 769 | 250 1555343397035 44.655533 10.934377 770 | 250 1555343397035 44.655254 10.934487 771 | 250 1555343397035 44.655434 10.934430 772 | 250 1555343397035 44.655571 10.934344 773 | 251 1555343397053 44.655571 10.934396 774 | 251 1555343397053 44.655533 10.934377 775 | 251 1555343397053 44.655434 10.934430 776 | 251 1555343397053 44.655243 10.934494 777 | 251 1555343397053 44.655571 10.934344 778 | 252 1555343397072 44.655571 10.934399 779 | 252 1555343397072 44.655533 10.934377 780 | 252 1555343397072 44.655243 10.934494 781 | 252 1555343397072 44.655434 10.934430 782 | 252 1555343397072 44.655571 10.934344 783 | 253 1555343397092 44.655571 10.934397 784 | 253 1555343397092 44.655533 10.934377 785 | 253 1555343397092 44.655434 10.934430 786 | 253 1555343397092 44.655243 10.934494 787 | 253 1555343397092 44.655571 10.934344 788 | 253 1555343397092 44.655571 10.934396 789 | 254 1555343397111 44.655571 10.934400 790 | 254 1555343397111 44.655533 10.934377 791 | 254 1555343397111 44.655243 10.934493 792 | 254 1555343397111 44.655434 10.934430 793 | 254 1555343397111 44.655571 10.934344 794 | 255 1555343397132 44.655567 10.934402 795 | 255 1555343397132 44.655533 10.934377 796 | 255 1555343397132 44.655243 10.934493 797 | 255 1555343397132 44.655434 10.934430 798 | 255 1555343397132 44.655571 10.934344 799 | 256 1555343397152 44.655567 10.934405 800 | 256 1555343397152 44.655529 10.934380 801 | 256 1555343397152 44.655434 10.934430 802 | 256 1555343397152 44.655228 10.934502 803 | 256 1555343397152 44.655571 10.934344 804 | 257 1555343397170 44.655567 10.934403 805 | 257 1555343397170 44.655529 10.934380 806 | 257 1555343397170 44.655434 10.934430 807 | 257 1555343397170 44.655228 10.934502 808 | 257 1555343397170 44.655571 10.934344 809 | 258 1555343397189 44.655571 10.934399 810 | 258 1555343397189 44.655529 10.934380 811 | 258 1555343397189 44.655434 10.934430 812 | 258 1555343397189 44.655571 10.934344 813 | 259 1555343397208 44.655571 10.934399 814 | 259 1555343397208 44.655529 10.934380 815 | 259 1555343397209 44.655434 10.934430 816 | 259 1555343397209 44.655571 10.934344 817 | 260 1555343397229 44.655571 10.934402 818 | 260 1555343397230 44.655533 10.934377 819 | 260 1555343397230 44.655434 10.934430 820 | 260 1555343397230 44.655571 10.934344 821 | 261 1555343397249 44.655571 10.934402 822 | 261 1555343397249 44.655533 10.934377 823 | 261 1555343397249 44.655434 10.934430 824 | 261 1555343397249 44.655571 10.934344 825 | 262 1555343397269 44.655571 10.934402 826 | 262 1555343397269 44.655533 10.934377 827 | 262 1555343397269 44.655434 10.934430 828 | 262 1555343397269 44.655571 10.934344 829 | 263 1555343397287 44.655571 10.934402 830 | 263 1555343397287 44.655533 10.934377 831 | 263 1555343397287 44.655434 10.934430 832 | 263 1555343397287 44.655571 10.934344 833 | 264 1555343397306 44.655571 10.934402 834 | 264 1555343397306 44.655529 10.934380 835 | 264 1555343397306 44.655434 10.934430 836 | 264 1555343397306 44.655571 10.934344 837 | 265 1555343397326 44.655571 10.934402 838 | 265 1555343397326 44.655533 10.934377 839 | 265 1555343397326 44.655434 10.934430 840 | 265 1555343397326 44.655571 10.934344 841 | 266 1555343397346 44.655571 10.934402 842 | 266 1555343397346 44.655529 10.934380 843 | 266 1555343397346 44.655434 10.934430 844 | 266 1555343397346 44.655571 10.934344 845 | 267 1555343397366 44.655571 10.934402 846 | 267 1555343397366 44.655533 10.934377 847 | 267 1555343397366 44.655434 10.934430 848 | 267 1555343397366 44.655571 10.934344 849 | 268 1555343397385 44.655571 10.934402 850 | 268 1555343397385 44.655533 10.934377 851 | 268 1555343397385 44.655434 10.934430 852 | 268 1555343397385 44.655571 10.934344 853 | 269 1555343397403 44.655571 10.934402 854 | 269 1555343397403 44.655533 10.934377 855 | 269 1555343397403 44.655434 10.934430 856 | 269 1555343397403 44.655571 10.934344 857 | 270 1555343397423 44.655571 10.934403 858 | 270 1555343397423 44.655529 10.934380 859 | 270 1555343397423 44.655434 10.934430 860 | 270 1555343397423 44.655571 10.934344 861 | 271 1555343397442 44.655571 10.934403 862 | 271 1555343397442 44.655529 10.934380 863 | 271 1555343397442 44.655434 10.934430 864 | 271 1555343397442 44.655571 10.934344 865 | 272 1555343397463 44.655571 10.934406 866 | 272 1555343397463 44.655533 10.934377 867 | 272 1555343397463 44.655434 10.934430 868 | 272 1555343397463 44.655571 10.934344 869 | 273 1555343397482 44.655571 10.934406 870 | 273 1555343397483 44.655529 10.934380 871 | 273 1555343397483 44.655434 10.934430 872 | 273 1555343397483 44.655571 10.934344 873 | 274 1555343397502 44.655571 10.934409 874 | 274 1555343397502 44.655533 10.934377 875 | 274 1555343397502 44.655434 10.934430 876 | 274 1555343397502 44.655571 10.934344 877 | 275 1555343397520 44.655571 10.934410 878 | 275 1555343397520 44.655533 10.934377 879 | 275 1555343397520 44.655434 10.934430 880 | 275 1555343397520 44.655571 10.934344 881 | 276 1555343397539 44.655571 10.934407 882 | 276 1555343397539 44.655529 10.934380 883 | 276 1555343397539 44.655434 10.934430 884 | 277 1555343397559 44.655571 10.934410 885 | 277 1555343397559 44.655529 10.934380 886 | 277 1555343397559 44.655434 10.934430 887 | 277 1555343397559 44.655571 10.934344 888 | 278 1555343397577 44.655571 10.934410 889 | 278 1555343397577 44.655529 10.934380 890 | 278 1555343397577 44.655434 10.934430 891 | 278 1555343397577 44.655571 10.934344 892 | 279 1555343397597 44.655571 10.934410 893 | 279 1555343397597 44.655529 10.934380 894 | 279 1555343397597 44.655434 10.934430 895 | 279 1555343397597 44.655571 10.934344 896 | 280 1555343397616 44.655571 10.934414 897 | 280 1555343397616 44.655529 10.934380 898 | 280 1555343397616 44.655434 10.934430 899 | 280 1555343397616 44.655571 10.934344 900 | 281 1555343397637 44.655571 10.934414 901 | 281 1555343397637 44.655529 10.934380 902 | 281 1555343397637 44.655434 10.934430 903 | 281 1555343397637 44.655571 10.934344 904 | 282 1555343397657 44.655571 10.934414 905 | 282 1555343397657 44.655529 10.934380 906 | 282 1555343397657 44.655434 10.934430 907 | 282 1555343397657 44.655571 10.934344 908 | 283 1555343397676 44.655571 10.934414 909 | 283 1555343397676 44.655529 10.934380 910 | 283 1555343397676 44.655434 10.934430 911 | 283 1555343397676 44.655571 10.934344 912 | 284 1555343397698 44.655571 10.934410 913 | 284 1555343397698 44.655529 10.934380 914 | 284 1555343397698 44.655434 10.934430 915 | 284 1555343397698 44.655571 10.934344 916 | 285 1555343397717 44.655571 10.934414 917 | 285 1555343397717 44.655533 10.934377 918 | 285 1555343397717 44.655434 10.934430 919 | 285 1555343397717 44.655571 10.934344 920 | 286 1555343397736 44.655571 10.934410 921 | 286 1555343397736 44.655529 10.934380 922 | 286 1555343397736 44.655434 10.934430 923 | 286 1555343397736 44.655571 10.934344 924 | 287 1555343397755 44.655571 10.934410 925 | 287 1555343397755 44.655529 10.934380 926 | 287 1555343397755 44.655434 10.934430 927 | 287 1555343397755 44.655571 10.934344 928 | 288 1555343397774 44.655571 10.934410 929 | 288 1555343397774 44.655533 10.934377 930 | 288 1555343397774 44.655434 10.934430 931 | 288 1555343397774 44.655571 10.934344 932 | 289 1555343397795 44.655571 10.934411 933 | 289 1555343397795 44.655533 10.934377 934 | 289 1555343397795 44.655434 10.934430 935 | 289 1555343397795 44.655571 10.934344 936 | 290 1555343397815 44.655571 10.934411 937 | 290 1555343397815 44.655533 10.934377 938 | 290 1555343397815 44.655434 10.934430 939 | 290 1555343397815 44.655571 10.934344 940 | 291 1555343397835 44.655571 10.934411 941 | 291 1555343397835 44.655533 10.934377 942 | 291 1555343397835 44.655434 10.934430 943 | 291 1555343397835 44.655571 10.934344 944 | 292 1555343397856 44.655571 10.934414 945 | 292 1555343397856 44.655533 10.934377 946 | 292 1555343397856 44.655434 10.934430 947 | 292 1555343397856 44.655571 10.934344 948 | 293 1555343397875 44.655571 10.934414 949 | 293 1555343397875 44.655533 10.934377 950 | 293 1555343397875 44.655434 10.934430 951 | 293 1555343397875 44.655571 10.934344 952 | 294 1555343397895 44.655571 10.934412 953 | 294 1555343397895 44.655533 10.934377 954 | 294 1555343397895 44.655434 10.934430 955 | 294 1555343397895 44.655571 10.934344 956 | 295 1555343397915 44.655571 10.934412 957 | 295 1555343397915 44.655533 10.934377 958 | 295 1555343397915 44.655434 10.934430 959 | 295 1555343397915 44.655571 10.934344 960 | 296 1555343397935 44.655567 10.934425 961 | 296 1555343397935 44.655533 10.934377 962 | 296 1555343397935 44.655434 10.934430 963 | 296 1555343397935 44.655571 10.934344 964 | 297 1555343397956 44.655567 10.934422 965 | 297 1555343397956 44.655533 10.934377 966 | 297 1555343397956 44.655434 10.934430 967 | 297 1555343397956 44.655571 10.934344 968 | 298 1555343397975 44.655567 10.934425 969 | 298 1555343397975 44.655533 10.934377 970 | 298 1555343397975 44.655434 10.934430 971 | 298 1555343397975 44.655571 10.934344 972 | 299 1555343397995 44.655567 10.934425 973 | 299 1555343397995 44.655533 10.934377 974 | 299 1555343397995 44.655434 10.934430 975 | 299 1555343397995 44.655571 10.934344 976 | 300 1555343398015 44.655533 10.934377 977 | 300 1555343398015 44.655567 10.934422 978 | 300 1555343398015 44.655434 10.934430 979 | 300 1555343398015 44.655567 10.934424 980 | 300 1555343398015 44.655571 10.934344 981 | 301 1555343398035 44.655567 10.934422 982 | 301 1555343398035 44.655533 10.934377 983 | 301 1555343398035 44.655434 10.934430 984 | 301 1555343398035 44.655571 10.934344 985 | 302 1555343398056 44.655567 10.934422 986 | 302 1555343398056 44.655533 10.934377 987 | 302 1555343398056 44.655434 10.934430 988 | 302 1555343398056 44.655571 10.934344 989 | 303 1555343398075 44.655567 10.934422 990 | 303 1555343398075 44.655533 10.934377 991 | 303 1555343398075 44.655434 10.934430 992 | 303 1555343398075 44.655571 10.934344 993 | 304 1555343398095 44.655567 10.934423 994 | 304 1555343398095 44.655533 10.934377 995 | 304 1555343398095 44.655434 10.934430 996 | 304 1555343398095 44.655571 10.934344 997 | 305 1555343398114 44.655567 10.934427 998 | 305 1555343398114 44.655533 10.934377 999 | 305 1555343398114 44.655434 10.934430 1000 | 305 1555343398114 44.655571 10.934344 1001 | 306 1555343398134 44.655567 10.934426 1002 | 306 1555343398134 44.655533 10.934377 1003 | 306 1555343398134 44.655434 10.934430 1004 | 306 1555343398134 44.655571 10.934344 1005 | 307 1555343398153 44.655567 10.934427 1006 | 307 1555343398153 44.655533 10.934377 1007 | 307 1555343398153 44.655434 10.934430 1008 | 307 1555343398153 44.655571 10.934344 1009 | 308 1555343398172 44.655567 10.934430 1010 | 308 1555343398172 44.655533 10.934377 1011 | 308 1555343398172 44.655434 10.934430 1012 | 308 1555343398172 44.655571 10.934344 1013 | 309 1555343398192 44.655567 10.934427 1014 | 309 1555343398192 44.655533 10.934377 1015 | 309 1555343398192 44.655434 10.934430 1016 | 309 1555343398192 44.655571 10.934344 1017 | 310 1555343398211 44.655567 10.934427 1018 | 310 1555343398211 44.655533 10.934377 1019 | 310 1555343398211 44.655434 10.934430 1020 | 310 1555343398211 44.655571 10.934344 1021 | 311 1555343398230 44.655567 10.934427 1022 | 311 1555343398230 44.655533 10.934377 1023 | 311 1555343398230 44.655434 10.934430 1024 | 311 1555343398230 44.655571 10.934344 1025 | 312 1555343398250 44.655567 10.934427 1026 | 312 1555343398250 44.655533 10.934377 1027 | 312 1555343398250 44.655434 10.934430 1028 | 312 1555343398250 44.655571 10.934344 1029 | 313 1555343398270 44.655567 10.934423 1030 | 313 1555343398270 44.655533 10.934377 1031 | 313 1555343398270 44.655434 10.934430 1032 | 313 1555343398270 44.655571 10.934344 1033 | 314 1555343398291 44.655567 10.934427 1034 | 314 1555343398291 44.655533 10.934377 1035 | 314 1555343398291 44.655434 10.934430 1036 | 315 1555343398309 44.655567 10.934430 1037 | 315 1555343398309 44.655529 10.934380 1038 | 315 1555343398310 44.655434 10.934430 1039 | 316 1555343398328 44.655567 10.934430 1040 | 316 1555343398329 44.655533 10.934377 1041 | 316 1555343398329 44.655434 10.934430 1042 | 316 1555343398329 44.655571 10.934344 1043 | 317 1555343398348 44.655567 10.934426 1044 | 317 1555343398348 44.655533 10.934377 1045 | 317 1555343398348 44.655434 10.934430 1046 | 317 1555343398348 44.655571 10.934344 1047 | 318 1555343398368 44.655567 10.934427 1048 | 318 1555343398369 44.655434 10.934430 1049 | 318 1555343398369 44.655525 10.934388 1050 | 318 1555343398369 44.655571 10.934344 1051 | 319 1555343398390 44.655567 10.934428 1052 | 319 1555343398390 44.655525 10.934388 1053 | 319 1555343398390 44.655434 10.934430 1054 | 319 1555343398390 44.655571 10.934344 1055 | 320 1555343398410 44.655567 10.934431 1056 | 320 1555343398410 44.655529 10.934380 1057 | 320 1555343398410 44.655434 10.934430 1058 | 321 1555343398429 44.655567 10.934431 1059 | 321 1555343398429 44.655529 10.934380 1060 | 321 1555343398429 44.655434 10.934430 1061 | 322 1555343398448 44.655567 10.934431 1062 | 322 1555343398448 44.655529 10.934380 1063 | 322 1555343398448 44.655434 10.934430 1064 | 323 1555343398470 44.655567 10.934431 1065 | 323 1555343398470 44.655529 10.934380 1066 | 323 1555343398470 44.655434 10.934430 1067 | 324 1555343398491 44.655567 10.934431 1068 | 324 1555343398491 44.655529 10.934380 1069 | 324 1555343398491 44.655434 10.934430 1070 | 325 1555343398510 44.655567 10.934436 1071 | 325 1555343398510 44.655529 10.934380 1072 | 326 1555343398528 44.655567 10.934441 1073 | 326 1555343398528 44.655529 10.934380 1074 | 326 1555343398528 44.655434 10.934430 1075 | 327 1555343398547 44.655567 10.934441 1076 | 327 1555343398547 44.655529 10.934380 1077 | 327 1555343398547 44.655434 10.934430 1078 | 328 1555343398567 44.655567 10.934441 1079 | 328 1555343398567 44.655529 10.934380 1080 | 329 1555343398588 44.655567 10.934441 1081 | 329 1555343398588 44.655529 10.934380 1082 | 330 1555343398607 44.655567 10.934436 1083 | 330 1555343398607 44.655529 10.934380 1084 | 330 1555343398607 44.655434 10.934430 1085 | 331 1555343398626 44.655567 10.934441 1086 | 331 1555343398626 44.655533 10.934377 1087 | 332 1555343398645 44.655567 10.934441 1088 | 332 1555343398645 44.655533 10.934377 1089 | 333 1555343398664 44.655567 10.934441 1090 | 333 1555343398664 44.655533 10.934377 1091 | 334 1555343398685 44.655567 10.934441 1092 | 334 1555343398685 44.655529 10.934380 1093 | 335 1555343398704 44.655567 10.934441 1094 | 335 1555343398704 44.655529 10.934380 1095 | 336 1555343398724 44.655567 10.934441 1096 | 336 1555343398724 44.655533 10.934377 1097 | 337 1555343398743 44.655567 10.934441 1098 | 337 1555343398743 44.655533 10.934377 1099 | 338 1555343398761 44.655563 10.934443 1100 | 338 1555343398761 44.655533 10.934377 1101 | 338 1555343398761 44.655434 10.934430 1102 | 339 1555343398780 44.655563 10.934443 1103 | 339 1555343398780 44.655525 10.934388 1104 | 339 1555343398780 44.655430 10.934435 1105 | 340 1555343398799 44.655563 10.934443 1106 | 340 1555343398799 44.655533 10.934377 1107 | 340 1555343398799 44.655434 10.934430 1108 | 341 1555343398820 44.655563 10.934444 1109 | 341 1555343398820 44.655533 10.934377 1110 | 341 1555343398820 44.655434 10.934430 1111 | 342 1555343398839 44.655567 10.934441 1112 | 342 1555343398839 44.655533 10.934377 1113 | 342 1555343398839 44.655434 10.934430 1114 | 343 1555343398858 44.655560 10.934457 1115 | 343 1555343398858 44.655533 10.934377 1116 | 343 1555343398858 44.655434 10.934430 1117 | 344 1555343398877 44.655560 10.934461 1118 | 344 1555343398877 44.655525 10.934388 1119 | 345 1555343398897 44.655560 10.934456 1120 | 345 1555343398897 44.655525 10.934388 1121 | 345 1555343398897 44.655434 10.934430 1122 | 346 1555343398918 44.655560 10.934456 1123 | 346 1555343398918 44.655525 10.934388 1124 | 347 1555343398937 44.655560 10.934456 1125 | 347 1555343398937 44.655525 10.934388 1126 | 348 1555343398957 44.655560 10.934456 1127 | 351 1555343399016 44.655525 10.934387 1128 | 351 1555343399016 44.655560 10.934457 1129 | 352 1555343399035 44.655521 10.934392 1130 | 352 1555343399035 44.655560 10.934460 1131 | 353 1555343399054 44.655560 10.934460 1132 | 353 1555343399054 44.655525 10.934387 1133 | 353 1555343399054 44.655430 10.934435 1134 | 354 1555343399074 44.655560 10.934457 1135 | 354 1555343399074 44.655525 10.934387 1136 | 354 1555343399074 44.655434 10.934430 1137 | 355 1555343399093 44.655560 10.934457 1138 | 355 1555343399093 44.655521 10.934392 1139 | 355 1555343399093 44.655434 10.934430 1140 | 356 1555343399113 44.655560 10.934461 1141 | 356 1555343399113 44.655521 10.934391 1142 | 356 1555343399113 44.655430 10.934435 1143 | 357 1555343399132 44.655560 10.934461 1144 | 357 1555343399132 44.655525 10.934387 1145 | 357 1555343399132 44.655430 10.934435 1146 | 358 1555343399153 44.655560 10.934464 1147 | 358 1555343399153 44.655430 10.934436 1148 | 359 1555343399173 44.655430 10.934435 1149 | 359 1555343399173 44.655560 10.934464 1150 | 360 1555343399192 44.655510 10.934179 1151 | 360 1555343399192 44.655430 10.934435 1152 | 360 1555343399192 44.655560 10.934464 1153 | 361 1555343399212 44.655510 10.934180 1154 | 361 1555343399212 44.655430 10.934435 1155 | 362 1555343399231 44.655510 10.934180 1156 | 362 1555343399231 44.655430 10.934435 1157 | 363 1555343399251 44.655510 10.934180 1158 | 363 1555343399251 44.655430 10.934435 1159 | 364 1555343399270 44.655510 10.934181 1160 | 364 1555343399270 44.655430 10.934435 1161 | 365 1555343399290 44.655510 10.934181 1162 | 365 1555343399290 44.655430 10.934435 1163 | 366 1555343399309 44.655510 10.934181 1164 | 366 1555343399309 44.655430 10.934435 1165 | 367 1555343399330 44.655514 10.934181 1166 | 367 1555343399330 44.655430 10.934435 1167 | 368 1555343399350 44.655514 10.934181 1168 | 368 1555343399350 44.655430 10.934435 1169 | 369 1555343399370 44.655510 10.934182 1170 | 369 1555343399370 44.655552 10.934478 1171 | 369 1555343399370 44.655430 10.934435 1172 | 370 1555343399389 44.655506 10.934182 1173 | 370 1555343399389 44.655430 10.934435 1174 | 371 1555343399409 44.655514 10.934182 1175 | 371 1555343399409 44.655552 10.934478 1176 | 371 1555343399409 44.655430 10.934435 1177 | 372 1555343399428 44.655514 10.934182 1178 | 372 1555343399428 44.655552 10.934478 1179 | 372 1555343399428 44.655430 10.934435 1180 | 373 1555343399449 44.655514 10.934183 1181 | 373 1555343399449 44.655552 10.934484 1182 | 373 1555343399449 44.655430 10.934435 1183 | 373 1555343399449 44.655441 10.934201 1184 | 374 1555343399468 44.655514 10.934183 1185 | 374 1555343399468 44.655552 10.934484 1186 | 374 1555343399468 44.655430 10.934435 1187 | 375 1555343399488 44.655514 10.934183 1188 | 375 1555343399488 44.655552 10.934484 1189 | 375 1555343399488 44.655430 10.934435 1190 | 376 1555343399507 44.655514 10.934183 1191 | 376 1555343399507 44.655552 10.934484 1192 | 376 1555343399507 44.655430 10.934435 1193 | 376 1555343399507 44.655441 10.934201 1194 | 376 1555343399507 44.655502 10.934198 1195 | 377 1555343399527 44.655514 10.934183 1196 | 377 1555343399527 44.655552 10.934484 1197 | 377 1555343399527 44.655430 10.934435 1198 | 377 1555343399527 44.655441 10.934201 1199 | 377 1555343399527 44.655502 10.934198 1200 | 378 1555343399548 44.655518 10.934183 1201 | 378 1555343399548 44.655552 10.934484 1202 | 378 1555343399548 44.655430 10.934435 1203 | 379 1555343399567 44.655518 10.934184 1204 | 379 1555343399567 44.655552 10.934484 1205 | 379 1555343399567 44.655441 10.934200 1206 | 379 1555343399567 44.655430 10.934435 1207 | 379 1555343399567 44.655502 10.934198 1208 | 379 1555343399567 44.655437 10.934196 1209 | 380 1555343399587 44.655518 10.934184 1210 | 380 1555343399587 44.655552 10.934484 1211 | 380 1555343399587 44.655502 10.934199 1212 | 380 1555343399587 44.655430 10.934435 1213 | 380 1555343399587 44.655445 10.934201 1214 | 380 1555343399587 44.655437 10.934197 1215 | 381 1555343399606 44.655518 10.934185 1216 | 381 1555343399606 44.655552 10.934484 1217 | 381 1555343399606 44.655430 10.934435 1218 | 381 1555343399606 44.655502 10.934199 1219 | 381 1555343399606 44.655445 10.934201 1220 | 381 1555343399606 44.655434 10.934197 1221 | 382 1555343399625 44.655518 10.934185 1222 | 382 1555343399625 44.655548 10.934488 1223 | 382 1555343399625 44.655430 10.934435 1224 | 382 1555343399625 44.655502 10.934199 1225 | 383 1555343399647 44.655518 10.934185 1226 | 383 1555343399647 44.655548 10.934488 1227 | 383 1555343399647 44.655430 10.934435 1228 | 383 1555343399647 44.655437 10.934196 1229 | 384 1555343399666 44.655548 10.934488 1230 | 384 1555343399666 44.655571 10.934351 1231 | 384 1555343399666 44.655430 10.934435 1232 | 384 1555343399666 44.655510 10.934187 1233 | 385 1555343399684 44.655567 10.934341 1234 | 385 1555343399684 44.655548 10.934488 1235 | 385 1555343399684 44.655510 10.934188 1236 | 385 1555343399684 44.655437 10.934196 1237 | 385 1555343399684 44.655430 10.934436 1238 | 386 1555343399703 44.655548 10.934488 1239 | 386 1555343399703 44.655518 10.934186 1240 | 386 1555343399703 44.655571 10.934343 1241 | 386 1555343399703 44.655529 10.934379 1242 | 386 1555343399703 44.655430 10.934436 1243 | 386 1555343399703 44.655567 10.934353 1244 | 387 1555343399723 44.655518 10.934187 1245 | 387 1555343399723 44.655567 10.934344 1246 | 387 1555343399723 44.655548 10.934488 1247 | 387 1555343399723 44.655430 10.934435 1248 | 387 1555343399723 44.655441 10.934195 1249 | 387 1555343399723 44.655529 10.934380 1250 | 387 1555343399723 44.655445 10.934202 1251 | 388 1555343399743 44.655518 10.934187 1252 | 388 1555343399743 44.655548 10.934488 1253 | 388 1555343399743 44.655563 10.934349 1254 | 388 1555343399743 44.655430 10.934435 1255 | 388 1555343399743 44.655529 10.934376 1256 | 388 1555343399743 44.655445 10.934202 1257 | 389 1555343399763 44.655521 10.934187 1258 | 389 1555343399763 44.655563 10.934355 1259 | 389 1555343399763 44.655548 10.934494 1260 | 389 1555343399763 44.655430 10.934436 1261 | 389 1555343399763 44.655567 10.934352 1262 | 389 1555343399763 44.655529 10.934376 1263 | 390 1555343399783 44.655521 10.934187 1264 | 390 1555343399783 44.655563 10.934360 1265 | 390 1555343399783 44.655548 10.934493 1266 | 390 1555343399783 44.655529 10.934376 1267 | 390 1555343399783 44.655567 10.934352 1268 | 390 1555343399783 44.655430 10.934435 1269 | 391 1555343399802 44.655518 10.934188 1270 | 391 1555343399802 44.655548 10.934488 1271 | 391 1555343399802 44.655529 10.934376 1272 | 391 1555343399802 44.655567 10.934352 1273 | 391 1555343399802 44.655487 10.934184 1274 | 391 1555343399802 44.655430 10.934435 1275 | 392 1555343399821 44.655518 10.934188 1276 | 392 1555343399821 44.655533 10.934377 1277 | 392 1555343399821 44.655548 10.934494 1278 | 392 1555343399821 44.655567 10.934352 1279 | 392 1555343399821 44.655487 10.934183 1280 | 392 1555343399821 44.655430 10.934435 1281 | 393 1555343399840 44.655529 10.934376 1282 | 393 1555343399840 44.655548 10.934493 1283 | 393 1555343399840 44.655571 10.934348 1284 | 393 1555343399840 44.655518 10.934189 1285 | 393 1555343399840 44.655487 10.934183 1286 | 393 1555343399840 44.655434 10.934430 1287 | 394 1555343399860 44.655548 10.934494 1288 | 394 1555343399860 44.655533 10.934377 1289 | 394 1555343399860 44.655518 10.934190 1290 | 394 1555343399860 44.655571 10.934346 1291 | 394 1555343399860 44.655434 10.934430 1292 | 394 1555343399860 44.655487 10.934183 1293 | 395 1555343399881 44.655548 10.934494 1294 | 395 1555343399881 44.655533 10.934377 1295 | 395 1555343399881 44.655521 10.934189 1296 | 395 1555343399881 44.655487 10.934183 1297 | 395 1555343399881 44.655430 10.934436 1298 | 395 1555343399881 44.655571 10.934348 1299 | 395 1555343399881 44.655567 10.934371 1300 | 396 1555343399900 44.655548 10.934487 1301 | 396 1555343399900 44.655533 10.934377 1302 | 396 1555343399900 44.655571 10.934348 1303 | 396 1555343399900 44.655521 10.934190 1304 | 396 1555343399900 44.655487 10.934183 1305 | 396 1555343399900 44.655430 10.934436 1306 | 396 1555343399900 44.655418 10.934446 1307 | 397 1555343399920 44.655548 10.934488 1308 | 397 1555343399920 44.655529 10.934380 1309 | 397 1555343399920 44.655487 10.934183 1310 | 397 1555343399920 44.655430 10.934436 1311 | 397 1555343399920 44.655571 10.934351 1312 | 397 1555343399920 44.655521 10.934190 1313 | 397 1555343399920 44.655418 10.934446 1314 | 398 1555343399939 44.655548 10.934494 1315 | 398 1555343399939 44.655521 10.934190 1316 | 398 1555343399939 44.655487 10.934183 1317 | 398 1555343399939 44.655529 10.934380 1318 | 398 1555343399939 44.655430 10.934436 1319 | 398 1555343399939 44.655418 10.934445 1320 | 399 1555343399958 44.655521 10.934191 1321 | 399 1555343399958 44.655548 10.934494 1322 | 399 1555343399958 44.655487 10.934183 1323 | 399 1555343399958 44.655529 10.934380 1324 | 399 1555343399958 44.655430 10.934436 1325 | 399 1555343399958 44.655418 10.934445 1326 | 400 1555343399979 44.655521 10.934190 1327 | 400 1555343399979 44.655544 10.934505 1328 | 400 1555343399979 44.655525 10.934388 1329 | 400 1555343399979 44.655487 10.934183 1330 | 400 1555343399979 44.655430 10.934436 1331 | 400 1555343399979 44.655418 10.934445 1332 | 401 1555343399999 44.655521 10.934191 1333 | 401 1555343399999 44.655544 10.934500 1334 | 401 1555343399999 44.655525 10.934388 1335 | 401 1555343399999 44.655430 10.934436 1336 | 401 1555343399999 44.655418 10.934445 1337 | 402 1555343400018 44.655544 10.934500 1338 | 402 1555343400018 44.655525 10.934388 1339 | 402 1555343400018 44.655525 10.934192 1340 | 402 1555343400018 44.655430 10.934436 1341 | 402 1555343400018 44.655418 10.934445 1342 | 403 1555343400037 44.655544 10.934499 1343 | 403 1555343400037 44.655525 10.934388 1344 | 403 1555343400037 44.655525 10.934192 1345 | 403 1555343400037 44.655430 10.934436 1346 | 403 1555343400037 44.655418 10.934446 1347 | 403 1555343400037 44.655571 10.934344 1348 | 404 1555343400056 44.655544 10.934499 1349 | 404 1555343400056 44.655525 10.934388 1350 | 404 1555343400056 44.655525 10.934191 1351 | 404 1555343400056 44.655430 10.934436 1352 | 404 1555343400056 44.655571 10.934344 1353 | 404 1555343400056 44.655418 10.934446 1354 | 405 1555343400076 44.655548 10.934493 1355 | 405 1555343400076 44.655525 10.934388 1356 | 405 1555343400076 44.655529 10.934192 1357 | 405 1555343400076 44.655430 10.934436 1358 | 405 1555343400076 44.655571 10.934344 1359 | 405 1555343400076 44.655418 10.934446 1360 | 406 1555343400095 44.655548 10.934493 1361 | 406 1555343400095 44.655525 10.934388 1362 | 406 1555343400095 44.655525 10.934192 1363 | 406 1555343400095 44.655430 10.934436 1364 | 406 1555343400095 44.655571 10.934344 1365 | 406 1555343400095 44.655418 10.934446 1366 | 407 1555343400115 44.655548 10.934493 1367 | 407 1555343400115 44.655525 10.934388 1368 | 407 1555343400115 44.655430 10.934436 1369 | 407 1555343400115 44.655571 10.934344 1370 | 407 1555343400115 44.655525 10.934192 1371 | 407 1555343400115 44.655418 10.934446 1372 | 408 1555343400135 44.655548 10.934493 1373 | 408 1555343400135 44.655525 10.934388 1374 | 408 1555343400135 44.655430 10.934436 1375 | 408 1555343400135 44.655571 10.934344 1376 | 408 1555343400135 44.655418 10.934446 1377 | 409 1555343400154 44.655544 10.934499 1378 | 409 1555343400154 44.655525 10.934388 1379 | 409 1555343400154 44.655434 10.934430 1380 | 409 1555343400154 44.655571 10.934344 1381 | 409 1555343400154 44.655418 10.934446 1382 | 409 1555343400154 44.655567 10.934547 1383 | 410 1555343400175 44.655544 10.934504 1384 | 410 1555343400175 44.655525 10.934388 1385 | 410 1555343400175 44.655430 10.934436 1386 | 410 1555343400175 44.655418 10.934446 1387 | 410 1555343400175 44.655567 10.934546 1388 | 410 1555343400175 44.655571 10.934346 1389 | 411 1555343400193 44.655544 10.934499 1390 | 411 1555343400193 44.655529 10.934380 1391 | 411 1555343400193 44.655567 10.934542 1392 | 411 1555343400193 44.655430 10.934436 1393 | 411 1555343400193 44.655571 10.934344 1394 | 412 1555343400212 44.655544 10.934499 1395 | 412 1555343400213 44.655529 10.934380 1396 | 412 1555343400213 44.655434 10.934430 1397 | 412 1555343400213 44.655567 10.934541 1398 | 412 1555343400213 44.655571 10.934344 1399 | 412 1555343400213 44.655418 10.934446 1400 | 413 1555343400232 44.655544 10.934499 1401 | 413 1555343400232 44.655529 10.934380 1402 | 413 1555343400232 44.655434 10.934430 1403 | 413 1555343400232 44.655571 10.934344 1404 | 413 1555343400232 44.655567 10.934541 1405 | 414 1555343400253 44.655544 10.934504 1406 | 414 1555343400253 44.655529 10.934380 1407 | 414 1555343400253 44.655567 10.934541 1408 | 414 1555343400253 44.655434 10.934430 1409 | 414 1555343400253 44.655571 10.934344 1410 | 415 1555343400273 44.655544 10.934504 1411 | 415 1555343400273 44.655529 10.934380 1412 | 415 1555343400273 44.655434 10.934430 1413 | 415 1555343400273 44.655571 10.934344 1414 | 416 1555343400293 44.655544 10.934504 1415 | 416 1555343400293 44.655529 10.934380 1416 | 416 1555343400293 44.655434 10.934430 1417 | 416 1555343400293 44.655571 10.934345 1418 | 417 1555343400313 44.655525 10.934388 1419 | 417 1555343400313 44.655434 10.934430 1420 | 417 1555343400313 44.655540 10.934510 1421 | 417 1555343400313 44.655571 10.934345 1422 | 418 1555343400333 44.655529 10.934380 1423 | 418 1555343400333 44.655434 10.934430 1424 | 418 1555343400333 44.655544 10.934504 1425 | 419 1555343400352 44.655544 10.934504 1426 | 419 1555343400352 44.655529 10.934380 1427 | 419 1555343400352 44.655434 10.934430 1428 | 420 1555343400373 44.655544 10.934504 1429 | 420 1555343400373 44.655529 10.934380 1430 | 420 1555343400373 44.655434 10.934430 1431 | 421 1555343400392 44.655544 10.934504 1432 | 421 1555343400392 44.655529 10.934380 1433 | 421 1555343400392 44.655434 10.934430 1434 | 422 1555343400412 44.655544 10.934503 1435 | 422 1555343400412 44.655529 10.934380 1436 | 422 1555343400412 44.655434 10.934430 1437 | 423 1555343400432 44.655544 10.934503 1438 | 423 1555343400432 44.655529 10.934380 1439 | 423 1555343400432 44.655434 10.934430 1440 | 424 1555343400452 44.655529 10.934380 1441 | 424 1555343400452 44.655544 10.934503 1442 | 424 1555343400452 44.655434 10.934430 1443 | 425 1555343400471 44.655544 10.934503 1444 | 425 1555343400471 44.655529 10.934380 1445 | 425 1555343400471 44.655434 10.934430 1446 | 426 1555343400490 44.655544 10.934503 1447 | 426 1555343400490 44.655529 10.934380 1448 | 426 1555343400490 44.655434 10.934430 1449 | 427 1555343400510 44.655544 10.934503 1450 | 427 1555343400510 44.655529 10.934380 1451 | 427 1555343400510 44.655434 10.934430 1452 | 428 1555343400529 44.655529 10.934380 1453 | 428 1555343400529 44.655434 10.934430 1454 | 429 1555343400549 44.655529 10.934380 1455 | 430 1555343400568 44.655529 10.934380 1456 | 430 1555343400568 44.655434 10.934430 1457 | 431 1555343400588 44.655529 10.934380 1458 | 431 1555343400588 44.655434 10.934430 1459 | 432 1555343400607 44.655529 10.934380 1460 | 432 1555343400607 44.655434 10.934430 1461 | 433 1555343400626 44.655529 10.934380 1462 | 433 1555343400626 44.655434 10.934430 1463 | 434 1555343400647 44.655529 10.934380 1464 | 434 1555343400647 44.655540 10.934509 1465 | 434 1555343400647 44.655434 10.934430 1466 | 435 1555343400667 44.655529 10.934380 1467 | 435 1555343400667 44.655540 10.934509 1468 | 435 1555343400667 44.655434 10.934430 1469 | 436 1555343400701 44.655529 10.934380 1470 | 436 1555343400701 44.655434 10.934430 1471 | 437 1555343400721 44.655529 10.934380 1472 | 437 1555343400721 44.655434 10.934430 1473 | 438 1555343400740 44.655529 10.934380 1474 | 438 1555343400740 44.655434 10.934430 1475 | 439 1555343400759 44.655529 10.934380 1476 | 439 1555343400759 44.655434 10.934430 1477 | 440 1555343400779 44.655529 10.934380 1478 | 440 1555343400779 44.655434 10.934430 1479 | 441 1555343400800 44.655529 10.934380 1480 | 441 1555343400800 44.655434 10.934430 1481 | 442 1555343400820 44.655529 10.934380 1482 | 442 1555343400820 44.655434 10.934430 1483 | 443 1555343400839 44.655529 10.934380 1484 | 444 1555343400858 44.655529 10.934380 1485 | 445 1555343400879 44.655529 10.934380 1486 | 445 1555343400879 44.655434 10.934430 1487 | 446 1555343400898 44.655529 10.934380 1488 | 446 1555343400898 44.655434 10.934430 1489 | 446 1555343400898 44.655537 10.934520 1490 | 447 1555343400918 44.655529 10.934380 1491 | 447 1555343400918 44.655537 10.934520 1492 | 447 1555343400918 44.655434 10.934430 1493 | 448 1555343400937 44.655529 10.934380 1494 | 448 1555343400938 44.655434 10.934430 1495 | 449 1555343400957 44.655529 10.934380 1496 | 449 1555343400957 44.655434 10.934430 1497 | 450 1555343400977 44.655529 10.934380 1498 | 450 1555343400977 44.655434 10.934430 1499 | 451 1555343400996 44.655529 10.934380 1500 | 451 1555343400996 44.655434 10.934430 1501 | 452 1555343401016 44.655529 10.934380 1502 | 452 1555343401016 44.655434 10.934430 1503 | 453 1555343401035 44.655529 10.934380 1504 | 453 1555343401035 44.655533 10.934525 1505 | 454 1555343401054 44.655529 10.934380 1506 | 455 1555343401075 44.655529 10.934380 1507 | 456 1555343401093 44.655529 10.934380 1508 | 457 1555343401114 44.655529 10.934380 1509 | 458 1555343401134 44.655529 10.934380 1510 | 459 1555343401153 44.655529 10.934380 1511 | 459 1555343401153 44.655533 10.934525 1512 | 460 1555343401174 44.655533 10.934525 1513 | 460 1555343401174 44.655529 10.934380 1514 | 461 1555343401192 44.655529 10.934380 1515 | 461 1555343401192 44.655533 10.934525 1516 | 462 1555343401213 44.655533 10.934525 1517 | 462 1555343401213 44.655529 10.934380 1518 | 463 1555343401232 44.655533 10.934525 1519 | 463 1555343401232 44.655529 10.934380 1520 | 464 1555343401252 44.655533 10.934525 1521 | 464 1555343401252 44.655529 10.934380 1522 | 465 1555343401273 44.655529 10.934380 1523 | 466 1555343401292 44.655529 10.934380 1524 | 467 1555343401312 44.655529 10.934380 1525 | 467 1555343401312 44.655533 10.934530 1526 | 468 1555343401331 44.655529 10.934380 1527 | 469 1555343401350 44.655529 10.934380 1528 | 470 1555343401369 44.655529 10.934380 1529 | 471 1555343401389 44.655529 10.934380 1530 | 472 1555343401409 44.655529 10.934380 1531 | 473 1555343401430 44.655533 10.934525 1532 | 473 1555343401430 44.655529 10.934380 1533 | 474 1555343401449 44.655533 10.934525 1534 | 474 1555343401449 44.655533 10.934377 1535 | 474 1555343401449 44.655571 10.934344 1536 | 475 1555343401469 44.655533 10.934530 1537 | 475 1555343401469 44.655533 10.934377 1538 | 475 1555343401469 44.655552 10.934222 1539 | 475 1555343401469 44.655571 10.934344 1540 | 475 1555343401469 44.655434 10.934430 1541 | 476 1555343401488 44.655533 10.934530 1542 | 476 1555343401488 44.655533 10.934377 1543 | 476 1555343401488 44.655571 10.934212 1544 | 476 1555343401489 44.655571 10.934344 1545 | 476 1555343401489 44.655434 10.934430 1546 | 477 1555343401509 44.655533 10.934377 1547 | 477 1555343401509 44.655571 10.934212 1548 | 477 1555343401509 44.655552 10.934222 1549 | 477 1555343401509 44.655533 10.934530 1550 | 477 1555343401509 44.655434 10.934430 1551 | 477 1555343401509 44.655571 10.934344 1552 | 478 1555343401528 44.655552 10.934222 1553 | 478 1555343401528 44.655533 10.934377 1554 | 478 1555343401528 44.655434 10.934430 1555 | 478 1555343401528 44.655571 10.934344 1556 | 478 1555343401528 44.655533 10.934530 1557 | 479 1555343401547 44.655533 10.934377 1558 | 479 1555343401547 44.655434 10.934430 1559 | 479 1555343401547 44.655571 10.934344 1560 | 480 1555343401567 44.655533 10.934525 1561 | 480 1555343401567 44.655529 10.934380 1562 | 480 1555343401567 44.655434 10.934430 1563 | 481 1555343401586 44.655533 10.934525 1564 | 481 1555343401586 44.655529 10.934380 1565 | 481 1555343401586 44.655434 10.934430 1566 | 481 1555343401586 44.655556 10.934222 1567 | 482 1555343401607 44.655533 10.934530 1568 | 482 1555343401607 44.655556 10.934223 1569 | 482 1555343401607 44.655533 10.934377 1570 | 482 1555343401607 44.655434 10.934430 1571 | 482 1555343401607 44.655571 10.934344 1572 | 483 1555343401626 44.655533 10.934530 1573 | 483 1555343401626 44.655556 10.934224 1574 | 483 1555343401626 44.655533 10.934377 1575 | 483 1555343401626 44.655434 10.934430 1576 | 483 1555343401626 44.655571 10.934344 1577 | 484 1555343401645 44.655556 10.934224 1578 | 484 1555343401645 44.655533 10.934525 1579 | 484 1555343401645 44.655533 10.934377 1580 | 484 1555343401645 44.655434 10.934430 1581 | 484 1555343401645 44.655571 10.934344 1582 | 485 1555343401664 44.655533 10.934525 1583 | 485 1555343401664 44.655556 10.934224 1584 | 485 1555343401664 44.655533 10.934377 1585 | 485 1555343401664 44.655434 10.934430 1586 | 485 1555343401664 44.655571 10.934344 1587 | 486 1555343401683 44.655556 10.934226 1588 | 486 1555343401683 44.655533 10.934377 1589 | 486 1555343401683 44.655434 10.934430 1590 | 486 1555343401683 44.655533 10.934530 1591 | 486 1555343401683 44.655571 10.934344 1592 | 487 1555343401703 44.655556 10.934226 1593 | 487 1555343401704 44.655533 10.934377 1594 | 487 1555343401704 44.655434 10.934430 1595 | 487 1555343401704 44.655571 10.934344 1596 | 487 1555343401704 44.655533 10.934530 1597 | 488 1555343401722 44.655556 10.934227 1598 | 488 1555343401722 44.655533 10.934377 1599 | 488 1555343401722 44.655434 10.934430 1600 | 488 1555343401722 44.655571 10.934344 1601 | 488 1555343401722 44.655529 10.934537 1602 | 489 1555343401741 44.655556 10.934226 1603 | 489 1555343401741 44.655529 10.934537 1604 | 489 1555343401741 44.655533 10.934377 1605 | 489 1555343401741 44.655434 10.934430 1606 | 489 1555343401741 44.655571 10.934344 1607 | 490 1555343401760 44.655556 10.934227 1608 | 490 1555343401760 44.655529 10.934537 1609 | 490 1555343401760 44.655533 10.934377 1610 | 490 1555343401760 44.655434 10.934430 1611 | 490 1555343401760 44.655571 10.934344 1612 | 491 1555343401779 44.655556 10.934228 1613 | 491 1555343401779 44.655529 10.934537 1614 | 491 1555343401779 44.655533 10.934377 1615 | 491 1555343401779 44.655434 10.934430 1616 | 492 1555343401801 44.655560 10.934228 1617 | 492 1555343401801 44.655529 10.934537 1618 | 492 1555343401801 44.655434 10.934430 1619 | 492 1555343401801 44.655533 10.934377 1620 | 493 1555343401820 44.655434 10.934430 1621 | 493 1555343401820 44.655529 10.934537 1622 | 493 1555343401820 44.655533 10.934377 1623 | 493 1555343401820 44.655556 10.934229 1624 | 494 1555343401840 44.655556 10.934230 1625 | 494 1555343401840 44.655533 10.934377 1626 | 494 1555343401840 44.655434 10.934430 1627 | 494 1555343401840 44.655529 10.934537 1628 | --------------------------------------------------------------------------------