From f2be24bdafd835a6d9ca315719eeb251eb9b6c28 Mon Sep 17 00:00:00 2001 From: nindanaoto Date: Sun, 26 Dec 2021 17:22:47 +0000 Subject: [PATCH 01/17] copy Example_old/ROS --- Examples/ROS/ORB_SLAM3/Asus.yaml | 70 ++ Examples/ROS/ORB_SLAM3/CMakeLists.txt | 116 ++++ Examples/ROS/ORB_SLAM3/manifest.xml | 15 + Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.cc | 640 ++++++++++++++++++ Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.h | 118 ++++ Examples/ROS/ORB_SLAM3/src/AR/ros_mono_ar.cc | 167 +++++ Examples/ROS/ORB_SLAM3/src/ros_mono.cc | 94 +++ .../ROS/ORB_SLAM3/src/ros_mono_inertial.cc | 194 ++++++ Examples/ROS/ORB_SLAM3/src/ros_rgbd.cc | 112 +++ Examples/ROS/ORB_SLAM3/src/ros_stereo.cc | 170 +++++ .../ROS/ORB_SLAM3/src/ros_stereo_inertial.cc | 286 ++++++++ 11 files changed, 1982 insertions(+) create mode 100644 Examples/ROS/ORB_SLAM3/Asus.yaml create mode 100644 Examples/ROS/ORB_SLAM3/CMakeLists.txt create mode 100644 Examples/ROS/ORB_SLAM3/manifest.xml create mode 100644 Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.cc create mode 100644 Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.h create mode 100644 Examples/ROS/ORB_SLAM3/src/AR/ros_mono_ar.cc create mode 100644 Examples/ROS/ORB_SLAM3/src/ros_mono.cc create mode 100644 Examples/ROS/ORB_SLAM3/src/ros_mono_inertial.cc create mode 100644 Examples/ROS/ORB_SLAM3/src/ros_rgbd.cc create mode 100644 Examples/ROS/ORB_SLAM3/src/ros_stereo.cc create mode 100644 Examples/ROS/ORB_SLAM3/src/ros_stereo_inertial.cc diff --git a/Examples/ROS/ORB_SLAM3/Asus.yaml b/Examples/ROS/ORB_SLAM3/Asus.yaml new file mode 100644 index 0000000000..4d0c08ec7d --- /dev/null +++ b/Examples/ROS/ORB_SLAM3/Asus.yaml @@ -0,0 +1,70 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- +Camera.type: "PinHole" + +# Camera calibration and distortion parameters (OpenCV) +Camera.fx: 535.4 +Camera.fy: 539.2 +Camera.cx: 320.1 +Camera.cy: 247.6 + +Camera.k1: 0.0 +Camera.k2: 0.0 +Camera.p1: 0.0 +Camera.p2: 0.0 + +Camera.width: 640 +Camera.height: 480 + +# Camera frames per second +Camera.fps: 30.0 + +# IR projector baseline times fx (aprox.) +Camera.bf: 40.0 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +# Close/Far threshold. Baseline times. +ThDepth: 40.0 + +# Deptmap values factor +DepthMapFactor: 1.0 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize:2 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3 +Viewer.ViewpointX: 0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500 + diff --git a/Examples/ROS/ORB_SLAM3/CMakeLists.txt b/Examples/ROS/ORB_SLAM3/CMakeLists.txt new file mode 100644 index 0000000000..12792fe44b --- /dev/null +++ b/Examples/ROS/ORB_SLAM3/CMakeLists.txt @@ -0,0 +1,116 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +rosbuild_init() + +IF(NOT ROS_BUILD_TYPE) + SET(ROS_BUILD_TYPE Release) +ENDIF() + +MESSAGE("Build type: " ${ROS_BUILD_TYPE}) + +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native") + +# Check C++11 or C++0x support +include(CheckCXXCompilerFlag) +CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) +CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X) +if(COMPILER_SUPPORTS_CXX11) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") + add_definitions(-DCOMPILEDWITHC11) + message(STATUS "Using flag -std=c++11.") +elseif(COMPILER_SUPPORTS_CXX0X) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") + add_definitions(-DCOMPILEDWITHC0X) + message(STATUS "Using flag -std=c++0x.") +else() + message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.") +endif() + +LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/../../../cmake_modules) + +find_package(OpenCV 3.0 QUIET) +if(NOT OpenCV_FOUND) + find_package(OpenCV 2.4.3 QUIET) + if(NOT OpenCV_FOUND) + message(FATAL_ERROR "OpenCV > 2.4.3 not found.") + endif() +endif() + +find_package(Eigen3 3.1.0 REQUIRED) +find_package(Pangolin REQUIRED) + +include_directories( +${PROJECT_SOURCE_DIR} +${PROJECT_SOURCE_DIR}/../../../ +${PROJECT_SOURCE_DIR}/../../../include +${PROJECT_SOURCE_DIR}/../../../include/CameraModels +${Pangolin_INCLUDE_DIRS} +) + +set(LIBS +${OpenCV_LIBS} +${EIGEN3_LIBS} +${Pangolin_LIBRARIES} +${PROJECT_SOURCE_DIR}/../../../Thirdparty/DBoW2/lib/libDBoW2.so +${PROJECT_SOURCE_DIR}/../../../Thirdparty/g2o/lib/libg2o.so +${PROJECT_SOURCE_DIR}/../../../lib/libORB_SLAM3.so +-lboost_system +) + +# Node for monocular camera +rosbuild_add_executable(Mono +src/ros_mono.cc +) + +target_link_libraries(Mono +${LIBS} +) + +# Node for monocular camera (Augmented Reality Demo) +rosbuild_add_executable(MonoAR +src/AR/ros_mono_ar.cc +src/AR/ViewerAR.h +src/AR/ViewerAR.cc +) + +target_link_libraries(MonoAR +${LIBS} +) + +# Node for stereo camera +rosbuild_add_executable(Stereo +src/ros_stereo.cc +) + +target_link_libraries(Stereo +${LIBS} +) + +# Node for RGB-D camera +rosbuild_add_executable(RGBD +src/ros_rgbd.cc +) + +target_link_libraries(RGBD +${LIBS} +) + +# Node for monocular-inertial camera +rosbuild_add_executable(Mono_Inertial +src/ros_mono_inertial.cc +) + +target_link_libraries(Mono_Inertial +${LIBS} +) + +# Node for stereo-inertial camera +rosbuild_add_executable(Stereo_Inertial +src/ros_stereo_inertial.cc +) + +target_link_libraries(Stereo_Inertial +${LIBS} +) diff --git a/Examples/ROS/ORB_SLAM3/manifest.xml b/Examples/ROS/ORB_SLAM3/manifest.xml new file mode 100644 index 0000000000..79e6e6fce9 --- /dev/null +++ b/Examples/ROS/ORB_SLAM3/manifest.xml @@ -0,0 +1,15 @@ + + + ORB_SLAM3 + + Carlos Campos, Richard Elvira, Juan J. Gomez, Jose M.M. Montiel, Juan D. Tardos + GPLv3 + + + + + + + + + diff --git a/Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.cc b/Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.cc new file mode 100644 index 0000000000..dc9f18b7e3 --- /dev/null +++ b/Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.cc @@ -0,0 +1,640 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include "ViewerAR.h" + +#include + +#include +#include +#include + +using namespace std; + +namespace ORB_SLAM3 +{ + +const float eps = 1e-4; + +cv::Mat ExpSO3(const float &x, const float &y, const float &z) +{ + cv::Mat I = cv::Mat::eye(3,3,CV_32F); + const float d2 = x*x+y*y+z*z; + const float d = sqrt(d2); + cv::Mat W = (cv::Mat_(3,3) << 0, -z, y, + z, 0, -x, + -y, x, 0); + if(d(0),v.at(1),v.at(2)); +} + +ViewerAR::ViewerAR(){} + +void ViewerAR::Run() +{ + int w,h,wui; + + cv::Mat im, Tcw; + int status; + vector vKeys; + vector vMPs; + + while(1) + { + GetImagePose(im,Tcw,status,vKeys,vMPs); + if(im.empty()) + cv::waitKey(mT); + else + { + w = im.cols; + h = im.rows; + break; + } + } + + wui=200; + + pangolin::CreateWindowAndBind("Viewer",w+wui,h); + + glEnable(GL_DEPTH_TEST); + glEnable (GL_BLEND); + + pangolin::CreatePanel("menu").SetBounds(0.0,1.0,0.0,pangolin::Attach::Pix(wui)); + pangolin::Var menu_detectplane("menu.Insert Cube",false,false); + pangolin::Var menu_clear("menu.Clear All",false,false); + pangolin::Var menu_drawim("menu.Draw Image",true,true); + pangolin::Var menu_drawcube("menu.Draw Cube",true,true); + pangolin::Var menu_cubesize("menu. Cube Size",0.05,0.01,0.3); + pangolin::Var menu_drawgrid("menu.Draw Grid",true,true); + pangolin::Var menu_ngrid("menu. Grid Elements",3,1,10); + pangolin::Var menu_sizegrid("menu. Element Size",0.05,0.01,0.3); + pangolin::Var menu_drawpoints("menu.Draw Points",false,true); + + pangolin::Var menu_LocalizationMode("menu.Localization Mode",false,true); + bool bLocalizationMode = false; + + pangolin::View& d_image = pangolin::Display("image") + .SetBounds(0,1.0f,pangolin::Attach::Pix(wui),1.0f,(float)w/h) + .SetLock(pangolin::LockLeft, pangolin::LockTop); + + pangolin::GlTexture imageTexture(w,h,GL_RGB,false,0,GL_RGB,GL_UNSIGNED_BYTE); + + pangolin::OpenGlMatrixSpec P = pangolin::ProjectionMatrixRDF_TopLeft(w,h,fx,fy,cx,cy,0.001,1000); + + vector vpPlane; + + while(1) + { + + if(menu_LocalizationMode && !bLocalizationMode) + { + mpSystem->ActivateLocalizationMode(); + bLocalizationMode = true; + } + else if(!menu_LocalizationMode && bLocalizationMode) + { + mpSystem->DeactivateLocalizationMode(); + bLocalizationMode = false; + } + + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + // Activate camera view + d_image.Activate(); + glColor3f(1.0,1.0,1.0); + + // Get last image and its computed pose from SLAM + GetImagePose(im,Tcw,status,vKeys,vMPs); + + // Add text to image + PrintStatus(status,bLocalizationMode,im); + + if(menu_drawpoints) + DrawTrackedPoints(vKeys,vMPs,im); + + // Draw image + if(menu_drawim) + DrawImageTexture(imageTexture,im); + + glClear(GL_DEPTH_BUFFER_BIT); + + // Load camera projection + glMatrixMode(GL_PROJECTION); + P.Load(); + + glMatrixMode(GL_MODELVIEW); + + // Load camera pose + LoadCameraPose(Tcw); + + // Draw virtual things + if(status==2) + { + if(menu_clear) + { + if(!vpPlane.empty()) + { + for(size_t i=0; iMapChanged()) + { + cout << "Map changed. All virtual elements are recomputed!" << endl; + bRecompute = true; + } + } + + for(size_t i=0; iRecompute(); + } + glPushMatrix(); + pPlane->glTpw.Multiply(); + + // Draw cube + if(menu_drawcube) + { + DrawCube(menu_cubesize); + } + + // Draw grid plane + if(menu_drawgrid) + { + DrawPlane(menu_ngrid,menu_sizegrid); + } + + glPopMatrix(); + } + } + } + + + } + + pangolin::FinishFrame(); + usleep(mT*1000); + } + +} + +void ViewerAR::SetImagePose(const cv::Mat &im, const cv::Mat &Tcw, const int &status, const vector &vKeys, const vector &vMPs) +{ + unique_lock lock(mMutexPoseImage); + mImage = im.clone(); + mTcw = Tcw.clone(); + mStatus = status; + mvKeys = vKeys; + mvMPs = vMPs; +} + +void ViewerAR::GetImagePose(cv::Mat &im, cv::Mat &Tcw, int &status, std::vector &vKeys, std::vector &vMPs) +{ + unique_lock lock(mMutexPoseImage); + im = mImage.clone(); + Tcw = mTcw.clone(); + status = mStatus; + vKeys = mvKeys; + vMPs = mvMPs; +} + +void ViewerAR::LoadCameraPose(const cv::Mat &Tcw) +{ + if(!Tcw.empty()) + { + pangolin::OpenGlMatrix M; + + M.m[0] = Tcw.at(0,0); + M.m[1] = Tcw.at(1,0); + M.m[2] = Tcw.at(2,0); + M.m[3] = 0.0; + + M.m[4] = Tcw.at(0,1); + M.m[5] = Tcw.at(1,1); + M.m[6] = Tcw.at(2,1); + M.m[7] = 0.0; + + M.m[8] = Tcw.at(0,2); + M.m[9] = Tcw.at(1,2); + M.m[10] = Tcw.at(2,2); + M.m[11] = 0.0; + + M.m[12] = Tcw.at(0,3); + M.m[13] = Tcw.at(1,3); + M.m[14] = Tcw.at(2,3); + M.m[15] = 1.0; + + M.Load(); + } +} + +void ViewerAR::PrintStatus(const int &status, const bool &bLocMode, cv::Mat &im) +{ + if(!bLocMode) + { + switch(status) + { + case 1: {AddTextToImage("SLAM NOT INITIALIZED",im,255,0,0); break;} + case 2: {AddTextToImage("SLAM ON",im,0,255,0); break;} + case 3: {AddTextToImage("SLAM LOST",im,255,0,0); break;} + } + } + else + { + switch(status) + { + case 1: {AddTextToImage("SLAM NOT INITIALIZED",im,255,0,0); break;} + case 2: {AddTextToImage("LOCALIZATION ON",im,0,255,0); break;} + case 3: {AddTextToImage("LOCALIZATION LOST",im,255,0,0); break;} + } + } +} + +void ViewerAR::AddTextToImage(const string &s, cv::Mat &im, const int r, const int g, const int b) +{ + int l = 10; + //imText.rowRange(im.rows-imText.rows,imText.rows) = cv::Mat::zeros(textSize.height+10,im.cols,im.type()); + cv::putText(im,s,cv::Point(l,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); + cv::putText(im,s,cv::Point(l-1,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); + cv::putText(im,s,cv::Point(l+1,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); + cv::putText(im,s,cv::Point(l-1,im.rows-(l-1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); + cv::putText(im,s,cv::Point(l,im.rows-(l-1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); + cv::putText(im,s,cv::Point(l+1,im.rows-(l-1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); + cv::putText(im,s,cv::Point(l-1,im.rows-(l+1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); + cv::putText(im,s,cv::Point(l,im.rows-(l+1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); + cv::putText(im,s,cv::Point(l+1,im.rows-(l+1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); + + cv::putText(im,s,cv::Point(l,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(r,g,b),2,8); +} + +void ViewerAR::DrawImageTexture(pangolin::GlTexture &imageTexture, cv::Mat &im) +{ + if(!im.empty()) + { + imageTexture.Upload(im.data,GL_RGB,GL_UNSIGNED_BYTE); + imageTexture.RenderToViewportFlipY(); + } +} + +void ViewerAR::DrawCube(const float &size,const float x, const float y, const float z) +{ + pangolin::OpenGlMatrix M = pangolin::OpenGlMatrix::Translate(-x,-size-y,-z); + glPushMatrix(); + M.Multiply(); + pangolin::glDrawColouredCube(-size,size); + glPopMatrix(); +} + +void ViewerAR::DrawPlane(Plane *pPlane, int ndivs, float ndivsize) +{ + glPushMatrix(); + pPlane->glTpw.Multiply(); + DrawPlane(ndivs,ndivsize); + glPopMatrix(); +} + +void ViewerAR::DrawPlane(int ndivs, float ndivsize) +{ + // Plane parallel to x-z at origin with normal -y + const float minx = -ndivs*ndivsize; + const float minz = -ndivs*ndivsize; + const float maxx = ndivs*ndivsize; + const float maxz = ndivs*ndivsize; + + + glLineWidth(2); + glColor3f(0.7f,0.7f,1.0f); + glBegin(GL_LINES); + + for(int n = 0; n<=2*ndivs; n++) + { + glVertex3f(minx+ndivsize*n,0,minz); + glVertex3f(minx+ndivsize*n,0,maxz); + glVertex3f(minx,0,minz+ndivsize*n); + glVertex3f(maxx,0,minz+ndivsize*n); + } + + glEnd(); + +} + +void ViewerAR::DrawTrackedPoints(const std::vector &vKeys, const std::vector &vMPs, cv::Mat &im) +{ + const int N = vKeys.size(); + + + for(int i=0; i &vMPs, const int iterations) +{ + // Retrieve 3D points + vector vPoints; + vPoints.reserve(vMPs.size()); + vector vPointMP; + vPointMP.reserve(vMPs.size()); + + for(size_t i=0; iObservations()>5) + { + vPoints.push_back(pMP->GetWorldPos()); + vPointMP.push_back(pMP); + } + } + } + + const int N = vPoints.size(); + + if(N<50) + return NULL; + + + // Indices for minimum set selection + vector vAllIndices; + vAllIndices.reserve(N); + vector vAvailableIndices; + + for(int i=0; i bestvDist; + + //RANSAC + for(int n=0; n(3,0); + const float b = vt.at(3,1); + const float c = vt.at(3,2); + const float d = vt.at(3,3); + + vector vDistances(N,0); + + const float f = 1.0f/sqrt(a*a+b*b+c*c+d*d); + + for(int i=0; i(0)*a+vPoints[i].at(1)*b+vPoints[i].at(2)*c+d)*f; + } + + vector vSorted = vDistances; + sort(vSorted.begin(),vSorted.end()); + + int nth = max((int)(0.2*N),20); + const float medianDist = vSorted[nth]; + + if(medianDist vbInliers(N,false); + int nInliers = 0; + for(int i=0; i vInlierMPs(nInliers,NULL); + int nin = 0; + for(int i=0; i &vMPs, const cv::Mat &Tcw):mvMPs(vMPs),mTcw(Tcw.clone()) +{ + rang = -3.14f/2+((float)rand()/RAND_MAX)*3.14f; + Recompute(); +} + +void Plane::Recompute() +{ + const int N = mvMPs.size(); + + // Recompute plane with all points + cv::Mat A = cv::Mat(N,4,CV_32F); + A.col(3) = cv::Mat::ones(N,1,CV_32F); + + o = cv::Mat::zeros(3,1,CV_32F); + + int nPoints = 0; + for(int i=0; iisBad()) + { + cv::Mat Xw = pMP->GetWorldPos(); + o+=Xw; + A.row(nPoints).colRange(0,3) = Xw.t(); + nPoints++; + } + } + A.resize(nPoints); + + cv::Mat u,w,vt; + cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV); + + float a = vt.at(3,0); + float b = vt.at(3,1); + float c = vt.at(3,2); + + o = o*(1.0f/nPoints); + const float f = 1.0f/sqrt(a*a+b*b+c*c); + + // Compute XC just the first time + if(XC.empty()) + { + cv::Mat Oc = -mTcw.colRange(0,3).rowRange(0,3).t()*mTcw.rowRange(0,3).col(3); + XC = Oc-o; + } + + if((XC.at(0)*a+XC.at(1)*b+XC.at(2)*c)>0) + { + a=-a; + b=-b; + c=-c; + } + + const float nx = a*f; + const float ny = b*f; + const float nz = c*f; + + n = (cv::Mat_(3,1)<(3,1) << 0.0f, 1.0f, 0.0f); + + cv::Mat v = up.cross(n); + const float sa = cv::norm(v); + const float ca = up.dot(n); + const float ang = atan2(sa,ca); + Tpw = cv::Mat::eye(4,4,CV_32F); + + + Tpw.rowRange(0,3).colRange(0,3) = ExpSO3(v*ang/sa)*ExpSO3(up*rang); + o.copyTo(Tpw.col(3).rowRange(0,3)); + + glTpw.m[0] = Tpw.at(0,0); + glTpw.m[1] = Tpw.at(1,0); + glTpw.m[2] = Tpw.at(2,0); + glTpw.m[3] = 0.0; + + glTpw.m[4] = Tpw.at(0,1); + glTpw.m[5] = Tpw.at(1,1); + glTpw.m[6] = Tpw.at(2,1); + glTpw.m[7] = 0.0; + + glTpw.m[8] = Tpw.at(0,2); + glTpw.m[9] = Tpw.at(1,2); + glTpw.m[10] = Tpw.at(2,2); + glTpw.m[11] = 0.0; + + glTpw.m[12] = Tpw.at(0,3); + glTpw.m[13] = Tpw.at(1,3); + glTpw.m[14] = Tpw.at(2,3); + glTpw.m[15] = 1.0; + +} + +Plane::Plane(const float &nx, const float &ny, const float &nz, const float &ox, const float &oy, const float &oz) +{ + n = (cv::Mat_(3,1)<(3,1)<(3,1) << 0.0f, 1.0f, 0.0f); + + cv::Mat v = up.cross(n); + const float s = cv::norm(v); + const float c = up.dot(n); + const float a = atan2(s,c); + Tpw = cv::Mat::eye(4,4,CV_32F); + const float rang = -3.14f/2+((float)rand()/RAND_MAX)*3.14f; + cout << rang; + Tpw.rowRange(0,3).colRange(0,3) = ExpSO3(v*a/s)*ExpSO3(up*rang); + o.copyTo(Tpw.col(3).rowRange(0,3)); + + glTpw.m[0] = Tpw.at(0,0); + glTpw.m[1] = Tpw.at(1,0); + glTpw.m[2] = Tpw.at(2,0); + glTpw.m[3] = 0.0; + + glTpw.m[4] = Tpw.at(0,1); + glTpw.m[5] = Tpw.at(1,1); + glTpw.m[6] = Tpw.at(2,1); + glTpw.m[7] = 0.0; + + glTpw.m[8] = Tpw.at(0,2); + glTpw.m[9] = Tpw.at(1,2); + glTpw.m[10] = Tpw.at(2,2); + glTpw.m[11] = 0.0; + + glTpw.m[12] = Tpw.at(0,3); + glTpw.m[13] = Tpw.at(1,3); + glTpw.m[14] = Tpw.at(2,3); + glTpw.m[15] = 1.0; +} + +} diff --git a/Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.h b/Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.h new file mode 100644 index 0000000000..ef4c578d46 --- /dev/null +++ b/Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.h @@ -0,0 +1,118 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#ifndef VIEWERAR_H +#define VIEWERAR_H + +#include +#include +#include +#include +#include"../../../include/System.h" + +namespace ORB_SLAM3 +{ + +class Plane +{ +public: + Plane(const std::vector &vMPs, const cv::Mat &Tcw); + Plane(const float &nx, const float &ny, const float &nz, const float &ox, const float &oy, const float &oz); + + void Recompute(); + + //normal + cv::Mat n; + //origin + cv::Mat o; + //arbitrary orientation along normal + float rang; + //transformation from world to the plane + cv::Mat Tpw; + pangolin::OpenGlMatrix glTpw; + //MapPoints that define the plane + std::vector mvMPs; + //camera pose when the plane was first observed (to compute normal direction) + cv::Mat mTcw, XC; +}; + +class ViewerAR +{ +public: + ViewerAR(); + + void SetFPS(const float fps){ + mFPS = fps; + mT=1e3/fps; + } + + void SetSLAM(ORB_SLAM3::System* pSystem){ + mpSystem = pSystem; + } + + // Main thread function. + void Run(); + + void SetCameraCalibration(const float &fx_, const float &fy_, const float &cx_, const float &cy_){ + fx = fx_; fy = fy_; cx = cx_; cy = cy_; + } + + void SetImagePose(const cv::Mat &im, const cv::Mat &Tcw, const int &status, + const std::vector &vKeys, const std::vector &vMPs); + + void GetImagePose(cv::Mat &im, cv::Mat &Tcw, int &status, + std::vector &vKeys, std::vector &vMPs); + +private: + + //SLAM + ORB_SLAM3::System* mpSystem; + + void PrintStatus(const int &status, const bool &bLocMode, cv::Mat &im); + void AddTextToImage(const std::string &s, cv::Mat &im, const int r=0, const int g=0, const int b=0); + void LoadCameraPose(const cv::Mat &Tcw); + void DrawImageTexture(pangolin::GlTexture &imageTexture, cv::Mat &im); + void DrawCube(const float &size, const float x=0, const float y=0, const float z=0); + void DrawPlane(int ndivs, float ndivsize); + void DrawPlane(Plane* pPlane, int ndivs, float ndivsize); + void DrawTrackedPoints(const std::vector &vKeys, const std::vector &vMPs, cv::Mat &im); + + Plane* DetectPlane(const cv::Mat Tcw, const std::vector &vMPs, const int iterations=50); + + // frame rate + float mFPS, mT; + float fx,fy,cx,cy; + + // Last processed image and computed pose by the SLAM + std::mutex mMutexPoseImage; + cv::Mat mTcw; + cv::Mat mImage; + int mStatus; + std::vector mvKeys; + std::vector mvMPs; + +}; + + +} + + +#endif // VIEWERAR_H + + diff --git a/Examples/ROS/ORB_SLAM3/src/AR/ros_mono_ar.cc b/Examples/ROS/ORB_SLAM3/src/AR/ros_mono_ar.cc new file mode 100644 index 0000000000..e26fbca66a --- /dev/null +++ b/Examples/ROS/ORB_SLAM3/src/AR/ros_mono_ar.cc @@ -0,0 +1,167 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include +#include +#include +#include + +#include +#include + +#include +#include + +#include"../../../include/System.h" + +#include"ViewerAR.h" + +using namespace std; + + +ORB_SLAM3::ViewerAR viewerAR; +bool bRGB = true; + +cv::Mat K; +cv::Mat DistCoef; + + +class ImageGrabber +{ +public: + ImageGrabber(ORB_SLAM3::System* pSLAM):mpSLAM(pSLAM){} + + void GrabImage(const sensor_msgs::ImageConstPtr& msg); + + ORB_SLAM3::System* mpSLAM; +}; + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "Mono"); + ros::start(); + + if(argc != 3) + { + cerr << endl << "Usage: rosrun ORB_SLAM3 Mono path_to_vocabulary path_to_settings" << endl; + ros::shutdown(); + return 1; + } + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR,false); + + + cout << endl << endl; + cout << "-----------------------" << endl; + cout << "Augmented Reality Demo" << endl; + cout << "1) Translate the camera to initialize SLAM." << endl; + cout << "2) Look at a planar region and translate the camera." << endl; + cout << "3) Press Insert Cube to place a virtual cube in the plane. " << endl; + cout << endl; + cout << "You can place several cubes in different planes." << endl; + cout << "-----------------------" << endl; + cout << endl; + + + viewerAR.SetSLAM(&SLAM); + + ImageGrabber igb(&SLAM); + + ros::NodeHandle nodeHandler; + ros::Subscriber sub = nodeHandler.subscribe("/camera/image_raw", 1, &ImageGrabber::GrabImage,&igb); + + + cv::FileStorage fSettings(argv[2], cv::FileStorage::READ); + bRGB = static_cast((int)fSettings["Camera.RGB"]); + float fps = fSettings["Camera.fps"]; + viewerAR.SetFPS(fps); + + float fx = fSettings["Camera.fx"]; + float fy = fSettings["Camera.fy"]; + float cx = fSettings["Camera.cx"]; + float cy = fSettings["Camera.cy"]; + + viewerAR.SetCameraCalibration(fx,fy,cx,cy); + + K = cv::Mat::eye(3,3,CV_32F); + K.at(0,0) = fx; + K.at(1,1) = fy; + K.at(0,2) = cx; + K.at(1,2) = cy; + + DistCoef = cv::Mat::zeros(4,1,CV_32F); + DistCoef.at(0) = fSettings["Camera.k1"]; + DistCoef.at(1) = fSettings["Camera.k2"]; + DistCoef.at(2) = fSettings["Camera.p1"]; + DistCoef.at(3) = fSettings["Camera.p2"]; + const float k3 = fSettings["Camera.k3"]; + if(k3!=0) + { + DistCoef.resize(5); + DistCoef.at(4) = k3; + } + + thread tViewer = thread(&ORB_SLAM3::ViewerAR::Run,&viewerAR); + + ros::spin(); + + // Stop all threads + SLAM.Shutdown(); + + // Save camera trajectory + SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt"); + + ros::shutdown(); + + return 0; +} + +void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr& msg) +{ + // Copy the ros image message to cv::Mat. + cv_bridge::CvImageConstPtr cv_ptr; + try + { + cv_ptr = cv_bridge::toCvShare(msg); + } + catch (cv_bridge::Exception& e) + { + ROS_ERROR("cv_bridge exception: %s", e.what()); + return; + } + cv::Mat im = cv_ptr->image.clone(); + cv::Mat imu; + cv::Mat Tcw = mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec()); + int state = mpSLAM->GetTrackingState(); + vector vMPs = mpSLAM->GetTrackedMapPoints(); + vector vKeys = mpSLAM->GetTrackedKeyPointsUn(); + + cv::undistort(im,imu,K,DistCoef); + + if(bRGB) + viewerAR.SetImagePose(imu,Tcw,state,vKeys,vMPs); + else + { + cv::cvtColor(imu,imu,CV_RGB2BGR); + viewerAR.SetImagePose(imu,Tcw,state,vKeys,vMPs); + } +} + + diff --git a/Examples/ROS/ORB_SLAM3/src/ros_mono.cc b/Examples/ROS/ORB_SLAM3/src/ros_mono.cc new file mode 100644 index 0000000000..7e1adb3009 --- /dev/null +++ b/Examples/ROS/ORB_SLAM3/src/ros_mono.cc @@ -0,0 +1,94 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include +#include +#include +#include + +#include +#include + +#include + +#include"../../../include/System.h" + +using namespace std; + +class ImageGrabber +{ +public: + ImageGrabber(ORB_SLAM3::System* pSLAM):mpSLAM(pSLAM){} + + void GrabImage(const sensor_msgs::ImageConstPtr& msg); + + ORB_SLAM3::System* mpSLAM; +}; + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "Mono"); + ros::start(); + + if(argc != 3) + { + cerr << endl << "Usage: rosrun ORB_SLAM3 Mono path_to_vocabulary path_to_settings" << endl; + ros::shutdown(); + return 1; + } + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR,true); + + ImageGrabber igb(&SLAM); + + ros::NodeHandle nodeHandler; + ros::Subscriber sub = nodeHandler.subscribe("/camera/image_raw", 1, &ImageGrabber::GrabImage,&igb); + + ros::spin(); + + // Stop all threads + SLAM.Shutdown(); + + // Save camera trajectory + SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt"); + + ros::shutdown(); + + return 0; +} + +void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr& msg) +{ + // Copy the ros image message to cv::Mat. + cv_bridge::CvImageConstPtr cv_ptr; + try + { + cv_ptr = cv_bridge::toCvShare(msg); + } + catch (cv_bridge::Exception& e) + { + ROS_ERROR("cv_bridge exception: %s", e.what()); + return; + } + + mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec()); +} + + diff --git a/Examples/ROS/ORB_SLAM3/src/ros_mono_inertial.cc b/Examples/ROS/ORB_SLAM3/src/ros_mono_inertial.cc new file mode 100644 index 0000000000..fa3630285c --- /dev/null +++ b/Examples/ROS/ORB_SLAM3/src/ros_mono_inertial.cc @@ -0,0 +1,194 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include"../../../include/System.h" +#include"../include/ImuTypes.h" + +using namespace std; + +class ImuGrabber +{ +public: + ImuGrabber(){}; + void GrabImu(const sensor_msgs::ImuConstPtr &imu_msg); + + queue imuBuf; + std::mutex mBufMutex; +}; + +class ImageGrabber +{ +public: + ImageGrabber(ORB_SLAM3::System* pSLAM, ImuGrabber *pImuGb, const bool bClahe): mpSLAM(pSLAM), mpImuGb(pImuGb), mbClahe(bClahe){} + + void GrabImage(const sensor_msgs::ImageConstPtr& msg); + cv::Mat GetImage(const sensor_msgs::ImageConstPtr &img_msg); + void SyncWithImu(); + + queue img0Buf; + std::mutex mBufMutex; + + ORB_SLAM3::System* mpSLAM; + ImuGrabber *mpImuGb; + + const bool mbClahe; + cv::Ptr mClahe = cv::createCLAHE(3.0, cv::Size(8, 8)); +}; + + + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "Mono_Inertial"); + ros::NodeHandle n("~"); + ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Info); + bool bEqual = false; + if(argc < 3 || argc > 4) + { + cerr << endl << "Usage: rosrun ORB_SLAM3 Mono_Inertial path_to_vocabulary path_to_settings [do_equalize]" << endl; + ros::shutdown(); + return 1; + } + + + if(argc==4) + { + std::string sbEqual(argv[3]); + if(sbEqual == "true") + bEqual = true; + } + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_MONOCULAR,true); + + ImuGrabber imugb; + ImageGrabber igb(&SLAM,&imugb,bEqual); // TODO + + // Maximum delay, 5 seconds + ros::Subscriber sub_imu = n.subscribe("/imu", 1000, &ImuGrabber::GrabImu, &imugb); + ros::Subscriber sub_img0 = n.subscribe("/camera/image_raw", 100, &ImageGrabber::GrabImage,&igb); + + std::thread sync_thread(&ImageGrabber::SyncWithImu,&igb); + + ros::spin(); + + return 0; +} + +void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr &img_msg) +{ + mBufMutex.lock(); + if (!img0Buf.empty()) + img0Buf.pop(); + img0Buf.push(img_msg); + mBufMutex.unlock(); +} + +cv::Mat ImageGrabber::GetImage(const sensor_msgs::ImageConstPtr &img_msg) +{ + // Copy the ros image message to cv::Mat. + cv_bridge::CvImageConstPtr cv_ptr; + try + { + cv_ptr = cv_bridge::toCvShare(img_msg, sensor_msgs::image_encodings::MONO8); + } + catch (cv_bridge::Exception& e) + { + ROS_ERROR("cv_bridge exception: %s", e.what()); + } + + if(cv_ptr->image.type()==0) + { + return cv_ptr->image.clone(); + } + else + { + std::cout << "Error type" << std::endl; + return cv_ptr->image.clone(); + } +} + +void ImageGrabber::SyncWithImu() +{ + while(1) + { + cv::Mat im; + double tIm = 0; + if (!img0Buf.empty()&&!mpImuGb->imuBuf.empty()) + { + tIm = img0Buf.front()->header.stamp.toSec(); + if(tIm>mpImuGb->imuBuf.back()->header.stamp.toSec()) + continue; + { + this->mBufMutex.lock(); + im = GetImage(img0Buf.front()); + img0Buf.pop(); + this->mBufMutex.unlock(); + } + + vector vImuMeas; + mpImuGb->mBufMutex.lock(); + if(!mpImuGb->imuBuf.empty()) + { + // Load imu measurements from buffer + vImuMeas.clear(); + while(!mpImuGb->imuBuf.empty() && mpImuGb->imuBuf.front()->header.stamp.toSec()<=tIm) + { + double t = mpImuGb->imuBuf.front()->header.stamp.toSec(); + cv::Point3f acc(mpImuGb->imuBuf.front()->linear_acceleration.x, mpImuGb->imuBuf.front()->linear_acceleration.y, mpImuGb->imuBuf.front()->linear_acceleration.z); + cv::Point3f gyr(mpImuGb->imuBuf.front()->angular_velocity.x, mpImuGb->imuBuf.front()->angular_velocity.y, mpImuGb->imuBuf.front()->angular_velocity.z); + vImuMeas.push_back(ORB_SLAM3::IMU::Point(acc,gyr,t)); + mpImuGb->imuBuf.pop(); + } + } + mpImuGb->mBufMutex.unlock(); + if(mbClahe) + mClahe->apply(im,im); + + mpSLAM->TrackMonocular(im,tIm,vImuMeas); + } + + std::chrono::milliseconds tSleep(1); + std::this_thread::sleep_for(tSleep); + } +} + +void ImuGrabber::GrabImu(const sensor_msgs::ImuConstPtr &imu_msg) +{ + mBufMutex.lock(); + imuBuf.push(imu_msg); + mBufMutex.unlock(); + return; +} + + diff --git a/Examples/ROS/ORB_SLAM3/src/ros_rgbd.cc b/Examples/ROS/ORB_SLAM3/src/ros_rgbd.cc new file mode 100644 index 0000000000..faf6131541 --- /dev/null +++ b/Examples/ROS/ORB_SLAM3/src/ros_rgbd.cc @@ -0,0 +1,112 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include + +#include"../../../include/System.h" + +using namespace std; + +class ImageGrabber +{ +public: + ImageGrabber(ORB_SLAM3::System* pSLAM):mpSLAM(pSLAM){} + + void GrabRGBD(const sensor_msgs::ImageConstPtr& msgRGB,const sensor_msgs::ImageConstPtr& msgD); + + ORB_SLAM3::System* mpSLAM; +}; + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "RGBD"); + ros::start(); + + if(argc != 3) + { + cerr << endl << "Usage: rosrun ORB_SLAM3 RGBD path_to_vocabulary path_to_settings" << endl; + ros::shutdown(); + return 1; + } + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::RGBD,true); + + ImageGrabber igb(&SLAM); + + ros::NodeHandle nh; + + message_filters::Subscriber rgb_sub(nh, "/camera/rgb/image_raw", 100); + message_filters::Subscriber depth_sub(nh, "camera/depth_registered/image_raw", 100); + typedef message_filters::sync_policies::ApproximateTime sync_pol; + message_filters::Synchronizer sync(sync_pol(10), rgb_sub,depth_sub); + sync.registerCallback(boost::bind(&ImageGrabber::GrabRGBD,&igb,_1,_2)); + + ros::spin(); + + // Stop all threads + SLAM.Shutdown(); + + // Save camera trajectory + SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt"); + + ros::shutdown(); + + return 0; +} + +void ImageGrabber::GrabRGBD(const sensor_msgs::ImageConstPtr& msgRGB,const sensor_msgs::ImageConstPtr& msgD) +{ + // Copy the ros image message to cv::Mat. + cv_bridge::CvImageConstPtr cv_ptrRGB; + try + { + cv_ptrRGB = cv_bridge::toCvShare(msgRGB); + } + catch (cv_bridge::Exception& e) + { + ROS_ERROR("cv_bridge exception: %s", e.what()); + return; + } + + cv_bridge::CvImageConstPtr cv_ptrD; + try + { + cv_ptrD = cv_bridge::toCvShare(msgD); + } + catch (cv_bridge::Exception& e) + { + ROS_ERROR("cv_bridge exception: %s", e.what()); + return; + } + mpSLAM->TrackRGBD(cv_ptrRGB->image,cv_ptrD->image,cv_ptrRGB->header.stamp.toSec()); +} + + diff --git a/Examples/ROS/ORB_SLAM3/src/ros_stereo.cc b/Examples/ROS/ORB_SLAM3/src/ros_stereo.cc new file mode 100644 index 0000000000..030fdb6af8 --- /dev/null +++ b/Examples/ROS/ORB_SLAM3/src/ros_stereo.cc @@ -0,0 +1,170 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include + +#include"../../../include/System.h" + +using namespace std; + +class ImageGrabber +{ +public: + ImageGrabber(ORB_SLAM3::System* pSLAM):mpSLAM(pSLAM){} + + void GrabStereo(const sensor_msgs::ImageConstPtr& msgLeft,const sensor_msgs::ImageConstPtr& msgRight); + + ORB_SLAM3::System* mpSLAM; + bool do_rectify; + cv::Mat M1l,M2l,M1r,M2r; +}; + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "RGBD"); + ros::start(); + + if(argc != 4) + { + cerr << endl << "Usage: rosrun ORB_SLAM3 Stereo path_to_vocabulary path_to_settings do_rectify" << endl; + ros::shutdown(); + return 1; + } + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::STEREO,true); + + ImageGrabber igb(&SLAM); + + stringstream ss(argv[3]); + ss >> boolalpha >> igb.do_rectify; + + if(igb.do_rectify) + { + // Load settings related to stereo calibration + cv::FileStorage fsSettings(argv[2], cv::FileStorage::READ); + if(!fsSettings.isOpened()) + { + cerr << "ERROR: Wrong path to settings" << endl; + return -1; + } + + cv::Mat K_l, K_r, P_l, P_r, R_l, R_r, D_l, D_r; + fsSettings["LEFT.K"] >> K_l; + fsSettings["RIGHT.K"] >> K_r; + + fsSettings["LEFT.P"] >> P_l; + fsSettings["RIGHT.P"] >> P_r; + + fsSettings["LEFT.R"] >> R_l; + fsSettings["RIGHT.R"] >> R_r; + + fsSettings["LEFT.D"] >> D_l; + fsSettings["RIGHT.D"] >> D_r; + + int rows_l = fsSettings["LEFT.height"]; + int cols_l = fsSettings["LEFT.width"]; + int rows_r = fsSettings["RIGHT.height"]; + int cols_r = fsSettings["RIGHT.width"]; + + if(K_l.empty() || K_r.empty() || P_l.empty() || P_r.empty() || R_l.empty() || R_r.empty() || D_l.empty() || D_r.empty() || + rows_l==0 || rows_r==0 || cols_l==0 || cols_r==0) + { + cerr << "ERROR: Calibration parameters to rectify stereo are missing!" << endl; + return -1; + } + + cv::initUndistortRectifyMap(K_l,D_l,R_l,P_l.rowRange(0,3).colRange(0,3),cv::Size(cols_l,rows_l),CV_32F,igb.M1l,igb.M2l); + cv::initUndistortRectifyMap(K_r,D_r,R_r,P_r.rowRange(0,3).colRange(0,3),cv::Size(cols_r,rows_r),CV_32F,igb.M1r,igb.M2r); + } + + ros::NodeHandle nh; + + message_filters::Subscriber left_sub(nh, "/camera/left/image_raw", 1); + message_filters::Subscriber right_sub(nh, "/camera/right/image_raw", 1); + typedef message_filters::sync_policies::ApproximateTime sync_pol; + message_filters::Synchronizer sync(sync_pol(10), left_sub,right_sub); + sync.registerCallback(boost::bind(&ImageGrabber::GrabStereo,&igb,_1,_2)); + + ros::spin(); + + // Stop all threads + SLAM.Shutdown(); + + // Save camera trajectory + SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory_TUM_Format.txt"); + SLAM.SaveTrajectoryTUM("FrameTrajectory_TUM_Format.txt"); + SLAM.SaveTrajectoryKITTI("FrameTrajectory_KITTI_Format.txt"); + + ros::shutdown(); + + return 0; +} + +void ImageGrabber::GrabStereo(const sensor_msgs::ImageConstPtr& msgLeft,const sensor_msgs::ImageConstPtr& msgRight) +{ + // Copy the ros image message to cv::Mat. + cv_bridge::CvImageConstPtr cv_ptrLeft; + try + { + cv_ptrLeft = cv_bridge::toCvShare(msgLeft); + } + catch (cv_bridge::Exception& e) + { + ROS_ERROR("cv_bridge exception: %s", e.what()); + return; + } + + cv_bridge::CvImageConstPtr cv_ptrRight; + try + { + cv_ptrRight = cv_bridge::toCvShare(msgRight); + } + catch (cv_bridge::Exception& e) + { + ROS_ERROR("cv_bridge exception: %s", e.what()); + return; + } + + if(do_rectify) + { + cv::Mat imLeft, imRight; + cv::remap(cv_ptrLeft->image,imLeft,M1l,M2l,cv::INTER_LINEAR); + cv::remap(cv_ptrRight->image,imRight,M1r,M2r,cv::INTER_LINEAR); + mpSLAM->TrackStereo(imLeft,imRight,cv_ptrLeft->header.stamp.toSec()); + } + else + { + mpSLAM->TrackStereo(cv_ptrLeft->image,cv_ptrRight->image,cv_ptrLeft->header.stamp.toSec()); + } + +} + + diff --git a/Examples/ROS/ORB_SLAM3/src/ros_stereo_inertial.cc b/Examples/ROS/ORB_SLAM3/src/ros_stereo_inertial.cc new file mode 100644 index 0000000000..231ad72c07 --- /dev/null +++ b/Examples/ROS/ORB_SLAM3/src/ros_stereo_inertial.cc @@ -0,0 +1,286 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include"../../../include/System.h" +#include"../include/ImuTypes.h" + +using namespace std; + +class ImuGrabber +{ +public: + ImuGrabber(){}; + void GrabImu(const sensor_msgs::ImuConstPtr &imu_msg); + + queue imuBuf; + std::mutex mBufMutex; +}; + +class ImageGrabber +{ +public: + ImageGrabber(ORB_SLAM3::System* pSLAM, ImuGrabber *pImuGb, const bool bRect, const bool bClahe): mpSLAM(pSLAM), mpImuGb(pImuGb), do_rectify(bRect), mbClahe(bClahe){} + + void GrabImageLeft(const sensor_msgs::ImageConstPtr& msg); + void GrabImageRight(const sensor_msgs::ImageConstPtr& msg); + cv::Mat GetImage(const sensor_msgs::ImageConstPtr &img_msg); + void SyncWithImu(); + + queue imgLeftBuf, imgRightBuf; + std::mutex mBufMutexLeft,mBufMutexRight; + + ORB_SLAM3::System* mpSLAM; + ImuGrabber *mpImuGb; + + const bool do_rectify; + cv::Mat M1l,M2l,M1r,M2r; + + const bool mbClahe; + cv::Ptr mClahe = cv::createCLAHE(3.0, cv::Size(8, 8)); +}; + + + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "Stereo_Inertial"); + ros::NodeHandle n("~"); + ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Info); + bool bEqual = false; + if(argc < 4 || argc > 5) + { + cerr << endl << "Usage: rosrun ORB_SLAM3 Stereo_Inertial path_to_vocabulary path_to_settings do_rectify [do_equalize]" << endl; + ros::shutdown(); + return 1; + } + + std::string sbRect(argv[3]); + if(argc==5) + { + std::string sbEqual(argv[4]); + if(sbEqual == "true") + bEqual = true; + } + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_STEREO,true); + + ImuGrabber imugb; + ImageGrabber igb(&SLAM,&imugb,sbRect == "true",bEqual); + + if(igb.do_rectify) + { + // Load settings related to stereo calibration + cv::FileStorage fsSettings(argv[2], cv::FileStorage::READ); + if(!fsSettings.isOpened()) + { + cerr << "ERROR: Wrong path to settings" << endl; + return -1; + } + + cv::Mat K_l, K_r, P_l, P_r, R_l, R_r, D_l, D_r; + fsSettings["LEFT.K"] >> K_l; + fsSettings["RIGHT.K"] >> K_r; + + fsSettings["LEFT.P"] >> P_l; + fsSettings["RIGHT.P"] >> P_r; + + fsSettings["LEFT.R"] >> R_l; + fsSettings["RIGHT.R"] >> R_r; + + fsSettings["LEFT.D"] >> D_l; + fsSettings["RIGHT.D"] >> D_r; + + int rows_l = fsSettings["LEFT.height"]; + int cols_l = fsSettings["LEFT.width"]; + int rows_r = fsSettings["RIGHT.height"]; + int cols_r = fsSettings["RIGHT.width"]; + + if(K_l.empty() || K_r.empty() || P_l.empty() || P_r.empty() || R_l.empty() || R_r.empty() || D_l.empty() || D_r.empty() || + rows_l==0 || rows_r==0 || cols_l==0 || cols_r==0) + { + cerr << "ERROR: Calibration parameters to rectify stereo are missing!" << endl; + return -1; + } + + cv::initUndistortRectifyMap(K_l,D_l,R_l,P_l.rowRange(0,3).colRange(0,3),cv::Size(cols_l,rows_l),CV_32F,igb.M1l,igb.M2l); + cv::initUndistortRectifyMap(K_r,D_r,R_r,P_r.rowRange(0,3).colRange(0,3),cv::Size(cols_r,rows_r),CV_32F,igb.M1r,igb.M2r); + } + + // Maximum delay, 5 seconds + ros::Subscriber sub_imu = n.subscribe("/imu", 1000, &ImuGrabber::GrabImu, &imugb); + ros::Subscriber sub_img_left = n.subscribe("/camera/left/image_raw", 100, &ImageGrabber::GrabImageLeft,&igb); + ros::Subscriber sub_img_right = n.subscribe("/camera/right/image_raw", 100, &ImageGrabber::GrabImageRight,&igb); + + std::thread sync_thread(&ImageGrabber::SyncWithImu,&igb); + + ros::spin(); + + return 0; +} + + + +void ImageGrabber::GrabImageLeft(const sensor_msgs::ImageConstPtr &img_msg) +{ + mBufMutexLeft.lock(); + if (!imgLeftBuf.empty()) + imgLeftBuf.pop(); + imgLeftBuf.push(img_msg); + mBufMutexLeft.unlock(); +} + +void ImageGrabber::GrabImageRight(const sensor_msgs::ImageConstPtr &img_msg) +{ + mBufMutexRight.lock(); + if (!imgRightBuf.empty()) + imgRightBuf.pop(); + imgRightBuf.push(img_msg); + mBufMutexRight.unlock(); +} + +cv::Mat ImageGrabber::GetImage(const sensor_msgs::ImageConstPtr &img_msg) +{ + // Copy the ros image message to cv::Mat. + cv_bridge::CvImageConstPtr cv_ptr; + try + { + cv_ptr = cv_bridge::toCvShare(img_msg, sensor_msgs::image_encodings::MONO8); + } + catch (cv_bridge::Exception& e) + { + ROS_ERROR("cv_bridge exception: %s", e.what()); + } + + if(cv_ptr->image.type()==0) + { + return cv_ptr->image.clone(); + } + else + { + std::cout << "Error type" << std::endl; + return cv_ptr->image.clone(); + } +} + +void ImageGrabber::SyncWithImu() +{ + const double maxTimeDiff = 0.01; + while(1) + { + cv::Mat imLeft, imRight; + double tImLeft = 0, tImRight = 0; + if (!imgLeftBuf.empty()&&!imgRightBuf.empty()&&!mpImuGb->imuBuf.empty()) + { + tImLeft = imgLeftBuf.front()->header.stamp.toSec(); + tImRight = imgRightBuf.front()->header.stamp.toSec(); + + this->mBufMutexRight.lock(); + while((tImLeft-tImRight)>maxTimeDiff && imgRightBuf.size()>1) + { + imgRightBuf.pop(); + tImRight = imgRightBuf.front()->header.stamp.toSec(); + } + this->mBufMutexRight.unlock(); + + this->mBufMutexLeft.lock(); + while((tImRight-tImLeft)>maxTimeDiff && imgLeftBuf.size()>1) + { + imgLeftBuf.pop(); + tImLeft = imgLeftBuf.front()->header.stamp.toSec(); + } + this->mBufMutexLeft.unlock(); + + if((tImLeft-tImRight)>maxTimeDiff || (tImRight-tImLeft)>maxTimeDiff) + { + // std::cout << "big time difference" << std::endl; + continue; + } + if(tImLeft>mpImuGb->imuBuf.back()->header.stamp.toSec()) + continue; + + this->mBufMutexLeft.lock(); + imLeft = GetImage(imgLeftBuf.front()); + imgLeftBuf.pop(); + this->mBufMutexLeft.unlock(); + + this->mBufMutexRight.lock(); + imRight = GetImage(imgRightBuf.front()); + imgRightBuf.pop(); + this->mBufMutexRight.unlock(); + + vector vImuMeas; + mpImuGb->mBufMutex.lock(); + if(!mpImuGb->imuBuf.empty()) + { + // Load imu measurements from buffer + vImuMeas.clear(); + while(!mpImuGb->imuBuf.empty() && mpImuGb->imuBuf.front()->header.stamp.toSec()<=tImLeft) + { + double t = mpImuGb->imuBuf.front()->header.stamp.toSec(); + cv::Point3f acc(mpImuGb->imuBuf.front()->linear_acceleration.x, mpImuGb->imuBuf.front()->linear_acceleration.y, mpImuGb->imuBuf.front()->linear_acceleration.z); + cv::Point3f gyr(mpImuGb->imuBuf.front()->angular_velocity.x, mpImuGb->imuBuf.front()->angular_velocity.y, mpImuGb->imuBuf.front()->angular_velocity.z); + vImuMeas.push_back(ORB_SLAM3::IMU::Point(acc,gyr,t)); + mpImuGb->imuBuf.pop(); + } + } + mpImuGb->mBufMutex.unlock(); + if(mbClahe) + { + mClahe->apply(imLeft,imLeft); + mClahe->apply(imRight,imRight); + } + + if(do_rectify) + { + cv::remap(imLeft,imLeft,M1l,M2l,cv::INTER_LINEAR); + cv::remap(imRight,imRight,M1r,M2r,cv::INTER_LINEAR); + } + + mpSLAM->TrackStereo(imLeft,imRight,tImLeft,vImuMeas); + + std::chrono::milliseconds tSleep(1); + std::this_thread::sleep_for(tSleep); + } + } +} + +void ImuGrabber::GrabImu(const sensor_msgs::ImuConstPtr &imu_msg) +{ + mBufMutex.lock(); + imuBuf.push(imu_msg); + mBufMutex.unlock(); + return; +} + + From d451e9c3f688186fc1bc8d4695282746c8a7c878 Mon Sep 17 00:00:00 2001 From: nindanaoto Date: Mon, 27 Dec 2021 01:05:56 +0000 Subject: [PATCH 02/17] compilable ROS Example --- Examples/ROS/ORB_SLAM3/CMakeLists.txt | 3 ++- Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.cc | 10 ++++++++-- Examples/ROS/ORB_SLAM3/src/AR/ros_mono_ar.cc | 10 ++++++++-- 3 files changed, 18 insertions(+), 5 deletions(-) diff --git a/Examples/ROS/ORB_SLAM3/CMakeLists.txt b/Examples/ROS/ORB_SLAM3/CMakeLists.txt index 12792fe44b..dd5861d057 100644 --- a/Examples/ROS/ORB_SLAM3/CMakeLists.txt +++ b/Examples/ROS/ORB_SLAM3/CMakeLists.txt @@ -30,7 +30,7 @@ endif() LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/../../../cmake_modules) -find_package(OpenCV 3.0 QUIET) +find_package(OpenCV 4.5 QUIET) if(NOT OpenCV_FOUND) find_package(OpenCV 2.4.3 QUIET) if(NOT OpenCV_FOUND) @@ -46,6 +46,7 @@ ${PROJECT_SOURCE_DIR} ${PROJECT_SOURCE_DIR}/../../../ ${PROJECT_SOURCE_DIR}/../../../include ${PROJECT_SOURCE_DIR}/../../../include/CameraModels +${PROJECT_SOURCE_DIR}/../../../Thirdparty/Sophus ${Pangolin_INCLUDE_DIRS} ) diff --git a/Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.cc b/Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.cc index dc9f18b7e3..4a8973f5e5 100644 --- a/Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.cc +++ b/Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.cc @@ -20,6 +20,9 @@ #include +#include +#include + #include #include #include @@ -402,7 +405,9 @@ Plane* ViewerAR::DetectPlane(const cv::Mat Tcw, const std::vector &vM { if(pMP->Observations()>5) { - vPoints.push_back(pMP->GetWorldPos()); + cv::Mat WorldPos; + cv::eigen2cv(pMP->GetWorldPos(), WorldPos); + vPoints.push_back(WorldPos); vPointMP.push_back(pMP); } } @@ -527,7 +532,8 @@ void Plane::Recompute() MapPoint* pMP = mvMPs[i]; if(!pMP->isBad()) { - cv::Mat Xw = pMP->GetWorldPos(); + cv::Mat Xw; + cv::eigen2cv(pMP->GetWorldPos(), Xw); o+=Xw; A.row(nPoints).colRange(0,3) = Xw.t(); nPoints++; diff --git a/Examples/ROS/ORB_SLAM3/src/AR/ros_mono_ar.cc b/Examples/ROS/ORB_SLAM3/src/AR/ros_mono_ar.cc index e26fbca66a..0a0b36bbea 100644 --- a/Examples/ROS/ORB_SLAM3/src/AR/ros_mono_ar.cc +++ b/Examples/ROS/ORB_SLAM3/src/AR/ros_mono_ar.cc @@ -23,9 +23,12 @@ #include #include -#include +#include + +#include #include +#include #include #include"../../../include/System.h" @@ -148,7 +151,10 @@ void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr& msg) } cv::Mat im = cv_ptr->image.clone(); cv::Mat imu; - cv::Mat Tcw = mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec()); + cv::Mat Tcw; + Sophus::SE3f Tcw_SE3f = mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec()); + Eigen::Matrix4f Tcw_Matrix = Tcw_SE3f.matrix(); + cv::eigen2cv(Tcw_Matrix, Tcw); int state = mpSLAM->GetTrackingState(); vector vMPs = mpSLAM->GetTrackedMapPoints(); vector vKeys = mpSLAM->GetTrackedKeyPointsUn(); From ec9ea0a24b4c5e2181a912751ad01bd17d31ea46 Mon Sep 17 00:00:00 2001 From: nindanaoto Date: Mon, 27 Dec 2021 06:30:08 +0000 Subject: [PATCH 03/17] Use OpenCV 4.4 --- Examples/ROS/ORB_SLAM3/CMakeLists.txt | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/Examples/ROS/ORB_SLAM3/CMakeLists.txt b/Examples/ROS/ORB_SLAM3/CMakeLists.txt index dd5861d057..a1cc580a17 100644 --- a/Examples/ROS/ORB_SLAM3/CMakeLists.txt +++ b/Examples/ROS/ORB_SLAM3/CMakeLists.txt @@ -30,12 +30,9 @@ endif() LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/../../../cmake_modules) -find_package(OpenCV 4.5 QUIET) +find_package(OpenCV 4.4 QUIET) if(NOT OpenCV_FOUND) - find_package(OpenCV 2.4.3 QUIET) - if(NOT OpenCV_FOUND) - message(FATAL_ERROR "OpenCV > 2.4.3 not found.") - endif() + message(FATAL_ERROR "OpenCV > 4.4 not found.") endif() find_package(Eigen3 3.1.0 REQUIRED) From 11198781b15e46563cb8193f467628dd0b275cd1 Mon Sep 17 00:00:00 2001 From: olayasturias Date: Thu, 31 Mar 2022 11:49:11 +0200 Subject: [PATCH 04/17] fixing problems --- CMakeLists.txt | 2 +- Examples/ROS/ORB_SLAM3/CMakeLists.txt | 2 +- build.sh | 1 + 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 016e74354d..30afb8e02b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -30,7 +30,7 @@ endif() LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules) -find_package(OpenCV 4.4) +find_package(OpenCV 3.2) if(NOT OpenCV_FOUND) message(FATAL_ERROR "OpenCV > 4.4 not found.") endif() diff --git a/Examples/ROS/ORB_SLAM3/CMakeLists.txt b/Examples/ROS/ORB_SLAM3/CMakeLists.txt index a1cc580a17..e1f44e8803 100644 --- a/Examples/ROS/ORB_SLAM3/CMakeLists.txt +++ b/Examples/ROS/ORB_SLAM3/CMakeLists.txt @@ -30,7 +30,7 @@ endif() LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/../../../cmake_modules) -find_package(OpenCV 4.4 QUIET) +find_package(OpenCV 3.2 QUIET) if(NOT OpenCV_FOUND) message(FATAL_ERROR "OpenCV > 4.4 not found.") endif() diff --git a/build.sh b/build.sh index 96d1c0941c..45b7065309 100755 --- a/build.sh +++ b/build.sh @@ -23,6 +23,7 @@ mkdir build cd build cmake .. -DCMAKE_BUILD_TYPE=Release make -j +make install cd ../../../ From cc577abc7269ae20fbb13b9c7b5d8624e64ccae0 Mon Sep 17 00:00:00 2001 From: olayasturias Date: Sun, 4 Sep 2022 00:18:56 +0200 Subject: [PATCH 05/17] MIMIR loader --- .vscode/settings.json | 7 + CMakeLists.txt | 12 + Examples/Monocular-Inertial/MIMIR.yaml | 91 ++++ .../Monocular-Inertial/mono_inertial_euroc.cc | 4 +- .../Monocular-Inertial/mono_inertial_mimir.cc | 310 ++++++++++++ Examples/Monocular/C922.yaml | 77 +++ Examples/Monocular/EuRoC.yaml | 3 +- Examples/Monocular/MIMIR.yaml | 77 +++ Examples/Monocular/mono_mimir.cc | 230 +++++++++ Examples/Stereo/MIMIR.yaml | 96 ++++ Examples/Stereo/stereo_mimir.cc | 212 ++++++++ include/System.h | 6 + src/System.cc | 478 +++++++++++++++++- 13 files changed, 1583 insertions(+), 20 deletions(-) create mode 100644 .vscode/settings.json create mode 100644 Examples/Monocular-Inertial/MIMIR.yaml create mode 100644 Examples/Monocular-Inertial/mono_inertial_mimir.cc create mode 100755 Examples/Monocular/C922.yaml create mode 100644 Examples/Monocular/MIMIR.yaml create mode 100644 Examples/Monocular/mono_mimir.cc create mode 100644 Examples/Stereo/MIMIR.yaml create mode 100644 Examples/Stereo/stereo_mimir.cc diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 0000000000..e5be246e8f --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,7 @@ +{ + "files.associations": { + "iostream": "cpp", + "ostream": "cpp", + "filesystem": "cpp" + } +} \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt index 30afb8e02b..5a87d4e2f7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -172,6 +172,10 @@ add_executable(stereo_euroc Examples/Stereo/stereo_euroc.cc) target_link_libraries(stereo_euroc ${PROJECT_NAME}) +add_executable(stereo_mimir + Examples/Stereo/stereo_mimir.cc) +target_link_libraries(stereo_mimir ${PROJECT_NAME}) + add_executable(stereo_tum_vi Examples/Stereo/stereo_tum_vi.cc) target_link_libraries(stereo_tum_vi ${PROJECT_NAME}) @@ -201,6 +205,10 @@ add_executable(mono_euroc Examples/Monocular/mono_euroc.cc) target_link_libraries(mono_euroc ${PROJECT_NAME}) +add_executable(mono_mimir + Examples/Monocular/mono_mimir.cc) +target_link_libraries(mono_mimir ${PROJECT_NAME}) + add_executable(mono_tum_vi Examples/Monocular/mono_tum_vi.cc) target_link_libraries(mono_tum_vi ${PROJECT_NAME}) @@ -222,6 +230,10 @@ add_executable(mono_inertial_euroc Examples/Monocular-Inertial/mono_inertial_euroc.cc) target_link_libraries(mono_inertial_euroc ${PROJECT_NAME}) +add_executable(mono_inertial_mimir + Examples/Monocular-Inertial/mono_inertial_mimir.cc) +target_link_libraries(mono_inertial_mimir ${PROJECT_NAME}) + add_executable(mono_inertial_tum_vi Examples/Monocular-Inertial/mono_inertial_tum_vi.cc) target_link_libraries(mono_inertial_tum_vi ${PROJECT_NAME}) diff --git a/Examples/Monocular-Inertial/MIMIR.yaml b/Examples/Monocular-Inertial/MIMIR.yaml new file mode 100644 index 0000000000..ad51e992e2 --- /dev/null +++ b/Examples/Monocular-Inertial/MIMIR.yaml @@ -0,0 +1,91 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- +File.version: "1.0" + +Camera.type: "PinHole" + +# Camera calibration and distortion parameters (OpenCV) +Camera1.fx: 252.07470703125 +Camera1.fy: 252.07470703125 +Camera1.cx: 360.0 +Camera1.cy: 270.0 + +Camera1.k1: 0.0 +Camera1.k2: 0.0 +Camera1.p1: 0.0 +Camera1.p2: 0.0 + +Camera.width: 720 +Camera.height: 540 + +Camera.newWidth: 720 +Camera.newHeight: 540 + +# Camera frames per second +Camera.fps: 30 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +# Transformation from camera to body-frame (imu) +IMU.T_b_c1: !!opencv-matrix + rows: 4 + cols: 4 + dt: f + data: [0.9659258262890682, -0.0, -0.25881904510252074, 0.45, + 0.0, 1.0, -0.0, -0.06, + 0.25881904510252074, 0.0, 0.9659258262890682, 0.0, + 0.0, 0.0, 0.0, 1.0] + +# "rate_hz": 210, +# "angular_random_walk": 0.3, +# "giro_bias_stability_tau": 500, +# "giro_bias_stability": 4.6, +# "velocity_random_walk": 0.24, +# "accel_bias_stability": 36, +# "accel_bias_stability_tau": 800 + +# IMU noise +IMU.NoiseGyro: 1.7e-4 #1.6968e-04 +IMU.NoiseAcc: 2.0000e-3 #2.0e-3 +IMU.GyroWalk: 1.9393e-05 +IMU.AccWalk: 3.0000e-03 # 3e-03 +IMU.Frequency: 210.0 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1000 # 1000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1.0 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize: 2.0 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3.0 +Viewer.ViewpointX: 0.0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -3.5 # -1.8 +Viewer.ViewpointF: 500.0 + diff --git a/Examples/Monocular-Inertial/mono_inertial_euroc.cc b/Examples/Monocular-Inertial/mono_inertial_euroc.cc index b9f320fd76..fe29df96f8 100644 --- a/Examples/Monocular-Inertial/mono_inertial_euroc.cc +++ b/Examples/Monocular-Inertial/mono_inertial_euroc.cc @@ -82,8 +82,8 @@ int main(int argc, char *argv[]) string pathSeq(argv[(2*seq) + 3]); string pathTimeStamps(argv[(2*seq) + 4]); - string pathCam0 = pathSeq + "/mav0/cam0/data"; - string pathImu = pathSeq + "/mav0/imu0/data.csv"; + string pathCam0 = pathSeq + "/auv0/rgb/cam0/data"; + string pathImu = pathSeq + "/auv0/imu0/data.csv"; LoadImages(pathCam0, pathTimeStamps, vstrImageFilenames[seq], vTimestampsCam[seq]); cout << "LOADED!" << endl; diff --git a/Examples/Monocular-Inertial/mono_inertial_mimir.cc b/Examples/Monocular-Inertial/mono_inertial_mimir.cc new file mode 100644 index 0000000000..b9f320fd76 --- /dev/null +++ b/Examples/Monocular-Inertial/mono_inertial_mimir.cc @@ -0,0 +1,310 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include "ImuTypes.h" + +using namespace std; + +void LoadImages(const string &strImagePath, const string &strPathTimes, + vector &vstrImages, vector &vTimeStamps); + +void LoadIMU(const string &strImuPath, vector &vTimeStamps, vector &vAcc, vector &vGyro); + +double ttrack_tot = 0; +int main(int argc, char *argv[]) +{ + + if(argc < 5) + { + cerr << endl << "Usage: ./mono_inertial_euroc path_to_vocabulary path_to_settings path_to_sequence_folder_1 path_to_times_file_1 (path_to_image_folder_2 path_to_times_file_2 ... path_to_image_folder_N path_to_times_file_N) " << endl; + return 1; + } + + const int num_seq = (argc-3)/2; + cout << "num_seq = " << num_seq << endl; + bool bFileName= (((argc-3) % 2) == 1); + string file_name; + if (bFileName) + { + file_name = string(argv[argc-1]); + cout << "file name: " << file_name << endl; + } + + // Load all sequences: + int seq; + vector< vector > vstrImageFilenames; + vector< vector > vTimestampsCam; + vector< vector > vAcc, vGyro; + vector< vector > vTimestampsImu; + vector nImages; + vector nImu; + vector first_imu(num_seq,0); + + vstrImageFilenames.resize(num_seq); + vTimestampsCam.resize(num_seq); + vAcc.resize(num_seq); + vGyro.resize(num_seq); + vTimestampsImu.resize(num_seq); + nImages.resize(num_seq); + nImu.resize(num_seq); + + int tot_images = 0; + for (seq = 0; seq vTimesTrack; + vTimesTrack.resize(tot_images); + + cout.precision(17); + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_MONOCULAR, true); + float imageScale = SLAM.GetImageScale(); + + double t_resize = 0.f; + double t_track = 0.f; + + int proccIm=0; + for (seq = 0; seq vImuMeas; + proccIm = 0; + for(int ni=0; ni >(t_End_Resize - t_Start_Resize).count(); + SLAM.InsertResizeTime(t_resize); +#endif + } + + // Load imu measurements from previous frame + vImuMeas.clear(); + + if(ni>0) + { + // cout << "t_cam " << tframe << endl; + + while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][ni]) + { + vImuMeas.push_back(ORB_SLAM3::IMU::Point(vAcc[seq][first_imu[seq]].x,vAcc[seq][first_imu[seq]].y,vAcc[seq][first_imu[seq]].z, + vGyro[seq][first_imu[seq]].x,vGyro[seq][first_imu[seq]].y,vGyro[seq][first_imu[seq]].z, + vTimestampsImu[seq][first_imu[seq]])); + first_imu[seq]++; + } + } + + #ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); + #else + std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now(); + #endif + + // Pass the image to the SLAM system + // cout << "tframe = " << tframe << endl; + SLAM.TrackMonocular(im,tframe,vImuMeas); // TODO change to monocular_inertial + + #ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); + #else + std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now(); + #endif + +#ifdef REGISTER_TIMES + t_track = t_resize + std::chrono::duration_cast >(t2 - t1).count(); + SLAM.InsertTrackTime(t_track); +#endif + + double ttrack= std::chrono::duration_cast >(t2 - t1).count(); + ttrack_tot += ttrack; + // std::cout << "ttrack: " << ttrack << std::endl; + + vTimesTrack[ni]=ttrack; + + // Wait to load the next frame + double T=0; + if(ni0) + T = tframe-vTimestampsCam[seq][ni-1]; + + if(ttrack &vstrImages, vector &vTimeStamps) +{ + ifstream fTimes; + fTimes.open(strPathTimes.c_str()); + vTimeStamps.reserve(5000); + vstrImages.reserve(5000); + while(!fTimes.eof()) + { + string s; + getline(fTimes,s); + if(!s.empty()) + { + stringstream ss; + ss << s; + vstrImages.push_back(strImagePath + "/" + ss.str() + ".png"); + double t; + ss >> t; + vTimeStamps.push_back(t/1e9); + + } + } +} + +void LoadIMU(const string &strImuPath, vector &vTimeStamps, vector &vAcc, vector &vGyro) +{ + ifstream fImu; + fImu.open(strImuPath.c_str()); + vTimeStamps.reserve(5000); + vAcc.reserve(5000); + vGyro.reserve(5000); + + while(!fImu.eof()) + { + string s; + getline(fImu,s); + if (s[0] == '#') + continue; + + if(!s.empty()) + { + string item; + size_t pos = 0; + double data[7]; + int count = 0; + while ((pos = s.find(',')) != string::npos) { + item = s.substr(0, pos); + data[count++] = stod(item); + s.erase(0, pos + 1); + } + item = s.substr(0, pos); + data[6] = stod(item); + + vTimeStamps.push_back(data[0]/1e9); + vAcc.push_back(cv::Point3f(data[4],data[5],data[6])); + vGyro.push_back(cv::Point3f(data[1],data[2],data[3])); + } + } +} diff --git a/Examples/Monocular/C922.yaml b/Examples/Monocular/C922.yaml new file mode 100755 index 0000000000..99c60a2907 --- /dev/null +++ b/Examples/Monocular/C922.yaml @@ -0,0 +1,77 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# System config +#-------------------------------------------------------------------------------------------- + +# When the variables are commented, the system doesn't load a previous session or not store the current one + +# If the LoadFile doesn't exist, the system give a message and create a new Atlas from scratch +#System.LoadAtlasFromFile: "Session_MH01_MH02_MH03_Mono" + +# The store file is created from the current session, if a file with the same name exists it is deleted +#System.SaveAtlasToFile: "Session_MH01_MH02_MH03_Mono" + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- +File.version: "1.0" + +Camera.type: "PinHole" + +# Camera calibration and distortion parameters (OpenCV) +Camera1.fx: 478.884888 +Camera1.fy: 479.366787 +Camera1.cx: 325.974713 +Camera1.cy: 180.202959 + +Camera1.k1: 0.025474 +Camera1.k2: -0.079350 +Camera1.p1: -0.000567 +Camera1.p2: -0.000980 + +Camera.width: 640 +Camera.height: 360 + +Camera.newWidth: 640 +Camera.newHeight: 360 + +# Camera frames per second +Camera.fps: 30 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#--------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1.0 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize: 2.0 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3.0 +Viewer.ViewpointX: 0.0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500.0 \ No newline at end of file diff --git a/Examples/Monocular/EuRoC.yaml b/Examples/Monocular/EuRoC.yaml index 3840edadbd..40b823ac56 100644 --- a/Examples/Monocular/EuRoC.yaml +++ b/Examples/Monocular/EuRoC.yaml @@ -74,5 +74,4 @@ Viewer.CameraLineWidth: 3.0 Viewer.ViewpointX: 0.0 Viewer.ViewpointY: -0.7 Viewer.ViewpointZ: -1.8 -Viewer.ViewpointF: 500.0 - +Viewer.ViewpointF: 500.0 \ No newline at end of file diff --git a/Examples/Monocular/MIMIR.yaml b/Examples/Monocular/MIMIR.yaml new file mode 100644 index 0000000000..4ee9715b10 --- /dev/null +++ b/Examples/Monocular/MIMIR.yaml @@ -0,0 +1,77 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# System config +#-------------------------------------------------------------------------------------------- + +# When the variables are commented, the system doesn't load a previous session or not store the current one + +# If the LoadFile doesn't exist, the system give a message and create a new Atlas from scratch +#System.LoadAtlasFromFile: "Session_MH01_MH02_MH03_Mono" + +# The store file is created from the current session, if a file with the same name exists it is deleted +#System.SaveAtlasToFile: "Session_MH01_MH02_MH03_Mono" + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- +File.version: "1.0" + +Camera.type: "PinHole" + +# Camera calibration and distortion parameters (OpenCV) +Camera1.fx: 252.07470703125 +Camera1.fy: 252.07470703125 +Camera1.cx: 360.0 +Camera1.cy: 270.0 + +Camera1.k1: 0.0 +Camera1.k2: 0.0 +Camera1.p1: 0.0 +Camera1.p2: 0.0 + +Camera.width: 720 +Camera.height: 540 + +Camera.newWidth: 720 +Camera.newHeight: 540 + +# Camera frames per second +Camera.fps: 30 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#--------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1.0 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize: 2.0 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3.0 +Viewer.ViewpointX: 0.0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500.0 \ No newline at end of file diff --git a/Examples/Monocular/mono_mimir.cc b/Examples/Monocular/mono_mimir.cc new file mode 100644 index 0000000000..1bb32ead61 --- /dev/null +++ b/Examples/Monocular/mono_mimir.cc @@ -0,0 +1,230 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include +#include +#include +#include + +#include + +#include + +using namespace std; + +void LoadImages(const string &strImagePath, const string &strPathTimes, + vector &vstrImages, vector &vTimeStamps); + +int main(int argc, char **argv) +{ + if(argc < 5) + { + cerr << endl << "Usage: ./mono_Mimir path_to_vocabulary path_to_settings path_to_sequence_folder_1 path_to_times_file_1 (path_to_image_folder_2 path_to_times_file_2 ... path_to_image_folder_N path_to_times_file_N) (trajectory_file_name)" << endl; + cerr << endl << "Example: ./Examples/Monocular/mono_mimir /home/olaya/dev/ORB_SLAM3/Vocabulary/ORBvoc.txt /home/olaya/dev/ORB_SLAM3/Examples/Monocular/MIMIR.yaml /home/olaya/Datasets/MIMIR/SeaFloor/track0/auv0/rgb/cam0/data /home/olaya/Datasets/MIMIR/SeaFloor/track0/auv0/ORB_timestamps.txt seafloor_track1.txt" << endl; + return 1; + } + + const int num_seq = (argc-3)/2; + cout << "num_seq = " << num_seq << endl; + bool bFileName= (((argc-3) % 2) == 1); + string file_name; + if (bFileName) + { + file_name = string(argv[argc-1]); + cout << "file name: " << file_name << endl; + } + + // Load all sequences: + int seq; + vector< vector > vstrImageFilenames; + vector< vector > vTimestampsCam; + vector nImages; + + vstrImageFilenames.resize(num_seq); + vTimestampsCam.resize(num_seq); + nImages.resize(num_seq); + + int tot_images = 0; + for (seq = 0; seq vTimesTrack; + vTimesTrack.resize(tot_images); + + cout << endl << "-------" << endl; + cout.precision(17); + + + int fps = 20; + float dT = 1.f/fps; + // Create SLAM system. It initializes all system threads and gets ready to process frames. + // ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR, false); FIX?? + ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR, true, 0, string(argv[3])); + float imageScale = SLAM.GetImageScale(); + + double t_resize = 0.f; + double t_track = 0.f; + + for (seq = 0; seq >(t_End_Resize - t_Start_Resize).count(); + SLAM.InsertResizeTime(t_resize); +#endif + } + + #ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); + #else + std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now(); + #endif + + // Pass the image to the SLAM system + // cout << "tframe = " << tframe << endl; + SLAM.TrackMonocular(im,tframe); // TODO change to monocular_inertial + + #ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); + #else + std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now(); + #endif + +#ifdef REGISTER_TIMES + t_track = t_resize + std::chrono::duration_cast >(t2 - t1).count(); + SLAM.InsertTrackTime(t_track); +#endif + + double ttrack= std::chrono::duration_cast >(t2 - t1).count(); + + vTimesTrack[ni]=ttrack; + + // Wait to load the next frame + double T=0; + if(ni0) + T = tframe-vTimestampsCam[seq][ni-1]; + + //std::cout << "T: " << T << std::endl; + //std::cout << "ttrack: " << ttrack << std::endl; + + if(ttrack &vstrImages, vector &vTimeStamps) +{ + ifstream fTimes; + fTimes.open(strPathTimes.c_str()); + vTimeStamps.reserve(5000); + vstrImages.reserve(5000); + while(!fTimes.eof()) + { + string s; + getline(fTimes,s); + if(!s.empty()) + { + stringstream ss; + ss << s; + vstrImages.push_back(strImagePath + "/" + ss.str() + ".png"); + double t; + ss >> t; + vTimeStamps.push_back(t*1e-9); + + } + } +} diff --git a/Examples/Stereo/MIMIR.yaml b/Examples/Stereo/MIMIR.yaml new file mode 100644 index 0000000000..547bcdccc7 --- /dev/null +++ b/Examples/Stereo/MIMIR.yaml @@ -0,0 +1,96 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# System config +#-------------------------------------------------------------------------------------------- + +# When the variables are commented, the system doesn't load a previous session or not store the current one + +# If the LoadFile doesn't exist, the system give a message and create a new Atlas from scratch +#System.LoadAtlasFromFile: "Session_MH01_MH02_MH03_Stereo60_Pseudo" + +# The store file is created from the current session, if a file with the same name exists it is deleted +#System.SaveAtlasToFile: "Session_MH01_MH02_MH03_Stereo60_Pseudo" + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- +File.version: "1.0" + +Camera.type: "PinHole" + +# Camera calibration and distortion parameters (OpenCV) +Camera1.fx: 252.07470703125 +Camera1.fy: 252.07470703125 +Camera1.cx: 360.0 +Camera1.cy: 270.0 + +Camera1.k1: 0.0 +Camera1.k2: 0.0 +Camera1.p1: 0.0 +Camera1.p2: 0.0 + +Camera2.fx: 252.07470703125 +Camera2.fy: 252.07470703125 +Camera2.cx: 360.0 +Camera2.cy: 270.0 + +Camera2.k1: 0.0 +Camera2.k2: 0.0 +Camera2.p1: 0.0 +Camera2.p2: 0.0 + +Camera.width: 720 +Camera.height: 540 + +# Camera frames per second +Camera.fps: 30 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +Stereo.ThDepth: 60.0 +Stereo.T_c1_c2: !!opencv-matrix + rows: 4 + cols: 4 + dt: f + data: [1,0,0,0, + 0,1,0,0.12, + 0,0,1,0, + 0,0,0,1] + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1200 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1.0 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize: 2.0 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3.0 +Viewer.ViewpointX: 0.0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500.0 +Viewer.imageViewScale: 1.0 + diff --git a/Examples/Stereo/stereo_mimir.cc b/Examples/Stereo/stereo_mimir.cc new file mode 100644 index 0000000000..ebe9861329 --- /dev/null +++ b/Examples/Stereo/stereo_mimir.cc @@ -0,0 +1,212 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include +#include +#include +#include +#include + +#include + +#include + +using namespace std; + +void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes, + vector &vstrImageLeft, vector &vstrImageRight, vector &vTimeStamps); + +int main(int argc, char **argv) +{ + if(argc < 5) + { + cerr << endl << "Usage: ./stereo_euroc path_to_vocabulary path_to_settings path_to_sequence_folder_1 path_to_times_file_1 (path_to_image_folder_2 path_to_times_file_2 ... path_to_image_folder_N path_to_times_file_N) (trajectory_file_name)" << endl; + cerr << endl << "Example: ./Examples/Monocular/stereo_mimir /home/olaya/dev/ORB_SLAM3/Vocabulary/ORBvoc.txt /home/olaya/dev/ORB_SLAM3/Examples/Stereo/MIMIR.yaml /home/olaya/Datasets/MIMIR/SeaFloor/track0 /home/olaya/Datasets/MIMIR/SeaFloor/track0/auv0/ORB_timestamps.txt /home/olaya/Datasets/MIMIR/SeaFloor/track0 /home/olaya/Datasets/MIMIR/SeaFloor/track0/auv0/ORB_timestamps.txt seafloor_track1.txt" << endl; + return 1; + } + + const int num_seq = (argc-3)/2; + cout << "num_seq = " << num_seq << endl; + bool bFileName= (((argc-3) % 2) == 1); + string file_name; + if (bFileName) + { + file_name = string(argv[argc-1]); + cout << "file name: " << file_name << endl; + } + + // Load all sequences: + int seq; + vector< vector > vstrImageLeft; + vector< vector > vstrImageRight; + vector< vector > vTimestampsCam; + vector nImages; + + vstrImageLeft.resize(num_seq); + vstrImageRight.resize(num_seq); + vTimestampsCam.resize(num_seq); + nImages.resize(num_seq); + + int tot_images = 0; + for (seq = 0; seq vTimesTrack; + vTimesTrack.resize(tot_images); + + cout << endl << "-------" << endl; + cout.precision(17); + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::STEREO, true); + + cv::Mat imLeft, imRight; + for (seq = 0; seq(), vstrImageLeft[seq][ni]); + + #ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); + #else + std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now(); + #endif + +#ifdef REGISTER_TIMES + t_track = t_resize + t_rect + std::chrono::duration_cast >(t2 - t1).count(); + SLAM.InsertTrackTime(t_track); +#endif + + double ttrack= std::chrono::duration_cast >(t2 - t1).count(); + + vTimesTrack[ni]=ttrack; + + // Wait to load the next frame + double T=0; + if(ni0) + T = tframe-vTimestampsCam[seq][ni-1]; + + if(ttrack &vstrImageLeft, vector &vstrImageRight, vector &vTimeStamps) +{ + ifstream fTimes; + fTimes.open(strPathTimes.c_str()); + vTimeStamps.reserve(5000); + vstrImageLeft.reserve(5000); + vstrImageRight.reserve(5000); + while(!fTimes.eof()) + { + string s; + getline(fTimes,s); + if(!s.empty()) + { + stringstream ss; + ss << s; + vstrImageLeft.push_back(strPathLeft + "/" + ss.str() + ".png"); + vstrImageRight.push_back(strPathRight + "/" + ss.str() + ".png"); + double t; + ss >> t; + vTimeStamps.push_back(t/1e9); + + } + } +} diff --git a/include/System.h b/include/System.h index 872c86e734..6b6c8eacf5 100644 --- a/include/System.h +++ b/include/System.h @@ -158,6 +158,12 @@ class System void SaveTrajectoryEuRoC(const string &filename, Map* pMap); void SaveKeyFrameTrajectoryEuRoC(const string &filename, Map* pMap); + void SaveTrajectoryMimir(const string &filename); + void SaveKeyFrameTrajectoryMimir(const string &filename); + + void SaveTrajectoryMimir(const string &filename, Map* pMap); + void SaveKeyFrameTrajectoryMimir(const string &filename, Map* pMap); + // Save data used for initialization debug void SaveDebugData(const int &iniIdx); diff --git a/src/System.cc b/src/System.cc index 60d9c5185a..d9badd49d5 100644 --- a/src/System.cc +++ b/src/System.cc @@ -1150,24 +1150,267 @@ void System::SaveKeyFrameTrajectoryEuRoC(const string &filename, Map* pMap) f.close(); } -/*void System::SaveTrajectoryKITTI(const string &filename) +/* MIMIR functions */ + + +void System::SaveTrajectoryMimir(const string &filename) { - cout << endl << "Saving camera trajectory to " << filename << " ..." << endl; + + cout << endl << "Saving trajectory to " << filename << " ..." << endl; + /*if(mSensor==MONOCULAR) + { + cerr << "ERROR: SaveTrajectoryMimir cannot be used for monocular." << endl; + return; + }*/ + + vector vpMaps = mpAtlas->GetAllMaps(); + int numMaxKFs = 0; + Map* pBiggerMap; + std::cout << "There are " << std::to_string(vpMaps.size()) << " maps in the atlas" << std::endl; + for(Map* pMap :vpMaps) + { + std::cout << " Map " << std::to_string(pMap->GetId()) << " has " << std::to_string(pMap->GetAllKeyFrames().size()) << " KFs" << std::endl; + if(pMap->GetAllKeyFrames().size() > numMaxKFs) + { + numMaxKFs = pMap->GetAllKeyFrames().size(); + pBiggerMap = pMap; + } + } + + vector vpKFs = pBiggerMap->GetAllKeyFrames(); + sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId); + + // Transform all keyframes so that the first keyframe is at the origin. + // After a loop closure the first keyframe might not be at the origin. + Sophus::SE3f Twb; // Can be word to cam0 or world to b depending on IMU or not. + if (mSensor==IMU_MONOCULAR || mSensor==IMU_STEREO || mSensor==IMU_RGBD) + Twb = vpKFs[0]->GetImuPose(); + else + Twb = vpKFs[0]->GetPoseInverse(); + + ofstream f; + f.open(filename.c_str()); + // cout << "file open" << endl; + f << fixed; + + // Frame pose is stored relative to its reference keyframe (which is optimized by BA and pose graph). + // We need to get first the keyframe pose and then concatenate the relative transformation. + // Frames not localized (tracking failure) are not saved. + + // For each frame we have a reference keyframe (lRit), the timestamp (lT) and a flag + // which is true when tracking failed (lbL). + list::iterator lRit = mpTracker->mlpReferences.begin(); + list::iterator lT = mpTracker->mlFrameTimes.begin(); + list::iterator lbL = mpTracker->mlbLost.begin(); + + //cout << "size mlpReferences: " << mpTracker->mlpReferences.size() << endl; + //cout << "size mlRelativeFramePoses: " << mpTracker->mlRelativeFramePoses.size() << endl; + //cout << "size mpTracker->mlFrameTimes: " << mpTracker->mlFrameTimes.size() << endl; + //cout << "size mpTracker->mlbLost: " << mpTracker->mlbLost.size() << endl; + + + for(auto lit=mpTracker->mlRelativeFramePoses.begin(), + lend=mpTracker->mlRelativeFramePoses.end();lit!=lend;lit++, lRit++, lT++, lbL++) + { + //cout << "1" << endl; + if(*lbL) + continue; + + + KeyFrame* pKF = *lRit; + //cout << "KF: " << pKF->mnId << endl; + + Sophus::SE3f Trw; + + // If the reference keyframe was culled, traverse the spanning tree to get a suitable keyframe. + if (!pKF) + continue; + + //cout << "2.5" << endl; + + while(pKF->isBad()) + { + //cout << " 2.bad" << endl; + Trw = Trw * pKF->mTcp; + pKF = pKF->GetParent(); + //cout << "--Parent KF: " << pKF->mnId << endl; + } + + if(!pKF || pKF->GetMap() != pBiggerMap) + { + //cout << "--Parent KF is from another map" << endl; + continue; + } + + //cout << "3" << endl; + + Trw = Trw * pKF->GetPose()*Twb; // Tcp*Tpw*Twb0=Tcb0 where b0 is the new world reference + + // cout << "4" << endl; + + if (mSensor == IMU_MONOCULAR || mSensor == IMU_STEREO || mSensor==IMU_RGBD) + { + Sophus::SE3f Twb = (pKF->mImuCalib.mTbc * (*lit) * Trw).inverse(); + Eigen::Quaternionf q = Twb.unit_quaternion(); + Eigen::Vector3f twb = Twb.translation(); + f << setprecision(6) << 1e9*(*lT) << " " << setprecision(9) << twb(0) << " " << twb(1) << " " << twb(2) << " " << q.x() << " " << q.y() << " " << q.z() << " " << q.w() << endl; + } + else + { + Sophus::SE3f Twc = ((*lit)*Trw).inverse(); + Eigen::Quaternionf q = Twc.unit_quaternion(); + Eigen::Vector3f twc = Twc.translation(); + f << setprecision(6) << 1e9*(*lT) << " " << setprecision(9) << twc(0) << " " << twc(1) << " " << twc(2) << " " << q.x() << " " << q.y() << " " << q.z() << " " << q.w() << endl; + } + + // cout << "5" << endl; + } + //cout << "end saving trajectory" << endl; + f.close(); + cout << endl << "End of saving trajectory to " << filename << " ..." << endl; +} + +void System::SaveTrajectoryMimir(const string &filename, Map* pMap) +{ + + cout << endl << "Saving trajectory of map " << pMap->GetId() << " to " << filename << " ..." << endl; + /*if(mSensor==MONOCULAR) + { + cerr << "ERROR: SaveTrajectoryMimir cannot be used for monocular." << endl; + return; + }*/ + + int numMaxKFs = 0; + + vector vpKFs = pMap->GetAllKeyFrames(); + sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId); + + // Transform all keyframes so that the first keyframe is at the origin. + // After a loop closure the first keyframe might not be at the origin. + Sophus::SE3f Twb; // Can be word to cam0 or world to b dependingo on IMU or not. + if (mSensor==IMU_MONOCULAR || mSensor==IMU_STEREO || mSensor==IMU_RGBD) + Twb = vpKFs[0]->GetImuPose(); + else + Twb = vpKFs[0]->GetPoseInverse(); + + ofstream f; + f.open(filename.c_str()); + // cout << "file open" << endl; + f << fixed; + + // Frame pose is stored relative to its reference keyframe (which is optimized by BA and pose graph). + // We need to get first the keyframe pose and then concatenate the relative transformation. + // Frames not localized (tracking failure) are not saved. + + // For each frame we have a reference keyframe (lRit), the timestamp (lT) and a flag + // which is true when tracking failed (lbL). + list::iterator lRit = mpTracker->mlpReferences.begin(); + list::iterator lT = mpTracker->mlFrameTimes.begin(); + list::iterator lbL = mpTracker->mlbLost.begin(); + + //cout << "size mlpReferences: " << mpTracker->mlpReferences.size() << endl; + //cout << "size mlRelativeFramePoses: " << mpTracker->mlRelativeFramePoses.size() << endl; + //cout << "size mpTracker->mlFrameTimes: " << mpTracker->mlFrameTimes.size() << endl; + //cout << "size mpTracker->mlbLost: " << mpTracker->mlbLost.size() << endl; + + + for(auto lit=mpTracker->mlRelativeFramePoses.begin(), + lend=mpTracker->mlRelativeFramePoses.end();lit!=lend;lit++, lRit++, lT++, lbL++) + { + //cout << "1" << endl; + if(*lbL) + continue; + + + KeyFrame* pKF = *lRit; + //cout << "KF: " << pKF->mnId << endl; + + Sophus::SE3f Trw; + + // If the reference keyframe was culled, traverse the spanning tree to get a suitable keyframe. + if (!pKF) + continue; + + //cout << "2.5" << endl; + + while(pKF->isBad()) + { + //cout << " 2.bad" << endl; + Trw = Trw * pKF->mTcp; + pKF = pKF->GetParent(); + //cout << "--Parent KF: " << pKF->mnId << endl; + } + + if(!pKF || pKF->GetMap() != pMap) + { + //cout << "--Parent KF is from another map" << endl; + continue; + } + + //cout << "3" << endl; + + Trw = Trw * pKF->GetPose()*Twb; // Tcp*Tpw*Twb0=Tcb0 where b0 is the new world reference + + // cout << "4" << endl; + + if (mSensor == IMU_MONOCULAR || mSensor == IMU_STEREO || mSensor==IMU_RGBD) + { + Sophus::SE3f Twb = (pKF->mImuCalib.mTbc * (*lit) * Trw).inverse(); + Eigen::Quaternionf q = Twb.unit_quaternion(); + Eigen::Vector3f twb = Twb.translation(); + f << setprecision(6) << 1e9*(*lT) << " " << setprecision(9) << twb(0) << " " << twb(1) << " " << twb(2) << " " << q.x() << " " << q.y() << " " << q.z() << " " << q.w() << endl; + } + else + { + Sophus::SE3f Twc = ((*lit)*Trw).inverse(); + Eigen::Quaternionf q = Twc.unit_quaternion(); + Eigen::Vector3f twc = Twc.translation(); + f << setprecision(6) << 1e9*(*lT) << " " << setprecision(9) << twc(0) << " " << twc(1) << " " << twc(2) << " " << q.x() << " " << q.y() << " " << q.z() << " " << q.w() << endl; + } + + // cout << "5" << endl; + } + //cout << "end saving trajectory" << endl; + f.close(); + cout << endl << "End of saving trajectory to " << filename << " ..." << endl; +} + +/*void System::SaveTrajectoryEuRoC(const string &filename) +{ + + cout << endl << "Saving trajectory to " << filename << " ..." << endl; if(mSensor==MONOCULAR) { - cerr << "ERROR: SaveTrajectoryKITTI cannot be used for monocular." << endl; + cerr << "ERROR: SaveTrajectoryEuRoC cannot be used for monocular." << endl; return; } - vector vpKFs = mpAtlas->GetAllKeyFrames(); + vector vpMaps = mpAtlas->GetAllMaps(); + Map* pBiggerMap; + int numMaxKFs = 0; + for(Map* pMap :vpMaps) + { + if(pMap->GetAllKeyFrames().size() > numMaxKFs) + { + numMaxKFs = pMap->GetAllKeyFrames().size(); + pBiggerMap = pMap; + } + } + + vector vpKFs = pBiggerMap->GetAllKeyFrames(); sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId); // Transform all keyframes so that the first keyframe is at the origin. // After a loop closure the first keyframe might not be at the origin. - cv::Mat Two = vpKFs[0]->GetPoseInverse(); + Sophus::SE3f Twb; // Can be word to cam0 or world to b dependingo on IMU or not. + if (mSensor==IMU_MONOCULAR || mSensor==IMU_STEREO || mSensor==IMU_RGBD) + Twb = vpKFs[0]->GetImuPose_(); + else + Twb = vpKFs[0]->GetPoseInverse_(); ofstream f; f.open(filename.c_str()); + // cout << "file open" << endl; f << fixed; // Frame pose is stored relative to its reference keyframe (which is optimized by BA and pose graph). @@ -1178,31 +1421,234 @@ void System::SaveKeyFrameTrajectoryEuRoC(const string &filename, Map* pMap) // which is true when tracking failed (lbL). list::iterator lRit = mpTracker->mlpReferences.begin(); list::iterator lT = mpTracker->mlFrameTimes.begin(); - for(list::iterator lit=mpTracker->mlRelativeFramePoses.begin(), lend=mpTracker->mlRelativeFramePoses.end();lit!=lend;lit++, lRit++, lT++) + list::iterator lbL = mpTracker->mlbLost.begin(); + + //cout << "size mlpReferences: " << mpTracker->mlpReferences.size() << endl; + //cout << "size mlRelativeFramePoses: " << mpTracker->mlRelativeFramePoses.size() << endl; + //cout << "size mpTracker->mlFrameTimes: " << mpTracker->mlFrameTimes.size() << endl; + //cout << "size mpTracker->mlbLost: " << mpTracker->mlbLost.size() << endl; + + + for(list::iterator lit=mpTracker->mlRelativeFramePoses.begin(), + lend=mpTracker->mlRelativeFramePoses.end();lit!=lend;lit++, lRit++, lT++, lbL++) { - ORB_SLAM3::KeyFrame* pKF = *lRit; + //cout << "1" << endl; + if(*lbL) + continue; + + + KeyFrame* pKF = *lRit; + //cout << "KF: " << pKF->mnId << endl; - cv::Mat Trw = cv::Mat::eye(4,4,CV_32F); + Sophus::SE3f Trw; + + // If the reference keyframe was culled, traverse the spanning tree to get a suitable keyframe. + if (!pKF) + continue; + + //cout << "2.5" << endl; while(pKF->isBad()) { - Trw = Trw * Converter::toCvMat(pKF->mTcp.matrix()); + //cout << " 2.bad" << endl; + Trw = Trw * pKF->mTcp; pKF = pKF->GetParent(); + //cout << "--Parent KF: " << pKF->mnId << endl; } - Trw = Trw * pKF->GetPoseCv() * Two; + if(!pKF || pKF->GetMap() != pBiggerMap) + { + //cout << "--Parent KF is from another map" << endl; + continue; + } + + //cout << "3" << endl; + + Trw = Trw * pKF->GetPose()*Twb; // Tcp*Tpw*Twb0=Tcb0 where b0 is the new world reference + + // cout << "4" << endl; - cv::Mat Tcw = (*lit)*Trw; - cv::Mat Rwc = Tcw.rowRange(0,3).colRange(0,3).t(); - cv::Mat twc = -Rwc*Tcw.rowRange(0,3).col(3); - f << setprecision(9) << Rwc.at(0,0) << " " << Rwc.at(0,1) << " " << Rwc.at(0,2) << " " << twc.at(0) << " " << - Rwc.at(1,0) << " " << Rwc.at(1,1) << " " << Rwc.at(1,2) << " " << twc.at(1) << " " << - Rwc.at(2,0) << " " << Rwc.at(2,1) << " " << Rwc.at(2,2) << " " << twc.at(2) << endl; + if (mSensor == IMU_MONOCULAR || mSensor == IMU_STEREO || mSensor==IMU_RGBD) + { + Sophus::SE3f Tbw = pKF->mImuCalib.Tbc_ * (*lit) * Trw; + Sophus::SE3f Twb = Tbw.inverse(); + + Eigen::Vector3f twb = Twb.translation(); + Eigen::Quaternionf q = Twb.unit_quaternion(); + f << setprecision(6) << 1e9*(*lT) << " " << setprecision(9) << twb(0) << " " << twb(1) << " " << twb(2) << " " << q.x() << " " << q.y() << " " << q.z() << " " << q.w() << endl; + } + else + { + Sophus::SE3f Tcw = (*lit) * Trw; + Sophus::SE3f Twc = Tcw.inverse(); + + Eigen::Vector3f twc = Twc.translation(); + Eigen::Quaternionf q = Twc.unit_quaternion(); + f << setprecision(6) << 1e9*(*lT) << " " << setprecision(9) << twc(0) << " " << twc(1) << " " << twc(2) << " " << q.x() << " " << q.y() << " " << q.z() << " " << q.w() << endl; + } + + // cout << "5" << endl; } + //cout << "end saving trajectory" << endl; f.close(); + cout << endl << "End of saving trajectory to " << filename << " ..." << endl; }*/ + +/*void System::SaveKeyFrameTrajectoryEuRoC_old(const string &filename) +{ + cout << endl << "Saving keyframe trajectory to " << filename << " ..." << endl; + + vector vpMaps = mpAtlas->GetAllMaps(); + Map* pBiggerMap; + int numMaxKFs = 0; + for(Map* pMap :vpMaps) + { + if(pMap->GetAllKeyFrames().size() > numMaxKFs) + { + numMaxKFs = pMap->GetAllKeyFrames().size(); + pBiggerMap = pMap; + } + } + + vector vpKFs = pBiggerMap->GetAllKeyFrames(); + sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId); + + // Transform all keyframes so that the first keyframe is at the origin. + // After a loop closure the first keyframe might not be at the origin. + ofstream f; + f.open(filename.c_str()); + f << fixed; + + for(size_t i=0; iSetPose(pKF->GetPose()*Two); + + if(pKF->isBad()) + continue; + if (mSensor == IMU_MONOCULAR || mSensor == IMU_STEREO || mSensor==IMU_RGBD) + { + cv::Mat R = pKF->GetImuRotation().t(); + vector q = Converter::toQuaternion(R); + cv::Mat twb = pKF->GetImuPosition(); + f << setprecision(6) << 1e9*pKF->mTimeStamp << " " << setprecision(9) << twb.at(0) << " " << twb.at(1) << " " << twb.at(2) << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl; + + } + else + { + cv::Mat R = pKF->GetRotation(); + vector q = Converter::toQuaternion(R); + cv::Mat t = pKF->GetCameraCenter(); + f << setprecision(6) << 1e9*pKF->mTimeStamp << " " << setprecision(9) << t.at(0) << " " << t.at(1) << " " << t.at(2) << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl; + } + } + f.close(); +}*/ + +void System::SaveKeyFrameTrajectoryMimir(const string &filename) +{ + cout << endl << "Saving keyframe trajectory to " << filename << " ..." << endl; + + vector vpMaps = mpAtlas->GetAllMaps(); + Map* pBiggerMap; + int numMaxKFs = 0; + for(Map* pMap :vpMaps) + { + if(pMap && pMap->GetAllKeyFrames().size() > numMaxKFs) + { + numMaxKFs = pMap->GetAllKeyFrames().size(); + pBiggerMap = pMap; + } + } + + if(!pBiggerMap) + { + std::cout << "There is not a map!!" << std::endl; + return; + } + + vector vpKFs = pBiggerMap->GetAllKeyFrames(); + sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId); + + // Transform all keyframes so that the first keyframe is at the origin. + // After a loop closure the first keyframe might not be at the origin. + ofstream f; + f.open(filename.c_str()); + f << fixed; + + for(size_t i=0; iSetPose(pKF->GetPose()*Two); + + if(!pKF || pKF->isBad()) + continue; + if (mSensor == IMU_MONOCULAR || mSensor == IMU_STEREO || mSensor==IMU_RGBD) + { + Sophus::SE3f Twb = pKF->GetImuPose(); + Eigen::Quaternionf q = Twb.unit_quaternion(); + Eigen::Vector3f twb = Twb.translation(); + f << setprecision(6) << 1e9*pKF->mTimeStamp << " " << setprecision(9) << twb(0) << " " << twb(1) << " " << twb(2) << " " << q.x() << " " << q.y() << " " << q.z() << " " << q.w() << endl; + + } + else + { + Sophus::SE3f Twc = pKF->GetPoseInverse(); + Eigen::Quaternionf q = Twc.unit_quaternion(); + Eigen::Vector3f t = Twc.translation(); + f << setprecision(6) << 1e9*pKF->mTimeStamp << " " << setprecision(9) << t(0) << " " << t(1) << " " << t(2) << " " << q.x() << " " << q.y() << " " << q.z() << " " << q.w() << endl; + } + } + f.close(); +} + +void System::SaveKeyFrameTrajectoryMimir(const string &filename, Map* pMap) +{ + cout << endl << "Saving keyframe trajectory of map " << pMap->GetId() << " to " << filename << " ..." << endl; + + vector vpKFs = pMap->GetAllKeyFrames(); + sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId); + + // Transform all keyframes so that the first keyframe is at the origin. + // After a loop closure the first keyframe might not be at the origin. + ofstream f; + f.open(filename.c_str()); + f << fixed; + + for(size_t i=0; iisBad()) + continue; + if (mSensor == IMU_MONOCULAR || mSensor == IMU_STEREO || mSensor==IMU_RGBD) + { + Sophus::SE3f Twb = pKF->GetImuPose(); + Eigen::Quaternionf q = Twb.unit_quaternion(); + Eigen::Vector3f twb = Twb.translation(); + f << setprecision(6) << 1e9*pKF->mTimeStamp << " " << setprecision(9) << twb(0) << " " << twb(1) << " " << twb(2) << " " << q.x() << " " << q.y() << " " << q.z() << " " << q.w() << endl; + + } + else + { + Sophus::SE3f Twc = pKF->GetPoseInverse(); + Eigen::Quaternionf q = Twc.unit_quaternion(); + Eigen::Vector3f t = Twc.translation(); + f << setprecision(6) << 1e9*pKF->mTimeStamp << " " << setprecision(9) << t(0) << " " << t(1) << " " << t(2) << " " << q.x() << " " << q.y() << " " << q.z() << " " << q.w() << endl; + } + } + f.close(); +} + + + + + + void System::SaveTrajectoryKITTI(const string &filename) { cout << endl << "Saving camera trajectory to " << filename << " ..." << endl; From a46e001306115422b934d042af288c2c79a320f9 Mon Sep 17 00:00:00 2001 From: olayasturias Date: Fri, 23 Sep 2022 16:05:08 +0200 Subject: [PATCH 06/17] MIMIR timestamp files --- .../OceanFloor_track0_dark.txt | 2405 +++++++ .../OceanFloor_track0_light.txt | 2421 +++++++ .../OceanFloor_track1_light.txt | 6263 +++++++++++++++++ .../MIMIR_TimeStamps/SandPipe_track0_dark.txt | 2741 ++++++++ .../SandPipe_track0_light.txt | 2605 +++++++ .../SeaFloor_Algae_track0.txt | 2934 ++++++++ .../SeaFloor_Algae_track1.txt | 2076 ++++++ .../SeaFloor_Algae_track2.txt | 2489 +++++++ .../MIMIR_TimeStamps/SeaFloor_track0.txt | 2847 ++++++++ .../MIMIR_TimeStamps/SeaFloor_track1.txt | 2030 ++++++ .../MIMIR_TimeStamps/SeaFloor_track2.txt | 2537 +++++++ .../Monocular-Inertial/mono_inertial_euroc.cc | 4 +- .../OceanFloor_track0_dark.txt | 2405 +++++++ .../OceanFloor_track0_light.txt | 2421 +++++++ .../OceanFloor_track1_light.txt | 6263 +++++++++++++++++ .../MIMIR_TimeStamps/SandPipe_track0_dark.txt | 2741 ++++++++ .../SandPipe_track0_light.txt | 2605 +++++++ .../SeaFloor_Algae_track0.txt | 2934 ++++++++ .../SeaFloor_Algae_track1.txt | 2076 ++++++ .../SeaFloor_Algae_track2.txt | 2489 +++++++ .../MIMIR_TimeStamps/SeaFloor_track0.txt | 2847 ++++++++ .../MIMIR_TimeStamps/SeaFloor_track1.txt | 2030 ++++++ .../MIMIR_TimeStamps/SeaFloor_track2.txt | 2537 +++++++ Examples/Monocular/mono_mimir.cc | 4 +- .../OceanFloor_track0_dark.txt | 2405 +++++++ .../OceanFloor_track0_light.txt | 2421 +++++++ .../OceanFloor_track1_light.txt | 6263 +++++++++++++++++ .../MIMIR_TimeStamps/SandPipe_track0_dark.txt | 2741 ++++++++ .../SandPipe_track0_light.txt | 2605 +++++++ .../SeaFloor_Algae_track0.txt | 2934 ++++++++ .../SeaFloor_Algae_track1.txt | 2076 ++++++ .../SeaFloor_Algae_track2.txt | 2489 +++++++ .../MIMIR_TimeStamps/SeaFloor_track0.txt | 2847 ++++++++ .../MIMIR_TimeStamps/SeaFloor_track1.txt | 2030 ++++++ .../MIMIR_TimeStamps/SeaFloor_track2.txt | 2537 +++++++ .../OceanFloor_track0_dark.txt | 2405 +++++++ .../OceanFloor_track0_light.txt | 2421 +++++++ .../OceanFloor_track1_light.txt | 6263 +++++++++++++++++ .../MIMIR_TimeStamps/SandPipe_track0_dark.txt | 2741 ++++++++ .../SandPipe_track0_light.txt | 2605 +++++++ .../SeaFloor_Algae_track0.txt | 2934 ++++++++ .../SeaFloor_Algae_track1.txt | 2076 ++++++ .../SeaFloor_Algae_track2.txt | 2489 +++++++ .../MIMIR_TimeStamps/SeaFloor_track0.txt | 2847 ++++++++ .../MIMIR_TimeStamps/SeaFloor_track1.txt | 2030 ++++++ .../MIMIR_TimeStamps/SeaFloor_track2.txt | 2537 +++++++ Examples/Stereo/stereo_mimir.cc | 4 +- run_mono.sh | 8 + run_stereo.sh | 5 + 49 files changed, 125411 insertions(+), 6 deletions(-) create mode 100644 Examples/Monocular-Inertial/MIMIR_TimeStamps/OceanFloor_track0_dark.txt create mode 100644 Examples/Monocular-Inertial/MIMIR_TimeStamps/OceanFloor_track0_light.txt create mode 100644 Examples/Monocular-Inertial/MIMIR_TimeStamps/OceanFloor_track1_light.txt create mode 100644 Examples/Monocular-Inertial/MIMIR_TimeStamps/SandPipe_track0_dark.txt create mode 100644 Examples/Monocular-Inertial/MIMIR_TimeStamps/SandPipe_track0_light.txt create mode 100644 Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt create mode 100644 Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt create mode 100644 Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt create mode 100644 Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_track0.txt create mode 100644 Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_track1.txt create mode 100644 Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_track2.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_dark.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_light.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track1_light.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_dark.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_light.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track0.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track1.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track2.txt create mode 100644 Examples/Stereo-Inertial/MIMIR_TimeStamps/OceanFloor_track0_dark.txt create mode 100644 Examples/Stereo-Inertial/MIMIR_TimeStamps/OceanFloor_track0_light.txt create mode 100644 Examples/Stereo-Inertial/MIMIR_TimeStamps/OceanFloor_track1_light.txt create mode 100644 Examples/Stereo-Inertial/MIMIR_TimeStamps/SandPipe_track0_dark.txt create mode 100644 Examples/Stereo-Inertial/MIMIR_TimeStamps/SandPipe_track0_light.txt create mode 100644 Examples/Stereo-Inertial/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt create mode 100644 Examples/Stereo-Inertial/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt create mode 100644 Examples/Stereo-Inertial/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt create mode 100644 Examples/Stereo-Inertial/MIMIR_TimeStamps/SeaFloor_track0.txt create mode 100644 Examples/Stereo-Inertial/MIMIR_TimeStamps/SeaFloor_track1.txt create mode 100644 Examples/Stereo-Inertial/MIMIR_TimeStamps/SeaFloor_track2.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/OceanFloor_track0_dark.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/OceanFloor_track0_light.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/OceanFloor_track1_light.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SandPipe_track0_dark.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SandPipe_track0_light.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SeaFloor_track0.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SeaFloor_track1.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SeaFloor_track2.txt create mode 100755 run_mono.sh create mode 100755 run_stereo.sh diff --git a/Examples/Monocular-Inertial/MIMIR_TimeStamps/OceanFloor_track0_dark.txt b/Examples/Monocular-Inertial/MIMIR_TimeStamps/OceanFloor_track0_dark.txt new file mode 100644 index 0000000000..e14794a331 --- /dev/null +++ b/Examples/Monocular-Inertial/MIMIR_TimeStamps/OceanFloor_track0_dark.txt @@ -0,0 +1,2405 @@ +1662138209585822464 +1662138209624823296 +1662138209666824192 +1662138209705825024 +1662138209747825920 +1662138209789826816 +1662138209831827712 +1662138209873828608 +1662138209918829568 +1662138209972830720 +1662138210017831680 +1662138210065832704 +1662138210110833664 +1662138210155834624 +1662138210197835520 +1662138210242836480 +1662138210287837440 +1662138210329838336 +1662138210374839296 +1662138210416840192 +1662138210467841280 +1662138210515842304 +1662138210563843328 +1662138210605844224 +1662138210647845120 +1662138210698846208 +1662138210740847104 +1662138210782848000 +1662138210824848896 +1662138210869849856 +1662138210914850816 +1662138210959851776 +1662138211001852672 +1662138211046853632 +1662138211088854528 +1662138211130855424 +1662138211181856512 +1662138211223857408 +1662138211262858240 +1662138211304859136 +1662138211349860096 +1662138211391860992 +1662138211436861952 +1662138211475862784 +1662138211517863680 +1662138211562864640 +1662138211607865600 +1662138211652866560 +1662138211697867520 +1662138211745868544 +1662138211787869440 +1662138211829870336 +1662138211874871296 +1662138211925872384 +1662138211967873280 +1662138212012874240 +1662138212060875264 +1662138212102876160 +1662138212141876992 +1662138212180877824 +1662138212222878720 +1662138212270879744 +1662138212318880768 +1662138212363881728 +1662138212411882752 +1662138212465883904 +1662138212507884800 +1662138212552885760 +1662138212597886720 +1662138212639887616 +1662138212684888576 +1662138212732889600 +1662138212771890432 +1662138212813891328 +1662138212855892224 +1662138212897893120 +1662138212939894016 +1662138212981894912 +1662138213026895872 +1662138213068896768 +1662138213116897792 +1662138213161898752 +1662138213206899712 +1662138213248900608 +1662138213290901504 +1662138213332902400 +1662138213374903296 +1662138213416904192 +1662138213461905152 +1662138213509906176 +1662138213551907072 +1662138213599908096 +1662138213641908992 +1662138213695910144 +1662138213737911040 +1662138213788912128 +1662138213833913088 +1662138213881914112 +1662138213929915136 +1662138213971916032 +1662138214019917056 +1662138214061917952 +1662138214109918976 +1662138214157920000 +1662138214208921088 +1662138214250921984 +1662138214298923008 +1662138214337923840 +1662138214382924800 +1662138214430925824 +1662138214478926848 +1662138214520927744 +1662138214562928640 +1662138214604929536 +1662138214649930496 +1662138214691931392 +1662138214733932288 +1662138214775933184 +1662138214820934144 +1662138214859934976 +1662138214904935936 +1662138214955937024 +1662138214997937920 +1662138215042938880 +1662138215084939776 +1662138215132940800 +1662138215171941632 +1662138215210942464 +1662138215255943424 +1662138215300944384 +1662138215342945280 +1662138215387946240 +1662138215429947136 +1662138215468947968 +1662138215513948928 +1662138215561949952 +1662138215606950912 +1662138215648951808 +1662138215690952704 +1662138215738953728 +1662138215780954624 +1662138215828955648 +1662138215870956544 +1662138215909957376 +1662138215957958400 +1662138215999959296 +1662138216041960192 +1662138216083961088 +1662138216122961920 +1662138216164962816 +1662138216212963840 +1662138216257964800 +1662138216299965696 +1662138216341966592 +1662138216383967488 +1662138216431968512 +1662138216470969344 +1662138216512970240 +1662138216554971136 +1662138216596972032 +1662138216641972992 +1662138216689974016 +1662138216737975040 +1662138216782976000 +1662138216824976896 +1662138216866977792 +1662138216905978624 +1662138216947979520 +1662138216992980480 +1662138217034981376 +1662138217085982464 +1662138217133983488 +1662138217175984384 +1662138217214985216 +1662138217259986176 +1662138217301987072 +1662138217349988096 +1662138217391988992 +1662138217433989888 +1662138217475990784 +1662138217517991680 +1662138217559992576 +1662138217607993600 +1662138217652994560 +1662138217700995584 +1662138217742996480 +1662138217787997440 +1662138217829998336 +1662138217871999232 +1662138217914000128 +1662138217956001024 +1662138217998001920 +1662138218040002816 +1662138218085003776 +1662138218130004736 +1662138218175005696 +1662138218217006592 +1662138218256007424 +1662138218298008320 +1662138218343009280 +1662138218385010176 +1662138218427011072 +1662138218469011968 +1662138218517012992 +1662138218559013888 +1662138218601014784 +1662138218646015744 +1662138218694016768 +1662138218739017728 +1662138218781018624 +1662138218823019520 +1662138218865020416 +1662138218907021312 +1662138218949022208 +1662138218997023232 +1662138219036024064 +1662138219081025024 +1662138219123025920 +1662138219162026752 +1662138219207027712 +1662138219249028608 +1662138219294029568 +1662138219339030528 +1662138219381031424 +1662138219423032320 +1662138219474033408 +1662138219519034368 +1662138219567035392 +1662138219612036352 +1662138219660037376 +1662138219708038400 +1662138219756039424 +1662138219798040320 +1662138219846041344 +1662138219888042240 +1662138219933043200 +1662138219987044352 +1662138220035045376 +1662138220080046336 +1662138220128047360 +1662138220173048320 +1662138220218049280 +1662138220263050240 +1662138220305051136 +1662138220350052096 +1662138220395053056 +1662138220434053888 +1662138220479054848 +1662138220524055808 +1662138220569056768 +1662138220611057664 +1662138220650058496 +1662138220692059392 +1662138220734060288 +1662138220779061248 +1662138220824062208 +1662138220869063168 +1662138220917064192 +1662138220962065152 +1662138221007066112 +1662138221049067008 +1662138221091067904 +1662138221133068800 +1662138221178069760 +1662138221220070656 +1662138221265071616 +1662138221307072512 +1662138221349073408 +1662138221403074560 +1662138221445075456 +1662138221493076480 +1662138221535077376 +1662138221580078336 +1662138221628079360 +1662138221670080256 +1662138221712081152 +1662138221757082112 +1662138221799083008 +1662138221838083840 +1662138221880084736 +1662138221922085632 +1662138221961086464 +1662138222009087488 +1662138222051088384 +1662138222102089472 +1662138222150090496 +1662138222195091456 +1662138222240092416 +1662138222288093440 +1662138222336094464 +1662138222381095424 +1662138222429096448 +1662138222471097344 +1662138222513098240 +1662138222558099200 +1662138222600100096 +1662138222648101120 +1662138222687101952 +1662138222732102912 +1662138222777103872 +1662138222822104832 +1662138222870105856 +1662138222912106752 +1662138222960107776 +1662138223002108672 +1662138223044109568 +1662138223086110464 +1662138223131111424 +1662138223173112320 +1662138223221113344 +1662138223266114304 +1662138223311115264 +1662138223359116288 +1662138223401117184 +1662138223437117952 +1662138223479118848 +1662138223527119872 +1662138223569120768 +1662138223611121664 +1662138223656122624 +1662138223701123584 +1662138223749124608 +1662138223791125504 +1662138223839126528 +1662138223881127424 +1662138223926128384 +1662138223968129280 +1662138224019130368 +1662138224058131200 +1662138224112132352 +1662138224160133376 +1662138224208134400 +1662138224247135232 +1662138224289136128 +1662138224334137088 +1662138224376137984 +1662138224418138880 +1662138224463139840 +1662138224511140864 +1662138224553141760 +1662138224598142720 +1662138224643143680 +1662138224688144640 +1662138224733145600 +1662138224784146688 +1662138224826147584 +1662138224868148480 +1662138224910149376 +1662138224952150272 +1662138224994151168 +1662138225039152128 +1662138225084153088 +1662138225132154112 +1662138225174155008 +1662138225219155968 +1662138225267156992 +1662138225315158016 +1662138225360158976 +1662138225405159936 +1662138225450160896 +1662138225501161984 +1662138225546162944 +1662138225588163840 +1662138225633164800 +1662138225678165760 +1662138225723166720 +1662138225765167616 +1662138225810168576 +1662138225858169600 +1662138225900170496 +1662138225948171520 +1662138225993172480 +1662138226035173376 +1662138226077174272 +1662138226122175232 +1662138226167176192 +1662138226212177152 +1662138226254178048 +1662138226302179072 +1662138226344179968 +1662138226392180992 +1662138226431181824 +1662138226473182720 +1662138226521183744 +1662138226566184704 +1662138226608185600 +1662138226650186496 +1662138226689187328 +1662138226743188480 +1662138226794189568 +1662138226839190528 +1662138226881191424 +1662138226923192320 +1662138226971193344 +1662138227013194240 +1662138227058195200 +1662138227103196160 +1662138227148197120 +1662138227193198080 +1662138227241199104 +1662138227286200064 +1662138227337201152 +1662138227391202304 +1662138227433203200 +1662138227475204096 +1662138227517204992 +1662138227559205888 +1662138227604206848 +1662138227652207872 +1662138227694208768 +1662138227739209728 +1662138227784210688 +1662138227826211584 +1662138227868212480 +1662138227910213376 +1662138227955214336 +1662138227997215232 +1662138228039216128 +1662138228084217088 +1662138228126217984 +1662138228171218944 +1662138228225220096 +1662138228267220992 +1662138228318222080 +1662138228363223040 +1662138228405223936 +1662138228456225024 +1662138228504226048 +1662138228549227008 +1662138228594227968 +1662138228642228992 +1662138228684229888 +1662138228729230848 +1662138228783232000 +1662138228828232960 +1662138228870233856 +1662138228918234880 +1662138228966235904 +1662138229008236800 +1662138229056237824 +1662138229095238656 +1662138229143239680 +1662138229185240576 +1662138229227241472 +1662138229269242368 +1662138229317243392 +1662138229359244288 +1662138229401245184 +1662138229449246208 +1662138229503247360 +1662138229545248256 +1662138229590249216 +1662138229632250112 +1662138229674251008 +1662138229716251904 +1662138229764252928 +1662138229806253824 +1662138229851254784 +1662138229893255680 +1662138229941256704 +1662138229986257664 +1662138230028258560 +1662138230073259520 +1662138230127260672 +1662138230169261568 +1662138230217262592 +1662138230262263552 +1662138230304264448 +1662138230349265408 +1662138230394266368 +1662138230436267264 +1662138230481268224 +1662138230526269184 +1662138230574270208 +1662138230613271040 +1662138230658272000 +1662138230706273024 +1662138230748273920 +1662138230790274816 +1662138230835275776 +1662138230877276672 +1662138230919277568 +1662138230961278464 +1662138231006279424 +1662138231048280320 +1662138231099281408 +1662138231141282304 +1662138231186283264 +1662138231228284160 +1662138231279285248 +1662138231324286208 +1662138231372287232 +1662138231414288128 +1662138231468289280 +1662138231510290176 +1662138231552291072 +1662138231594291968 +1662138231633292800 +1662138231675293696 +1662138231714294528 +1662138231759295488 +1662138231810296576 +1662138231852297472 +1662138231894298368 +1662138231942299392 +1662138231984300288 +1662138232023301120 +1662138232068302080 +1662138232113303040 +1662138232155303936 +1662138232203304960 +1662138232248305920 +1662138232290306816 +1662138232338307840 +1662138232386308864 +1662138232428309760 +1662138232467310592 +1662138232515311616 +1662138232557312512 +1662138232614313728 +1662138232656314624 +1662138232695315456 +1662138232737316352 +1662138232782317312 +1662138232833318400 +1662138232875319296 +1662138232917320192 +1662138232959321088 +1662138233001321984 +1662138233046322944 +1662138233088323840 +1662138233136324864 +1662138233187325952 +1662138233232326912 +1662138233280327936 +1662138233322328832 +1662138233364329728 +1662138233409330688 +1662138233451331584 +1662138233493332480 +1662138233535333376 +1662138233580334336 +1662138233625335296 +1662138233667336192 +1662138233715337216 +1662138233757338112 +1662138233805339136 +1662138233856340224 +1662138233895341056 +1662138233940342016 +1662138233979342848 +1662138234021343744 +1662138234066344704 +1662138234108345600 +1662138234153346560 +1662138234192347392 +1662138234237348352 +1662138234282349312 +1662138234324350208 +1662138234366351104 +1662138234408352000 +1662138234453352960 +1662138234504354048 +1662138234549355008 +1662138234591355904 +1662138234645357056 +1662138234690358016 +1662138234735358976 +1662138234780359936 +1662138234828360960 +1662138234870361856 +1662138234912362752 +1662138234957363712 +1662138235002364672 +1662138235050365696 +1662138235095366656 +1662138235143367680 +1662138235194368768 +1662138235236369664 +1662138235275370496 +1662138235317371392 +1662138235359372288 +1662138235407373312 +1662138235452374272 +1662138235497375232 +1662138235545376256 +1662138235596377344 +1662138235644378368 +1662138235686379264 +1662138235728380160 +1662138235773381120 +1662138235812381952 +1662138235854382848 +1662138235905383936 +1662138235947384832 +1662138235989385728 +1662138236037386752 +1662138236079387648 +1662138236121388544 +1662138236163389440 +1662138236211390464 +1662138236256391424 +1662138236298392320 +1662138236340393216 +1662138236388394240 +1662138236430395136 +1662138236475396096 +1662138236520397056 +1662138236565398016 +1662138236607398912 +1662138236652399872 +1662138236706401024 +1662138236748401920 +1662138236796402944 +1662138236844403968 +1662138236886404864 +1662138236931405824 +1662138236976406784 +1662138237018407680 +1662138237066408704 +1662138237108409600 +1662138237150410496 +1662138237201411584 +1662138237246412544 +1662138237288413440 +1662138237336414464 +1662138237378415360 +1662138237423416320 +1662138237471417344 +1662138237513418240 +1662138237555419136 +1662138237597420032 +1662138237642420992 +1662138237687421952 +1662138237729422848 +1662138237771423744 +1662138237813424640 +1662138237852425472 +1662138237894426368 +1662138237939427328 +1662138237981428224 +1662138238023429120 +1662138238065430016 +1662138238110430976 +1662138238152431872 +1662138238197432832 +1662138238248433920 +1662138238299435008 +1662138238350436096 +1662138238392436992 +1662138238434437888 +1662138238476438784 +1662138238515439616 +1662138238563440640 +1662138238608441600 +1662138238653442560 +1662138238695443456 +1662138238737444352 +1662138238779445248 +1662138238821446144 +1662138238863447040 +1662138238905447936 +1662138238956449024 +1662138239001449984 +1662138239049451008 +1662138239091451904 +1662138239130452736 +1662138239169453568 +1662138239211454464 +1662138239259455488 +1662138239304456448 +1662138239349457408 +1662138239400458496 +1662138239451459584 +1662138239499460608 +1662138239541461504 +1662138239586462464 +1662138239640463616 +1662138239682464512 +1662138239733465600 +1662138239778466560 +1662138239823467520 +1662138239865468416 +1662138239910469376 +1662138239961470464 +1662138240006471424 +1662138240048472320 +1662138240096473344 +1662138240141474304 +1662138240183475200 +1662138240225476096 +1662138240270477056 +1662138240315478016 +1662138240357478912 +1662138240402479872 +1662138240447480832 +1662138240492481792 +1662138240534482688 +1662138240576483584 +1662138240618484480 +1662138240663485440 +1662138240717486592 +1662138240762487552 +1662138240810488576 +1662138240849489408 +1662138240897490432 +1662138240945491456 +1662138240987492352 +1662138241032493312 +1662138241077494272 +1662138241122495232 +1662138241167496192 +1662138241209497088 +1662138241257498112 +1662138241299499008 +1662138241344499968 +1662138241389500928 +1662138241434501888 +1662138241479502848 +1662138241527503872 +1662138241569504768 +1662138241608505600 +1662138241650506496 +1662138241695507456 +1662138241743508480 +1662138241785509376 +1662138241830510336 +1662138241878511360 +1662138241923512320 +1662138241974513408 +1662138242019514368 +1662138242061515264 +1662138242106516224 +1662138242151517184 +1662138242193518080 +1662138242235518976 +1662138242277519872 +1662138242319520768 +1662138242361521664 +1662138242406522624 +1662138242454523648 +1662138242499524608 +1662138242538525440 +1662138242580526336 +1662138242622527232 +1662138242667528192 +1662138242712529152 +1662138242754530048 +1662138242796530944 +1662138242844531968 +1662138242889532928 +1662138242931533824 +1662138242982534912 +1662138243030535936 +1662138243072536832 +1662138243114537728 +1662138243159538688 +1662138243204539648 +1662138243249540608 +1662138243294541568 +1662138243336542464 +1662138243381543424 +1662138243423544320 +1662138243465545216 +1662138243510546176 +1662138243552547072 +1662138243594547968 +1662138243639548928 +1662138243681549824 +1662138243723550720 +1662138243765551616 +1662138243810552576 +1662138243861553664 +1662138243900554496 +1662138243948555520 +1662138243996556544 +1662138244044557568 +1662138244086558464 +1662138244131559424 +1662138244173560320 +1662138244218561280 +1662138244260562176 +1662138244308563200 +1662138244350564096 +1662138244392564992 +1662138244431565824 +1662138244473566720 +1662138244515567616 +1662138244557568512 +1662138244599569408 +1662138244641570304 +1662138244689571328 +1662138244737572352 +1662138244782573312 +1662138244824574208 +1662138244866575104 +1662138244914576128 +1662138244965577216 +1662138245010578176 +1662138245058579200 +1662138245106580224 +1662138245151581184 +1662138245196582144 +1662138245244583168 +1662138245292584192 +1662138245337585152 +1662138245391586304 +1662138245442587392 +1662138245487588352 +1662138245535589376 +1662138245577590272 +1662138245619591168 +1662138245667592192 +1662138245706593024 +1662138245754594048 +1662138245796594944 +1662138245847596032 +1662138245895597056 +1662138245937597952 +1662138245982598912 +1662138246027599872 +1662138246078600960 +1662138246123601920 +1662138246174603008 +1662138246216603904 +1662138246258604800 +1662138246300605696 +1662138246345606656 +1662138246387607552 +1662138246435608576 +1662138246480609536 +1662138246522610432 +1662138246567611392 +1662138246609612288 +1662138246654613248 +1662138246699614208 +1662138246744615168 +1662138246786616064 +1662138246825616896 +1662138246876617984 +1662138246918618880 +1662138246960619776 +1662138247011620864 +1662138247053621760 +1662138247104622848 +1662138247149623808 +1662138247191624704 +1662138247233625600 +1662138247284626688 +1662138247329627648 +1662138247371628544 +1662138247419629568 +1662138247461630464 +1662138247509631488 +1662138247554632448 +1662138247599633408 +1662138247650634496 +1662138247692635392 +1662138247740636416 +1662138247782637312 +1662138247833638400 +1662138247875639296 +1662138247917640192 +1662138247959641088 +1662138248007642112 +1662138248049643008 +1662138248097644032 +1662138248139644928 +1662138248181645824 +1662138248229646848 +1662138248268647680 +1662138248313648640 +1662138248355649536 +1662138248400650496 +1662138248442651392 +1662138248487652352 +1662138248532653312 +1662138248571654144 +1662138248616655104 +1662138248655655936 +1662138248697656832 +1662138248739657728 +1662138248784658688 +1662138248832659712 +1662138248874660608 +1662138248919661568 +1662138248967662592 +1662138249015663616 +1662138249057664512 +1662138249105665536 +1662138249150666496 +1662138249198667520 +1662138249240668416 +1662138249282669312 +1662138249324670208 +1662138249366671104 +1662138249411672064 +1662138249456673024 +1662138249501673984 +1662138249546674944 +1662138249594675968 +1662138249636676864 +1662138249678677760 +1662138249726678784 +1662138249768679680 +1662138249810680576 +1662138249855681536 +1662138249897682432 +1662138249942683392 +1662138249990684416 +1662138250032685312 +1662138250080686336 +1662138250122687232 +1662138250170688256 +1662138250215689216 +1662138250257690112 +1662138250305691136 +1662138250347692032 +1662138250398693120 +1662138250440694016 +1662138250485694976 +1662138250527695872 +1662138250569696768 +1662138250614697728 +1662138250662698752 +1662138250707699712 +1662138250752700672 +1662138250800701696 +1662138250845702656 +1662138250887703552 +1662138250938704640 +1662138250980705536 +1662138251022706432 +1662138251067707392 +1662138251112708352 +1662138251154709248 +1662138251196710144 +1662138251238711040 +1662138251280711936 +1662138251322712832 +1662138251364713728 +1662138251409714688 +1662138251451715584 +1662138251493716480 +1662138251541717504 +1662138251583718400 +1662138251628719360 +1662138251676720384 +1662138251715721216 +1662138251757722112 +1662138251808723200 +1662138251853724160 +1662138251898725120 +1662138251937725952 +1662138251985726976 +1662138252027727872 +1662138252072728832 +1662138252114729728 +1662138252156730624 +1662138252198731520 +1662138252246732544 +1662138252285733376 +1662138252327734272 +1662138252372735232 +1662138252420736256 +1662138252459737088 +1662138252501737984 +1662138252546738944 +1662138252591739904 +1662138252633740800 +1662138252690742016 +1662138252735742976 +1662138252783744000 +1662138252831745024 +1662138252873745920 +1662138252915746816 +1662138252957747712 +1662138252996748544 +1662138253041749504 +1662138253083750400 +1662138253125751296 +1662138253167752192 +1662138253215753216 +1662138253263754240 +1662138253314755328 +1662138253353756160 +1662138253398757120 +1662138253443758080 +1662138253494759168 +1662138253536760064 +1662138253581761024 +1662138253629762048 +1662138253683763200 +1662138253725764096 +1662138253770765056 +1662138253818766080 +1662138253857766912 +1662138253899767808 +1662138253953768960 +1662138254001769984 +1662138254043770880 +1662138254088771840 +1662138254136772864 +1662138254181773824 +1662138254223774720 +1662138254265775616 +1662138254310776576 +1662138254361777664 +1662138254406778624 +1662138254451779584 +1662138254496780544 +1662138254532781312 +1662138254577782272 +1662138254622783232 +1662138254670784256 +1662138254709785088 +1662138254751785984 +1662138254799787008 +1662138254841787904 +1662138254883788800 +1662138254931789824 +1662138254979790848 +1662138255024791808 +1662138255069792768 +1662138255111793664 +1662138255153794560 +1662138255195795456 +1662138255237796352 +1662138255282797312 +1662138255333798400 +1662138255378799360 +1662138255423800320 +1662138255462801152 +1662138255507802112 +1662138255549803008 +1662138255588803840 +1662138255633804800 +1662138255675805696 +1662138255717806592 +1662138255759807488 +1662138255801808384 +1662138255846809344 +1662138255894810368 +1662138255936811264 +1662138255981812224 +1662138256023813120 +1662138256065814016 +1662138256113815040 +1662138256161816064 +1662138256206817024 +1662138256242817792 +1662138256281818624 +1662138256329819648 +1662138256371820544 +1662138256419821568 +1662138256464822528 +1662138256506823424 +1662138256554824448 +1662138256596825344 +1662138256638826240 +1662138256683827200 +1662138256725828096 +1662138256770829056 +1662138256812829952 +1662138256860830976 +1662138256911832064 +1662138256956833024 +1662138257001833984 +1662138257052835072 +1662138257094835968 +1662138257139836928 +1662138257184837888 +1662138257235838976 +1662138257277839872 +1662138257328840960 +1662138257370841856 +1662138257412842752 +1662138257454843648 +1662138257496844544 +1662138257544845568 +1662138257586846464 +1662138257628847360 +1662138257670848256 +1662138257724849408 +1662138257769850368 +1662138257811851264 +1662138257853852160 +1662138257895853056 +1662138257937853952 +1662138257979854848 +1662138258021855744 +1662138258069856768 +1662138258117857792 +1662138258156858624 +1662138258201859584 +1662138258246860544 +1662138258294861568 +1662138258342862592 +1662138258387863552 +1662138258429864448 +1662138258471865344 +1662138258516866304 +1662138258567867392 +1662138258609868288 +1662138258654869248 +1662138258696870144 +1662138258741871104 +1662138258786872064 +1662138258825872896 +1662138258867873792 +1662138258912874752 +1662138258957875712 +1662138259005876736 +1662138259047877632 +1662138259095878656 +1662138259149879808 +1662138259200880896 +1662138259242881792 +1662138259287882752 +1662138259335883776 +1662138259386884864 +1662138259428885760 +1662138259470886656 +1662138259512887552 +1662138259560888576 +1662138259602889472 +1662138259647890432 +1662138259689891328 +1662138259734892288 +1662138259776893184 +1662138259824894208 +1662138259866895104 +1662138259911896064 +1662138259956897024 +1662138259998897920 +1662138260040898816 +1662138260088899840 +1662138260133900800 +1662138260175901696 +1662138260226902784 +1662138260268903680 +1662138260316904704 +1662138260364905728 +1662138260406906624 +1662138260448907520 +1662138260490908416 +1662138260529909248 +1662138260574910208 +1662138260616911104 +1662138260667912192 +1662138260721913344 +1662138260769914368 +1662138260814915328 +1662138260856916224 +1662138260898917120 +1662138260937917952 +1662138260985918976 +1662138261036920064 +1662138261081921024 +1662138261120921856 +1662138261165922816 +1662138261207923712 +1662138261252924672 +1662138261300925696 +1662138261342926592 +1662138261384927488 +1662138261441928704 +1662138261483929600 +1662138261528930560 +1662138261573931520 +1662138261618932480 +1662138261666933504 +1662138261708934400 +1662138261753935360 +1662138261801936384 +1662138261849937408 +1662138261900938496 +1662138261945939456 +1662138261987940352 +1662138262026941184 +1662138262074942208 +1662138262116943104 +1662138262164944128 +1662138262209945088 +1662138262254946048 +1662138262296946944 +1662138262350948096 +1662138262395949056 +1662138262437949952 +1662138262482950912 +1662138262533952000 +1662138262575952896 +1662138262617953792 +1662138262668954880 +1662138262716955904 +1662138262767956992 +1662138262815958016 +1662138262857958912 +1662138262905959936 +1662138262950960896 +1662138262992961792 +1662138263043962880 +1662138263088963840 +1662138263130964736 +1662138263178965760 +1662138263220966656 +1662138263265967616 +1662138263304968448 +1662138263355969536 +1662138263400970496 +1662138263451971584 +1662138263493972480 +1662138263544973568 +1662138263592974592 +1662138263634975488 +1662138263673976320 +1662138263718977280 +1662138263763978240 +1662138263811979264 +1662138263859980288 +1662138263901981184 +1662138263949982208 +1662138263991983104 +1662138264036984064 +1662138264087985152 +1662138264129986048 +1662138264174987008 +1662138264219987968 +1662138264258988800 +1662138264303989760 +1662138264354990848 +1662138264399991808 +1662138264444992768 +1662138264483993600 +1662138264525994496 +1662138264573995520 +1662138264618996480 +1662138264660997376 +1662138264702998272 +1662138264762999552 +1662138264808000512 +1662138264850001408 +1662138264898002432 +1662138264943003392 +1662138264985004288 +1662138265030005248 +1662138265072006144 +1662138265114007040 +1662138265159008000 +1662138265207009024 +1662138265249009920 +1662138265300011008 +1662138265348012032 +1662138265390012928 +1662138265432013824 +1662138265477014784 +1662138265522015744 +1662138265564016640 +1662138265606017536 +1662138265651018496 +1662138265696019456 +1662138265744020480 +1662138265786021376 +1662138265831022336 +1662138265873023232 +1662138265918024192 +1662138265966025216 +1662138266008026112 +1662138266050027008 +1662138266095027968 +1662138266146029056 +1662138266188029952 +1662138266239031040 +1662138266284032000 +1662138266332033024 +1662138266371033856 +1662138266413034752 +1662138266455035648 +1662138266497036544 +1662138266542037504 +1662138266587038464 +1662138266629039360 +1662138266674040320 +1662138266725041408 +1662138266770042368 +1662138266821043456 +1662138266863044352 +1662138266908045312 +1662138266950046208 +1662138266992047104 +1662138267037048064 +1662138267079048960 +1662138267121049856 +1662138267166050816 +1662138267208051712 +1662138267253052672 +1662138267298053632 +1662138267343054592 +1662138267391055616 +1662138267433056512 +1662138267475057408 +1662138267520058368 +1662138267568059392 +1662138267610060288 +1662138267649061120 +1662138267694062080 +1662138267739063040 +1662138267778063872 +1662138267820064768 +1662138267862065664 +1662138267907066624 +1662138267952067584 +1662138267994068480 +1662138268039069440 +1662138268078070272 +1662138268117071104 +1662138268165072128 +1662138268210073088 +1662138268264074240 +1662138268306075136 +1662138268348076032 +1662138268387076864 +1662138268429077760 +1662138268471078656 +1662138268519079680 +1662138268564080640 +1662138268606081536 +1662138268657082624 +1662138268696083456 +1662138268744084480 +1662138268792085504 +1662138268831086336 +1662138268879087360 +1662138268924088320 +1662138268972089344 +1662138269017090304 +1662138269068091392 +1662138269107092224 +1662138269152093184 +1662138269194094080 +1662138269236094976 +1662138269290096128 +1662138269335097088 +1662138269377097984 +1662138269419098880 +1662138269464099840 +1662138269506100736 +1662138269548101632 +1662138269590102528 +1662138269632103424 +1662138269680104448 +1662138269731105536 +1662138269776106496 +1662138269818107392 +1662138269863108352 +1662138269905109248 +1662138269956110336 +1662138269998111232 +1662138270040112128 +1662138270085113088 +1662138270130114048 +1662138270172114944 +1662138270217115904 +1662138270262116864 +1662138270304117760 +1662138270352118784 +1662138270394119680 +1662138270442120704 +1662138270484121600 +1662138270529122560 +1662138270571123456 +1662138270613124352 +1662138270661125376 +1662138270703126272 +1662138270745127168 +1662138270790128128 +1662138270841129216 +1662138270886130176 +1662138270928131072 +1662138270973132032 +1662138271015132928 +1662138271063133952 +1662138271108134912 +1662138271156135936 +1662138271201136896 +1662138271243137792 +1662138271294138880 +1662138271336139776 +1662138271384140800 +1662138271426141696 +1662138271477142784 +1662138271519143680 +1662138271558144512 +1662138271600145408 +1662138271645146368 +1662138271690147328 +1662138271729148160 +1662138271777149184 +1662138271819150080 +1662138271864151040 +1662138271912152064 +1662138271954152960 +1662138271996153856 +1662138272038154752 +1662138272080155648 +1662138272125156608 +1662138272173157632 +1662138272215158528 +1662138272260159488 +1662138272305160448 +1662138272347161344 +1662138272389162240 +1662138272434163200 +1662138272485164288 +1662138272530165248 +1662138272572166144 +1662138272614167040 +1662138272659168000 +1662138272716169216 +1662138272758170112 +1662138272803171072 +1662138272848172032 +1662138272893172992 +1662138272935173888 +1662138272983174912 +1662138273028175872 +1662138273070176768 +1662138273118177792 +1662138273172178944 +1662138273217179904 +1662138273265180928 +1662138273313181952 +1662138273358182912 +1662138273406183936 +1662138273448184832 +1662138273490185728 +1662138273538186752 +1662138273583187712 +1662138273634188800 +1662138273676189696 +1662138273721190656 +1662138273766191616 +1662138273808192512 +1662138273850193408 +1662138273892194304 +1662138273931195136 +1662138273970195968 +1662138274012196864 +1662138274057197824 +1662138274099198720 +1662138274141199616 +1662138274183200512 +1662138274231201536 +1662138274279202560 +1662138274324203520 +1662138274372204544 +1662138274414205440 +1662138274459206400 +1662138274501207296 +1662138274549208320 +1662138274591209216 +1662138274633210112 +1662138274681211136 +1662138274729212160 +1662138274771213056 +1662138274813213952 +1662138274855214848 +1662138274897215744 +1662138274939216640 +1662138274981217536 +1662138275026218496 +1662138275071219456 +1662138275113220352 +1662138275155221248 +1662138275197222144 +1662138275242223104 +1662138275287224064 +1662138275332225024 +1662138275380226048 +1662138275425227008 +1662138275473228032 +1662138275518228992 +1662138275563229952 +1662138275602230784 +1662138275647231744 +1662138275689232640 +1662138275734233600 +1662138275776234496 +1662138275821235456 +1662138275863236352 +1662138275905237248 +1662138275953238272 +1662138275998239232 +1662138276040240128 +1662138276085241088 +1662138276133242112 +1662138276178243072 +1662138276220243968 +1662138276265244928 +1662138276307245824 +1662138276355246848 +1662138276394247680 +1662138276445248768 +1662138276487249664 +1662138276529250560 +1662138276577251584 +1662138276622252544 +1662138276673253632 +1662138276718254592 +1662138276760255488 +1662138276802256384 +1662138276850257408 +1662138276892258304 +1662138276940259328 +1662138276982260224 +1662138277030261248 +1662138277072262144 +1662138277120263168 +1662138277165264128 +1662138277210265088 +1662138277252265984 +1662138277303267072 +1662138277342267904 +1662138277384268800 +1662138277423269632 +1662138277465270528 +1662138277507271424 +1662138277555272448 +1662138277600273408 +1662138277645274368 +1662138277696275456 +1662138277741276416 +1662138277783277312 +1662138277825278208 +1662138277864279040 +1662138277906279936 +1662138277951280896 +1662138277999281920 +1662138278044282880 +1662138278086283776 +1662138278125284608 +1662138278179285760 +1662138278224286720 +1662138278266287616 +1662138278308288512 +1662138278350289408 +1662138278398290432 +1662138278443291392 +1662138278485292288 +1662138278524293120 +1662138278566294016 +1662138278608294912 +1662138278662296064 +1662138278710297088 +1662138278752297984 +1662138278800299008 +1662138278845299968 +1662138278887300864 +1662138278929301760 +1662138278971302656 +1662138279016303616 +1662138279058304512 +1662138279100305408 +1662138279151306496 +1662138279196307456 +1662138279244308480 +1662138279295309568 +1662138279343310592 +1662138279385311488 +1662138279430312448 +1662138279475313408 +1662138279526314496 +1662138279571315456 +1662138279634316800 +1662138279673317632 +1662138279721318656 +1662138279766319616 +1662138279820320768 +1662138279862321664 +1662138279907322624 +1662138279952323584 +1662138279994324480 +1662138280039325440 +1662138280081326336 +1662138280126327296 +1662138280174328320 +1662138280222329344 +1662138280264330240 +1662138280306331136 +1662138280348332032 +1662138280390332928 +1662138280438333952 +1662138280483334912 +1662138280525335808 +1662138280567336704 +1662138280615337728 +1662138280663338752 +1662138280705339648 +1662138280747340544 +1662138280792341504 +1662138280834342400 +1662138280879343360 +1662138280921344256 +1662138280966345216 +1662138281011346176 +1662138281056347136 +1662138281104348160 +1662138281152349184 +1662138281194350080 +1662138281242351104 +1662138281287352064 +1662138281338353152 +1662138281380354048 +1662138281419354880 +1662138281461355776 +1662138281503356672 +1662138281557357824 +1662138281599358720 +1662138281644359680 +1662138281689360640 +1662138281731361536 +1662138281782362624 +1662138281824363520 +1662138281878364672 +1662138281926365696 +1662138281971366656 +1662138282022367744 +1662138282064368640 +1662138282106369536 +1662138282148370432 +1662138282190371328 +1662138282232372224 +1662138282271373056 +1662138282313373952 +1662138282352374784 +1662138282397375744 +1662138282442376704 +1662138282484377600 +1662138282532378624 +1662138282574379520 +1662138282619380480 +1662138282661381376 +1662138282703382272 +1662138282745383168 +1662138282787384064 +1662138282829384960 +1662138282889386240 +1662138282934387200 +1662138282976388096 +1662138283024389120 +1662138283066390016 +1662138283108390912 +1662138283153391872 +1662138283195392768 +1662138283237393664 +1662138283279394560 +1662138283330395648 +1662138283375396608 +1662138283426397696 +1662138283477398784 +1662138283519399680 +1662138283561400576 +1662138283603401472 +1662138283645402368 +1662138283687403264 +1662138283729404160 +1662138283768404992 +1662138283810405888 +1662138283855406848 +1662138283900407808 +1662138283942408704 +1662138283987409664 +1662138284032410624 +1662138284077411584 +1662138284122412544 +1662138284167413504 +1662138284212414464 +1662138284254415360 +1662138284302416384 +1662138284350417408 +1662138284404418560 +1662138284446419456 +1662138284488420352 +1662138284536421376 +1662138284584422400 +1662138284626423296 +1662138284668424192 +1662138284728425472 +1662138284770426368 +1662138284812427264 +1662138284854428160 +1662138284896429056 +1662138284941430016 +1662138284992431104 +1662138285037432064 +1662138285082433024 +1662138285130434048 +1662138285178435072 +1662138285229436160 +1662138285271437056 +1662138285319438080 +1662138285370439168 +1662138285418440192 +1662138285460441088 +1662138285502441984 +1662138285550443008 +1662138285601444096 +1662138285655445248 +1662138285694446080 +1662138285742447104 +1662138285784448000 +1662138285826448896 +1662138285880450048 +1662138285928451072 +1662138285970451968 +1662138286012452864 +1662138286057453824 +1662138286108454912 +1662138286165456128 +1662138286207457024 +1662138286249457920 +1662138286297458944 +1662138286342459904 +1662138286390460928 +1662138286435461888 +1662138286480462848 +1662138286519463680 +1662138286564464640 +1662138286609465600 +1662138286660466688 +1662138286711467776 +1662138286756468736 +1662138286804469760 +1662138286852470784 +1662138286891471616 +1662138286933472512 +1662138286975473408 +1662138287020474368 +1662138287071475456 +1662138287113476352 +1662138287152477184 +1662138287197478144 +1662138287239479040 +1662138287281479936 +1662138287320480768 +1662138287362481664 +1662138287416482816 +1662138287458483712 +1662138287500484608 +1662138287545485568 +1662138287587486464 +1662138287629487360 +1662138287677488384 +1662138287719489280 +1662138287761490176 +1662138287806491136 +1662138287851492096 +1662138287893492992 +1662138287938493952 +1662138287983494912 +1662138288025495808 +1662138288067496704 +1662138288118497792 +1662138288157498624 +1662138288199499520 +1662138288238500352 +1662138288283501312 +1662138288325502208 +1662138288373503232 +1662138288418504192 +1662138288460505088 +1662138288502505984 +1662138288547506944 +1662138288592507904 +1662138288634508800 +1662138288676509696 +1662138288718510592 +1662138288763511552 +1662138288814512640 +1662138288856513536 +1662138288898514432 +1662138288940515328 +1662138288985516288 +1662138289027517184 +1662138289075518208 +1662138289117519104 +1662138289159520000 +1662138289201520896 +1662138289246521856 +1662138289291522816 +1662138289336523776 +1662138289384524800 +1662138289435525888 +1662138289480526848 +1662138289528527872 +1662138289576528896 +1662138289621529856 +1662138289663530752 +1662138289711531776 +1662138289759532800 +1662138289810533888 +1662138289852534784 +1662138289897535744 +1662138289942536704 +1662138289981537536 +1662138290026538496 +1662138290068539392 +1662138290122540544 +1662138290167541504 +1662138290215542528 +1662138290260543488 +1662138290302544384 +1662138290350545408 +1662138290392546304 +1662138290446547456 +1662138290494548480 +1662138290539549440 +1662138290584550400 +1662138290626551296 +1662138290674552320 +1662138290725553408 +1662138290767554304 +1662138290815555328 +1662138290857556224 +1662138290899557120 +1662138290944558080 +1662138290995559168 +1662138291037560064 +1662138291082561024 +1662138291124561920 +1662138291166562816 +1662138291208563712 +1662138291253564672 +1662138291304565760 +1662138291352566784 +1662138291394567680 +1662138291439568640 +1662138291484569600 +1662138291532570624 +1662138291574571520 +1662138291622572544 +1662138291667573504 +1662138291712574464 +1662138291760575488 +1662138291802576384 +1662138291844577280 +1662138291889578240 +1662138291931579136 +1662138291979580160 +1662138292021581056 +1662138292063581952 +1662138292105582848 +1662138292147583744 +1662138292198584832 +1662138292243585792 +1662138292288586752 +1662138292333587712 +1662138292378588672 +1662138292429589760 +1662138292471590656 +1662138292510591488 +1662138292552592384 +1662138292597593344 +1662138292645594368 +1662138292687595264 +1662138292726596096 +1662138292768596992 +1662138292813597952 +1662138292861598976 +1662138292903599872 +1662138292948600832 +1662138292990601728 +1662138293032602624 +1662138293077603584 +1662138293125604608 +1662138293170605568 +1662138293218606592 +1662138293266607616 +1662138293311608576 +1662138293359609600 +1662138293404610560 +1662138293446611456 +1662138293488612352 +1662138293533613312 +1662138293581614336 +1662138293623615232 +1662138293665616128 +1662138293710617088 +1662138293755618048 +1662138293800619008 +1662138293845619968 +1662138293887620864 +1662138293929621760 +1662138293989623040 +1662138294037624064 +1662138294085625088 +1662138294127625984 +1662138294172626944 +1662138294214627840 +1662138294265628928 +1662138294307629824 +1662138294349630720 +1662138294394631680 +1662138294436632576 +1662138294481633536 +1662138294526634496 +1662138294574635520 +1662138294619636480 +1662138294661637376 +1662138294706638336 +1662138294751639296 +1662138294796640256 +1662138294841641216 +1662138294886642176 +1662138294931643136 +1662138294973644032 +1662138295018644992 +1662138295063645952 +1662138295105646848 +1662138295153647872 +1662138295195648768 +1662138295246649856 +1662138295288650752 +1662138295339651840 +1662138295384652800 +1662138295426653696 +1662138295480654848 +1662138295531655936 +1662138295573656832 +1662138295618657792 +1662138295663658752 +1662138295708659712 +1662138295765660928 +1662138295810661888 +1662138295852662784 +1662138295897663744 +1662138295936664576 +1662138295975665408 +1662138296026666496 +1662138296068667392 +1662138296110668288 +1662138296155669248 +1662138296200670208 +1662138296242671104 +1662138296284672000 +1662138296329672960 +1662138296380674048 +1662138296419674880 +1662138296470675968 +1662138296512676864 +1662138296554677760 +1662138296602678784 +1662138296644679680 +1662138296686680576 +1662138296737681664 +1662138296779682560 +1662138296821683456 +1662138296872684544 +1662138296917685504 +1662138296959686400 +1662138297016687616 +1662138297061688576 +1662138297109689600 +1662138297154690560 +1662138297193691392 +1662138297235692288 +1662138297289693440 +1662138297337694464 +1662138297382695424 +1662138297424696320 +1662138297466697216 +1662138297508698112 +1662138297559699200 +1662138297601700096 +1662138297646701056 +1662138297697702144 +1662138297742703104 +1662138297784704000 +1662138297823704832 +1662138297862705664 +1662138297901706496 +1662138297952707584 +1662138298000708608 +1662138298045709568 +1662138298090710528 +1662138298141711616 +1662138298183712512 +1662138298225713408 +1662138298270714368 +1662138298315715328 +1662138298360716288 +1662138298405717248 +1662138298447718144 +1662138298492719104 +1662138298534720000 +1662138298576720896 +1662138298618721792 +1662138298660722688 +1662138298702723584 +1662138298744724480 +1662138298798725632 +1662138298840726528 +1662138298888727552 +1662138298936728576 +1662138298981729536 +1662138299023730432 +1662138299065731328 +1662138299107732224 +1662138299155733248 +1662138299197734144 +1662138299239735040 +1662138299287736064 +1662138299329736960 +1662138299374737920 +1662138299428739072 +1662138299479740160 +1662138299527741184 +1662138299578742272 +1662138299620743168 +1662138299662744064 +1662138299707745024 +1662138299749745920 +1662138299803747072 +1662138299848748032 +1662138299902749184 +1662138299944750080 +1662138299986750976 +1662138300028751872 +1662138300073752832 +1662138300118753792 +1662138300160754688 +1662138300199755520 +1662138300241756416 +1662138300286757376 +1662138300331758336 +1662138300373759232 +1662138300421760256 +1662138300463761152 +1662138300505762048 +1662138300559763200 +1662138300601764096 +1662138300643764992 +1662138300691766016 +1662138300730766848 +1662138300781767936 +1662138300823768832 +1662138300865769728 +1662138300904770560 +1662138300949771520 +1662138300997772544 +1662138301039773440 +1662138301087774464 +1662138301129775360 +1662138301174776320 +1662138301222777344 +1662138301264778240 +1662138301306779136 +1662138301351780096 +1662138301399781120 +1662138301441782016 +1662138301489783040 +1662138301531783936 +1662138301573784832 +1662138301621785856 +1662138301666786816 +1662138301708787712 +1662138301753788672 +1662138301795789568 +1662138301837790464 +1662138301879791360 +1662138301927792384 +1662138301978793472 +1662138302023794432 +1662138302065795328 +1662138302116796416 +1662138302167797504 +1662138302215798528 +1662138302266799616 +1662138302308800512 +1662138302356801536 +1662138302398802432 +1662138302446803456 +1662138302488804352 +1662138302533805312 +1662138302587806464 +1662138302629807360 +1662138302671808256 +1662138302713809152 +1662138302758810112 +1662138302803811072 +1662138302851812096 +1662138302896813056 +1662138302938813952 +1662138302983814912 +1662138303025815808 +1662138303073816832 +1662138303118817792 +1662138303163818752 +1662138303208819712 +1662138303256820736 +1662138303298821632 +1662138303340822528 +1662138303391823616 +1662138303439824640 +1662138303487825664 +1662138303532826624 +1662138303577827584 +1662138303625828608 +1662138303667829504 +1662138303709830400 +1662138303754831360 +1662138303799832320 +1662138303844833280 +1662138303886834176 +1662138303937835264 +1662138303982836224 +1662138304024837120 +1662138304066838016 +1662138304114839040 +1662138304171840256 +1662138304213841152 +1662138304264842240 +1662138304309843200 +1662138304357844224 +1662138304405845248 +1662138304450846208 +1662138304492847104 +1662138304540848128 +1662138304585849088 +1662138304627849984 +1662138304675851008 +1662138304720851968 +1662138304765852928 +1662138304813853952 +1662138304855854848 +1662138304903855872 +1662138304948856832 +1662138304999857920 +1662138305047858944 +1662138305089859840 +1662138305140860928 +1662138305194862080 +1662138305239863040 +1662138305278863872 +1662138305326864896 +1662138305374865920 +1662138305419866880 +1662138305461867776 +1662138305509868800 +1662138305557869824 +1662138305599870720 +1662138305647871744 +1662138305689872640 +1662138305734873600 +1662138305776874496 +1662138305830875648 +1662138305878876672 +1662138305929877760 +1662138305974878720 +1662138306019879680 +1662138306073880832 +1662138306115881728 +1662138306160882688 +1662138306202883584 +1662138306250884608 +1662138306292885504 +1662138306334886400 +1662138306376887296 +1662138306421888256 +1662138306463889152 +1662138306505890048 +1662138306565891328 +1662138306610892288 +1662138306652893184 +1662138306694894080 +1662138306742895104 +1662138306787896064 +1662138306838897152 +1662138306880898048 +1662138306925899008 +1662138306970899968 +1662138307021901056 +1662138307060901888 +1662138307105902848 +1662138307147903744 +1662138307192904704 +1662138307237905664 +1662138307288906752 +1662138307327907584 +1662138307375908608 +1662138307420909568 +1662138307468910592 +1662138307516911616 +1662138307561912576 +1662138307612913664 +1662138307654914560 +1662138307705915648 +1662138307753916672 +1662138307801917696 +1662138307852918784 +1662138307900919808 +1662138307948920832 +1662138307990921728 +1662138308032922624 +1662138308080923648 +1662138308125924608 +1662138308176925696 +1662138308221926656 +1662138308266927616 +1662138308308928512 +1662138308356929536 +1662138308401930496 +1662138308446931456 +1662138308494932480 +1662138308545933568 +1662138308584934400 +1662138308623935232 +1662138308668936192 +1662138308713937152 +1662138308758938112 +1662138308800939008 +1662138308845939968 +1662138308887940864 +1662138308929941760 +1662138308980942848 +1662138309022943744 +1662138309064944640 +1662138309109945600 +1662138309157946624 +1662138309205947648 +1662138309256948736 +1662138309301949696 +1662138309352950784 +1662138309397951744 +1662138309442952704 +1662138309493953792 +1662138309535954688 +1662138309583955712 +1662138309634956800 +1662138309676957696 +1662138309718958592 +1662138309763959552 +1662138309805960448 +1662138309859961600 +1662138309907962624 +1662138309949963520 +1662138310006964736 +1662138310048965632 +1662138310090966528 +1662138310138967552 +1662138310183968512 +1662138310225969408 +1662138310282970624 +1662138310321971456 +1662138310363972352 +1662138310411973376 +1662138310456974336 +1662138310501975296 +1662138310552976384 +1662138310594977280 +1662138310639978240 +1662138310684979200 +1662138310729980160 +1662138310771981056 +1662138310819982080 +1662138310861982976 +1662138310909984000 +1662138310960985088 +1662138311011986176 +1662138311065987328 +1662138311110988288 +1662138311152989184 +1662138311194990080 +1662138311239991040 +1662138311284992000 +1662138311332993024 +1662138311380994048 +1662138311428995072 +1662138311479996160 +1662138311530997248 +1662138311578998272 +1662138311623999232 +1662138311675000320 +1662138311717001216 +1662138311759002112 +1662138311804003072 +1662138311855004160 +1662138311906005248 +1662138311951006208 +1662138311993007104 +1662138312044008192 +1662138312089009152 +1662138312134010112 +1662138312179011072 +1662138312224012032 +1662138312266012928 +1662138312314013952 +1662138312362014976 +1662138312407015936 +1662138312449016832 +1662138312497017856 +1662138312536018688 +1662138312593019904 +1662138312638020864 +1662138312686021888 +1662138312731022848 +1662138312782023936 +1662138312830024960 +1662138312878025984 +1662138312920026880 +1662138312962027776 +1662138313010028800 +1662138313064029952 +1662138313112030976 +1662138313163032064 +1662138313208033024 +1662138313253033984 +1662138313301035008 +1662138313343035904 +1662138313388036864 +1662138313427037696 +1662138313472038656 +1662138313517039616 +1662138313565040640 +1662138313610041600 +1662138313658042624 +1662138313703043584 +1662138313748044544 +1662138313787045376 +1662138313841046528 +1662138313886047488 +1662138313931048448 +1662138313976049408 +1662138314021050368 +1662138314063051264 +1662138314111052288 +1662138314156053248 +1662138314201054208 +1662138314258055424 +1662138314303056384 +1662138314345057280 +1662138314387058176 +1662138314432059136 +1662138314474060032 +1662138314516060928 +1662138314564061952 +1662138314612062976 +1662138314657063936 +1662138314696064768 +1662138314738065664 +1662138314783066624 +1662138314783066624 +1662138314828067584 +1662138314873068544 +1662138314915069440 +1662138314957070336 +1662138314999071232 +1662138315041072128 +1662138315080072960 +1662138315128073984 +1662138315176075008 +1662138315224076032 +1662138315269076992 +1662138315317078016 +1662138315362078976 +1662138315410080000 +1662138315461081088 +1662138315509082112 +1662138315551083008 +1662138315599084032 +1662138315641084928 +1662138315683085824 +1662138315728086784 +1662138315770087680 +1662138315815088640 +1662138315854089472 +1662138315905090560 +1662138315947091456 +1662138315992092416 +1662138316037093376 +1662138316082094336 +1662138316133095424 +1662138316178096384 +1662138316223097344 +1662138316265098240 +1662138316310099200 +1662138316358100224 +1662138316397101056 +1662138316442102016 +1662138316493103104 +1662138316538104064 +1662138316583105024 +1662138316625105920 +1662138316676107008 +1662138316727108096 +1662138316772109056 +1662138316814109952 +1662138316859110912 +1662138316901111808 +1662138316946112768 +1662138316994113792 +1662138317036114688 +1662138317081115648 +1662138317123116544 +1662138317165117440 diff --git a/Examples/Monocular-Inertial/MIMIR_TimeStamps/OceanFloor_track0_light.txt b/Examples/Monocular-Inertial/MIMIR_TimeStamps/OceanFloor_track0_light.txt new file mode 100644 index 0000000000..cca6f70bc4 --- /dev/null +++ b/Examples/Monocular-Inertial/MIMIR_TimeStamps/OceanFloor_track0_light.txt @@ -0,0 +1,2421 @@ +1662135911410189568 +1662135911452190464 +1662135911491191296 +1662135911539192320 +1662135911584193280 +1662135911638194432 +1662135911683195392 +1662135911731196416 +1662135911776197376 +1662135911824198400 +1662135911866199296 +1662135911908200192 +1662135911953201152 +1662135912001202176 +1662135912052203264 +1662135912094204160 +1662135912136205056 +1662135912181206016 +1662135912232207104 +1662135912280208128 +1662135912322209024 +1662135912370210048 +1662135912412210944 +1662135912454211840 +1662135912496212736 +1662135912538213632 +1662135912583214592 +1662135912625215488 +1662135912667216384 +1662135912712217344 +1662135912754218240 +1662135912796219136 +1662135912844220160 +1662135912889221120 +1662135912928221952 +1662135912970222848 +1662135913015223808 +1662135913057224704 +1662135913108225792 +1662135913159226880 +1662135913210227968 +1662135913249228800 +1662135913306230016 +1662135913351230976 +1662135913396231936 +1662135913441232896 +1662135913492233984 +1662135913540235008 +1662135913585235968 +1662135913639237120 +1662135913681238016 +1662135913729239040 +1662135913774240000 +1662135913825241088 +1662135913867241984 +1662135913909242880 +1662135913951243776 +1662135913993244672 +1662135914041245696 +1662135914086246656 +1662135914131247616 +1662135914173248512 +1662135914218249472 +1662135914260250368 +1662135914302251264 +1662135914350252288 +1662135914392253184 +1662135914437254144 +1662135914491255296 +1662135914530256128 +1662135914569256960 +1662135914611257856 +1662135914653258752 +1662135914698259712 +1662135914740260608 +1662135914782261504 +1662135914824262400 +1662135914866263296 +1662135914908264192 +1662135914953265152 +1662135914998266112 +1662135915046267136 +1662135915091268096 +1662135915136269056 +1662135915181270016 +1662135915223270912 +1662135915277272064 +1662135915325273088 +1662135915364273920 +1662135915415275008 +1662135915457275904 +1662135915499276800 +1662135915544277760 +1662135915586278656 +1662135915628279552 +1662135915676280576 +1662135915718281472 +1662135915772282624 +1662135915811283456 +1662135915853284352 +1662135915907285504 +1662135915949286400 +1662135915994287360 +1662135916039288320 +1662135916093289472 +1662135916135290368 +1662135916177291264 +1662135916222292224 +1662135916267293184 +1662135916309294080 +1662135916351294976 +1662135916393295872 +1662135916438296832 +1662135916486297856 +1662135916531298816 +1662135916573299712 +1662135916621300736 +1662135916669301760 +1662135916714302720 +1662135916759303680 +1662135916807304704 +1662135916849305600 +1662135916891306496 +1662135916933307392 +1662135916984308480 +1662135917035309568 +1662135917080310528 +1662135917125311488 +1662135917167312384 +1662135917212313344 +1662135917257314304 +1662135917311315456 +1662135917356316416 +1662135917395317248 +1662135917437318144 +1662135917482319104 +1662135917524320000 +1662135917569320960 +1662135917623322112 +1662135917668323072 +1662135917716324096 +1662135917758324992 +1662135917800325888 +1662135917839326720 +1662135917887327744 +1662135917929328640 +1662135917971329536 +1662135918013330432 +1662135918052331264 +1662135918094332160 +1662135918136333056 +1662135918178333952 +1662135918220334848 +1662135918262335744 +1662135918307336704 +1662135918361337856 +1662135918406338816 +1662135918448339712 +1662135918508340992 +1662135918550341888 +1662135918592342784 +1662135918643343872 +1662135918685344768 +1662135918733345792 +1662135918775346688 +1662135918817347584 +1662135918856348416 +1662135918898349312 +1662135918946350336 +1662135918994351360 +1662135919036352256 +1662135919078353152 +1662135919120354048 +1662135919159354880 +1662135919201355776 +1662135919246356736 +1662135919294357760 +1662135919342358784 +1662135919387359744 +1662135919429360640 +1662135919474361600 +1662135919513362432 +1662135919555363328 +1662135919597364224 +1662135919645365248 +1662135919690366208 +1662135919732367104 +1662135919774368000 +1662135919816368896 +1662135919861369856 +1662135919906370816 +1662135919951371776 +1662135920005372928 +1662135920047373824 +1662135920095374848 +1662135920140375808 +1662135920185376768 +1662135920230377728 +1662135920272378624 +1662135920314379520 +1662135920356380416 +1662135920398381312 +1662135920440382208 +1662135920488383232 +1662135920536384256 +1662135920578385152 +1662135920617385984 +1662135920659386880 +1662135920704387840 +1662135920749388800 +1662135920797389824 +1662135920851390976 +1662135920896391936 +1662135920941392896 +1662135920983393792 +1662135921025394688 +1662135921070395648 +1662135921115396608 +1662135921154397440 +1662135921196398336 +1662135921250399488 +1662135921292400384 +1662135921358401792 +1662135921406402816 +1662135921448403712 +1662135921496404736 +1662135921544405760 +1662135921595406848 +1662135921640407808 +1662135921685408768 +1662135921724409600 +1662135921775410688 +1662135921823411712 +1662135921865412608 +1662135921907413504 +1662135921952414464 +1662135921997415424 +1662135922039416320 +1662135922081417216 +1662135922123418112 +1662135922165419008 +1662135922207419904 +1662135922249420800 +1662135922300421888 +1662135922345422848 +1662135922390423808 +1662135922435424768 +1662135922480425728 +1662135922522426624 +1662135922567427584 +1662135922609428480 +1662135922654429440 +1662135922705430528 +1662135922750431488 +1662135922792432384 +1662135922840433408 +1662135922897434624 +1662135922942435584 +1662135922987436544 +1662135923029437440 +1662135923071438336 +1662135923113439232 +1662135923155440128 +1662135923203441152 +1662135923245442048 +1662135923284442880 +1662135923326443776 +1662135923365444608 +1662135923407445504 +1662135923449446400 +1662135923491447296 +1662135923533448192 +1662135923578449152 +1662135923620450048 +1662135923674451200 +1662135923716452096 +1662135923758452992 +1662135923800453888 +1662135923848454912 +1662135923890455808 +1662135923932456704 +1662135923983457792 +1662135924025458688 +1662135924079459840 +1662135924121460736 +1662135924163461632 +1662135924208462592 +1662135924268463872 +1662135924310464768 +1662135924355465728 +1662135924394466560 +1662135924436467456 +1662135924481468416 +1662135924532469504 +1662135924577470464 +1662135924616471296 +1662135924667472384 +1662135924709473280 +1662135924751474176 +1662135924793475072 +1662135924835475968 +1662135924883476992 +1662135924925477888 +1662135924973478912 +1662135925015479808 +1662135925057480704 +1662135925099481600 +1662135925147482624 +1662135925186483456 +1662135925228484352 +1662135925273485312 +1662135925315486208 +1662135925360487168 +1662135925408488192 +1662135925453489152 +1662135925495490048 +1662135925540491008 +1662135925582491904 +1662135925624492800 +1662135925663493632 +1662135925708494592 +1662135925750495488 +1662135925798496512 +1662135925846497536 +1662135925888498432 +1662135925930499328 +1662135925987500544 +1662135926035501568 +1662135926077502464 +1662135926122503424 +1662135926164504320 +1662135926209505280 +1662135926263506432 +1662135926311507456 +1662135926353508352 +1662135926401509376 +1662135926449510400 +1662135926488511232 +1662135926530512128 +1662135926578513152 +1662135926620514048 +1662135926665515008 +1662135926707515904 +1662135926749516800 +1662135926791517696 +1662135926833518592 +1662135926875519488 +1662135926914520320 +1662135926959521280 +1662135927001522176 +1662135927055523328 +1662135927097524224 +1662135927148525312 +1662135927199526400 +1662135927238527232 +1662135927280528128 +1662135927322529024 +1662135927367529984 +1662135927406530816 +1662135927445531648 +1662135927487532544 +1662135927538533632 +1662135927580534528 +1662135927622535424 +1662135927664536320 +1662135927709537280 +1662135927760538368 +1662135927802539264 +1662135927850540288 +1662135927892541184 +1662135927937542144 +1662135927988543232 +1662135928030544128 +1662135928075545088 +1662135928120546048 +1662135928162546944 +1662135928207547904 +1662135928255548928 +1662135928303549952 +1662135928345550848 +1662135928393551872 +1662135928435552768 +1662135928477553664 +1662135928519554560 +1662135928561555456 +1662135928603556352 +1662135928645557248 +1662135928687558144 +1662135928729559040 +1662135928774560000 +1662135928822561024 +1662135928864561920 +1662135928912562944 +1662135928954563840 +1662135929002564864 +1662135929041565696 +1662135929083566592 +1662135929125567488 +1662135929167568384 +1662135929212569344 +1662135929257570304 +1662135929299571200 +1662135929341572096 +1662135929386573056 +1662135929428573952 +1662135929467574784 +1662135929512575744 +1662135929566576896 +1662135929608577792 +1662135929659578880 +1662135929707579904 +1662135929749580800 +1662135929800581888 +1662135929842582784 +1662135929884583680 +1662135929926584576 +1662135929968585472 +1662135930010586368 +1662135930061587456 +1662135930103588352 +1662135930154589440 +1662135930199590400 +1662135930241591296 +1662135930283592192 +1662135930328593152 +1662135930367593984 +1662135930415595008 +1662135930460595968 +1662135930511597056 +1662135930553597952 +1662135930598598912 +1662135930640599808 +1662135930685600768 +1662135930730601728 +1662135930778602752 +1662135930820603648 +1662135930865604608 +1662135930907605504 +1662135930952606464 +1662135930997607424 +1662135931039608320 +1662135931081609216 +1662135931135610368 +1662135931180611328 +1662135931222612224 +1662135931270613248 +1662135931321614336 +1662135931372615424 +1662135931420616448 +1662135931465617408 +1662135931507618304 +1662135931549619200 +1662135931591620096 +1662135931639621120 +1662135931684622080 +1662135931726622976 +1662135931774624000 +1662135931819624960 +1662135931870626048 +1662135931912626944 +1662135931960627968 +1662135932002628864 +1662135932065630208 +1662135932107631104 +1662135932149632000 +1662135932209633280 +1662135932254634240 +1662135932299635200 +1662135932350636288 +1662135932392637184 +1662135932434638080 +1662135932482639104 +1662135932524640000 +1662135932566640896 +1662135932608641792 +1662135932650642688 +1662135932695643648 +1662135932743644672 +1662135932785645568 +1662135932830646528 +1662135932875647488 +1662135932917648384 +1662135932959649280 +1662135933004650240 +1662135933049651200 +1662135933091652096 +1662135933133652992 +1662135933178653952 +1662135933223654912 +1662135933268655872 +1662135933310656768 +1662135933358657792 +1662135933403658752 +1662135933454659840 +1662135933499660800 +1662135933541661696 +1662135933589662720 +1662135933631663616 +1662135933679664640 +1662135933718665472 +1662135933757666304 +1662135933802667264 +1662135933853668352 +1662135933898669312 +1662135933940670208 +1662135933979671040 +1662135934024672000 +1662135934066672896 +1662135934111673856 +1662135934156674816 +1662135934210675968 +1662135934255676928 +1662135934297677824 +1662135934345678848 +1662135934387679744 +1662135934429680640 +1662135934468681472 +1662135934513682432 +1662135934555683328 +1662135934600684288 +1662135934642685184 +1662135934684686080 +1662135934729687040 +1662135934771687936 +1662135934816688896 +1662135934858689792 +1662135934900690688 +1662135934942691584 +1662135934990692608 +1662135935032693504 +1662135935077694464 +1662135935119695360 +1662135935158696192 +1662135935209697280 +1662135935251698176 +1662135935293699072 +1662135935344700160 +1662135935389701120 +1662135935431702016 +1662135935482703104 +1662135935524704000 +1662135935572705024 +1662135935620706048 +1662135935668707072 +1662135935713708032 +1662135935758708992 +1662135935803709952 +1662135935845710848 +1662135935887711744 +1662135935932712704 +1662135935974713600 +1662135936019714560 +1662135936067715584 +1662135936106716416 +1662135936154717440 +1662135936196718336 +1662135936235719168 +1662135936277720064 +1662135936325721088 +1662135936367721984 +1662135936415723008 +1662135936457723904 +1662135936499724800 +1662135936544725760 +1662135936592726784 +1662135936631727616 +1662135936679728640 +1662135936727729664 +1662135936772730624 +1662135936814731520 +1662135936856732416 +1662135936907733504 +1662135936949734400 +1662135936997735424 +1662135937045736448 +1662135937093737472 +1662135937135738368 +1662135937180739328 +1662135937222740224 +1662135937267741184 +1662135937306742016 +1662135937351742976 +1662135937396743936 +1662135937435744768 +1662135937477745664 +1662135937522746624 +1662135937567747584 +1662135937609748480 +1662135937660749568 +1662135937705750528 +1662135937756751616 +1662135937804752640 +1662135937846753536 +1662135937903754752 +1662135937942755584 +1662135937984756480 +1662135938032757504 +1662135938071758336 +1662135938119759360 +1662135938161760256 +1662135938212761344 +1662135938254762240 +1662135938308763392 +1662135938350764288 +1662135938395765248 +1662135938452766464 +1662135938500767488 +1662135938539768320 +1662135938584769280 +1662135938629770240 +1662135938671771136 +1662135938716772096 +1662135938764773120 +1662135938815774208 +1662135938863775232 +1662135938905776128 +1662135938953777152 +1662135939001778176 +1662135939043779072 +1662135939094780160 +1662135939142781184 +1662135939187782144 +1662135939235783168 +1662135939274784000 +1662135939322785024 +1662135939367785984 +1662135939409786880 +1662135939460787968 +1662135939502788864 +1662135939541789696 +1662135939592790784 +1662135939637791744 +1662135939688792832 +1662135939736793856 +1662135939778794752 +1662135939820795648 +1662135939865796608 +1662135939919797760 +1662135939961798656 +1662135940006799616 +1662135940045800448 +1662135940093801472 +1662135940135802368 +1662135940180803328 +1662135940228804352 +1662135940282805504 +1662135940327806464 +1662135940372807424 +1662135940426808576 +1662135940468809472 +1662135940510810368 +1662135940552811264 +1662135940603812352 +1662135940642813184 +1662135940681814016 +1662135940723814912 +1662135940765815808 +1662135940807816704 +1662135940849817600 +1662135940888818432 +1662135940930819328 +1662135940978820352 +1662135941023821312 +1662135941065822208 +1662135941107823104 +1662135941149824000 +1662135941188824832 +1662135941233825792 +1662135941281826816 +1662135941323827712 +1662135941365828608 +1662135941413829632 +1662135941455830528 +1662135941500831488 +1662135941542832384 +1662135941581833216 +1662135941623834112 +1662135941665835008 +1662135941707835904 +1662135941746836736 +1662135941791837696 +1662135941833838592 +1662135941878839552 +1662135941929840640 +1662135941977841664 +1662135942025842688 +1662135942061843456 +1662135942103844352 +1662135942145845248 +1662135942199846400 +1662135942247847424 +1662135942292848384 +1662135942334849280 +1662135942388850432 +1662135942433851392 +1662135942478852352 +1662135942520853248 +1662135942562854144 +1662135942613855232 +1662135942658856192 +1662135942700857088 +1662135942751858176 +1662135942793859072 +1662135942835859968 +1662135942883860992 +1662135942925861888 +1662135942967862784 +1662135943006863616 +1662135943048864512 +1662135943093865472 +1662135943138866432 +1662135943186867456 +1662135943234868480 +1662135943276869376 +1662135943321870336 +1662135943369871360 +1662135943408872192 +1662135943456873216 +1662135943501874176 +1662135943543875072 +1662135943582875904 +1662135943627876864 +1662135943669877760 +1662135943720878848 +1662135943762879744 +1662135943804880640 +1662135943849881600 +1662135943894882560 +1662135943945883648 +1662135943996884736 +1662135944038885632 +1662135944083886592 +1662135944134887680 +1662135944182888704 +1662135944224889600 +1662135944275890688 +1662135944317891584 +1662135944362892544 +1662135944410893568 +1662135944452894464 +1662135944497895424 +1662135944551896576 +1662135944593897472 +1662135944635898368 +1662135944680899328 +1662135944731900416 +1662135944776901376 +1662135944824902400 +1662135944878903552 +1662135944923904512 +1662135944965905408 +1662135945010906368 +1662135945058907392 +1662135945100908288 +1662135945142909184 +1662135945190910208 +1662135945235911168 +1662135945289912320 +1662135945331913216 +1662135945376914176 +1662135945421915136 +1662135945466916096 +1662135945508916992 +1662135945550917888 +1662135945595918848 +1662135945634919680 +1662135945679920640 +1662135945727921664 +1662135945775922688 +1662135945817923584 +1662135945862924544 +1662135945904925440 +1662135945949926400 +1662135945991927296 +1662135946036928256 +1662135946081929216 +1662135946123930112 +1662135946165931008 +1662135946216932096 +1662135946261933056 +1662135946306934016 +1662135946351934976 +1662135946393935872 +1662135946438936832 +1662135946477937664 +1662135946519938560 +1662135946564939520 +1662135946609940480 +1662135946651941376 +1662135946690942208 +1662135946735943168 +1662135946783944192 +1662135946825945088 +1662135946867945984 +1662135946918947072 +1662135946963948032 +1662135947005948928 +1662135947047949824 +1662135947095950848 +1662135947134951680 +1662135947188952832 +1662135947236953856 +1662135947278954752 +1662135947320955648 +1662135947368956672 +1662135947410957568 +1662135947452958464 +1662135947494959360 +1662135947539960320 +1662135947578961152 +1662135947623962112 +1662135947665963008 +1662135947716964096 +1662135947758964992 +1662135947800965888 +1662135947842966784 +1662135947890967808 +1662135947941968896 +1662135947989969920 +1662135948031970816 +1662135948079971840 +1662135948121972736 +1662135948163973632 +1662135948211974656 +1662135948253975552 +1662135948292976384 +1662135948337977344 +1662135948382978304 +1662135948430979328 +1662135948472980224 +1662135948514981120 +1662135948553981952 +1662135948595982848 +1662135948637983744 +1662135948685984768 +1662135948730985728 +1662135948772986624 +1662135948814987520 +1662135948856988416 +1662135948895989248 +1662135948937990144 +1662135948982991104 +1662135949033992192 +1662135949078993152 +1662135949120994048 +1662135949174995200 +1662135949216996096 +1662135949261997056 +1662135949306998016 +1662135949348998912 +1662135949393999872 +1662135949439000832 +1662135949481001728 +1662135949529002752 +1662135949568003584 +1662135949616004608 +1662135949667005696 +1662135949709006592 +1662135949754007552 +1662135949796008448 +1662135949838009344 +1662135949886010368 +1662135949928011264 +1662135949970012160 +1662135950012013056 +1662135950057014016 +1662135950099014912 +1662135950144015872 +1662135950186016768 +1662135950240017920 +1662135950285018880 +1662135950327019776 +1662135950375020800 +1662135950417021696 +1662135950468022784 +1662135950510023680 +1662135950558024704 +1662135950600025600 +1662135950642026496 +1662135950690027520 +1662135950735028480 +1662135950777029376 +1662135950822030336 +1662135950870031360 +1662135950918032384 +1662135950960033280 +1662135951002034176 +1662135951047035136 +1662135951089036032 +1662135951146037248 +1662135951188038144 +1662135951230039040 +1662135951272039936 +1662135951317040896 +1662135951368041984 +1662135951413042944 +1662135951455043840 +1662135951494044672 +1662135951545045760 +1662135951587046656 +1662135951632047616 +1662135951674048512 +1662135951722049536 +1662135951770050560 +1662135951815051520 +1662135951860052480 +1662135951902053376 +1662135951944054272 +1662135951986055168 +1662135952028056064 +1662135952067056896 +1662135952112057856 +1662135952154058752 +1662135952196059648 +1662135952238060544 +1662135952280061440 +1662135952337062656 +1662135952379063552 +1662135952424064512 +1662135952466065408 +1662135952517066496 +1662135952559067392 +1662135952616068608 +1662135952661069568 +1662135952709070592 +1662135952763071744 +1662135952808072704 +1662135952850073600 +1662135952895074560 +1662135952937075456 +1662135952982076416 +1662135953033077504 +1662135953075078400 +1662135953117079296 +1662135953159080192 +1662135953201081088 +1662135953243081984 +1662135953291083008 +1662135953333083904 +1662135953384084992 +1662135953426085888 +1662135953471086848 +1662135953513087744 +1662135953555088640 +1662135953603089664 +1662135953651090688 +1662135953693091584 +1662135953741092608 +1662135953786093568 +1662135953828094464 +1662135953870095360 +1662135953912096256 +1662135953957097216 +1662135953999098112 +1662135954044099072 +1662135954092100096 +1662135954134100992 +1662135954176101888 +1662135954218102784 +1662135954260103680 +1662135954308104704 +1662135954353105664 +1662135954392106496 +1662135954431107328 +1662135954479108352 +1662135954518109184 +1662135954566110208 +1662135954611111168 +1662135954656112128 +1662135954704113152 +1662135954746114048 +1662135954791115008 +1662135954833115904 +1662135954878116864 +1662135954923117824 +1662135954965118720 +1662135955016119808 +1662135955058120704 +1662135955097121536 +1662135955136122368 +1662135955178123264 +1662135955217124096 +1662135955259124992 +1662135955304125952 +1662135955346126848 +1662135955391127808 +1662135955436128768 +1662135955487129856 +1662135955526130688 +1662135955568131584 +1662135955610132480 +1662135955655133440 +1662135955697134336 +1662135955739135232 +1662135955781136128 +1662135955826137088 +1662135955868137984 +1662135955913138944 +1662135955964140032 +1662135956009140992 +1662135956057142016 +1662135956105143040 +1662135956153144064 +1662135956195144960 +1662135956240145920 +1662135956288146944 +1662135956336147968 +1662135956381148928 +1662135956426149888 +1662135956468150784 +1662135956513151744 +1662135956555152640 +1662135956600153600 +1662135956648154624 +1662135956690155520 +1662135956732156416 +1662135956774157312 +1662135956828158464 +1662135956876159488 +1662135956921160448 +1662135956963161344 +1662135957008162304 +1662135957056163328 +1662135957104164352 +1662135957146165248 +1662135957188166144 +1662135957230167040 +1662135957266167808 +1662135957308168704 +1662135957350169600 +1662135957392170496 +1662135957437171456 +1662135957479172352 +1662135957521173248 +1662135957566174208 +1662135957608175104 +1662135957650176000 +1662135957695176960 +1662135957734177792 +1662135957785178880 +1662135957827179776 +1662135957869180672 +1662135957911181568 +1662135957956182528 +1662135958001183488 +1662135958046184448 +1662135958088185344 +1662135958130186240 +1662135958175187200 +1662135958226188288 +1662135958268189184 +1662135958310190080 +1662135958352190976 +1662135958394191872 +1662135958445192960 +1662135958487193856 +1662135958529194752 +1662135958565195520 +1662135958610196480 +1662135958652197376 +1662135958694198272 +1662135958739199232 +1662135958781200128 +1662135958826201088 +1662135958868201984 +1662135958910202880 +1662135958952203776 +1662135958994204672 +1662135959039205632 +1662135959084206592 +1662135959129207552 +1662135959174208512 +1662135959216209408 +1662135959261210368 +1662135959306211328 +1662135959351212288 +1662135959396213248 +1662135959438214144 +1662135959483215104 +1662135959531216128 +1662135959573217024 +1662135959615217920 +1662135959654218752 +1662135959696219648 +1662135959738220544 +1662135959780221440 +1662135959825222400 +1662135959870223360 +1662135959909224192 +1662135959951225088 +1662135959999226112 +1662135960041227008 +1662135960083227904 +1662135960125228800 +1662135960167229696 +1662135960218230784 +1662135960260231680 +1662135960299232512 +1662135960347233536 +1662135960392234496 +1662135960440235520 +1662135960485236480 +1662135960539237632 +1662135960584238592 +1662135960635239680 +1662135960680240640 +1662135960725241600 +1662135960776242688 +1662135960818243584 +1662135960863244544 +1662135960908245504 +1662135960950246400 +1662135961001247488 +1662135961043248384 +1662135961085249280 +1662135961127250176 +1662135961178251264 +1662135961220252160 +1662135961265253120 +1662135961307254016 +1662135961352254976 +1662135961400256000 +1662135961448257024 +1662135961490257920 +1662135961535258880 +1662135961580259840 +1662135961619260672 +1662135961658261504 +1662135961700262400 +1662135961742263296 +1662135961784264192 +1662135961826265088 +1662135961868265984 +1662135961907266816 +1662135961949267712 +1662135961991268608 +1662135962039269632 +1662135962081270528 +1662135962123271424 +1662135962165272320 +1662135962210273280 +1662135962252274176 +1662135962303275264 +1662135962345276160 +1662135962387277056 +1662135962432278016 +1662135962477278976 +1662135962528280064 +1662135962570280960 +1662135962615281920 +1662135962657282816 +1662135962699283712 +1662135962741284608 +1662135962792285696 +1662135962837286656 +1662135962882287616 +1662135962924288512 +1662135962972289536 +1662135963014290432 +1662135963065291520 +1662135963113292544 +1662135963164293632 +1662135963212294656 +1662135963254295552 +1662135963299296512 +1662135963341297408 +1662135963386298368 +1662135963425299200 +1662135963467300096 +1662135963512301056 +1662135963554301952 +1662135963596302848 +1662135963644303872 +1662135963686304768 +1662135963728305664 +1662135963773306624 +1662135963815307520 +1662135963857308416 +1662135963902309376 +1662135963947310336 +1662135963995311360 +1662135964040312320 +1662135964088313344 +1662135964139314432 +1662135964181315328 +1662135964223316224 +1662135964271317248 +1662135964313318144 +1662135964358319104 +1662135964406320128 +1662135964445320960 +1662135964487321856 +1662135964532322816 +1662135964574323712 +1662135964619324672 +1662135964667325696 +1662135964709326592 +1662135964754327552 +1662135964796328448 +1662135964835329280 +1662135964883330304 +1662135964928331264 +1662135964970332160 +1662135965012333056 +1662135965057334016 +1662135965108335104 +1662135965144335872 +1662135965186336768 +1662135965234337792 +1662135965276338688 +1662135965327339776 +1662135965369340672 +1662135965414341632 +1662135965459342592 +1662135965507343616 +1662135965549344512 +1662135965591345408 +1662135965633346304 +1662135965678347264 +1662135965720348160 +1662135965765349120 +1662135965810350080 +1662135965852350976 +1662135965894351872 +1662135965933352704 +1662135965972353536 +1662135966017354496 +1662135966065355520 +1662135966107356416 +1662135966152357376 +1662135966191358208 +1662135966239359232 +1662135966284360192 +1662135966329361152 +1662135966371362048 +1662135966419363072 +1662135966464364032 +1662135966512365056 +1662135966551365888 +1662135966596366848 +1662135966638367744 +1662135966680368640 +1662135966719369472 +1662135966761370368 +1662135966803371264 +1662135966848372224 +1662135966890373120 +1662135966932374016 +1662135966974374912 +1662135967025376000 +1662135967067376896 +1662135967115377920 +1662135967160378880 +1662135967202379776 +1662135967250380800 +1662135967295381760 +1662135967340382720 +1662135967382383616 +1662135967424384512 +1662135967466385408 +1662135967505386240 +1662135967550387200 +1662135967592388096 +1662135967646389248 +1662135967685390080 +1662135967733391104 +1662135967775392000 +1662135967817392896 +1662135967874394112 +1662135967919395072 +1662135967961395968 +1662135968012397056 +1662135968054397952 +1662135968096398848 +1662135968141399808 +1662135968186400768 +1662135968225401600 +1662135968264402432 +1662135968312403456 +1662135968360404480 +1662135968402405376 +1662135968447406336 +1662135968492407296 +1662135968534408192 +1662135968582409216 +1662135968624410112 +1662135968666411008 +1662135968708411904 +1662135968747412736 +1662135968789413632 +1662135968834414592 +1662135968879415552 +1662135968921416448 +1662135968963417344 +1662135969008418304 +1662135969050419200 +1662135969092420096 +1662135969137421056 +1662135969182422016 +1662135969227422976 +1662135969269423872 +1662135969311424768 +1662135969356425728 +1662135969404426752 +1662135969452427776 +1662135969497428736 +1662135969548429824 +1662135969596430848 +1662135969641431808 +1662135969695432960 +1662135969740433920 +1662135969779434752 +1662135969821435648 +1662135969863436544 +1662135969908437504 +1662135969953438464 +1662135970004439552 +1662135970043440384 +1662135970088441344 +1662135970130442240 +1662135970178443264 +1662135970223444224 +1662135970265445120 +1662135970307446016 +1662135970358447104 +1662135970400448000 +1662135970445448960 +1662135970487449856 +1662135970526450688 +1662135970565451520 +1662135970607452416 +1662135970649453312 +1662135970691454208 +1662135970736455168 +1662135970781456128 +1662135970829457152 +1662135970871458048 +1662135970913458944 +1662135970958459904 +1662135971006460928 +1662135971063462144 +1662135971105463040 +1662135971150464000 +1662135971198465024 +1662135971240465920 +1662135971285466880 +1662135971336467968 +1662135971381468928 +1662135971426469888 +1662135971468470784 +1662135971510471680 +1662135971552472576 +1662135971600473600 +1662135971642474496 +1662135971690475520 +1662135971741476608 +1662135971786477568 +1662135971831478528 +1662135971876479488 +1662135971918480384 +1662135971960481280 +1662135972014482432 +1662135972068483584 +1662135972116484608 +1662135972164485632 +1662135972209486592 +1662135972254487552 +1662135972296488448 +1662135972344489472 +1662135972395490560 +1662135972443491584 +1662135972488492544 +1662135972533493504 +1662135972575494400 +1662135972620495360 +1662135972662496256 +1662135972704497152 +1662135972749498112 +1662135972797499136 +1662135972842500096 +1662135972887501056 +1662135972926501888 +1662135972974502912 +1662135973016503808 +1662135973070504960 +1662135973115505920 +1662135973160506880 +1662135973205507840 +1662135973262509056 +1662135973304509952 +1662135973346510848 +1662135973391511808 +1662135973433512704 +1662135973472513536 +1662135973514514432 +1662135973556515328 +1662135973598516224 +1662135973649517312 +1662135973700518400 +1662135973748519424 +1662135973793520384 +1662135973835521280 +1662135973883522304 +1662135973928523264 +1662135973976524288 +1662135974018525184 +1662135974060526080 +1662135974108527104 +1662135974150528000 +1662135974192528896 +1662135974237529856 +1662135974282530816 +1662135974324531712 +1662135974369532672 +1662135974411533568 +1662135974456534528 +1662135974501535488 +1662135974543536384 +1662135974585537280 +1662135974627538176 +1662135974681539328 +1662135974729540352 +1662135974771541248 +1662135974813542144 +1662135974858543104 +1662135974906544128 +1662135974945544960 +1662135974987545856 +1662135975035546880 +1662135975083547904 +1662135975134548992 +1662135975176549888 +1662135975218550784 +1662135975263551744 +1662135975311552768 +1662135975359553792 +1662135975401554688 +1662135975452555776 +1662135975494556672 +1662135975542557696 +1662135975587558656 +1662135975632559616 +1662135975677560576 +1662135975725561600 +1662135975767562496 +1662135975818563584 +1662135975866564608 +1662135975908565504 +1662135975950566400 +1662135975995567360 +1662135976040568320 +1662135976085569280 +1662135976127570176 +1662135976169571072 +1662135976211571968 +1662135976256572928 +1662135976295573760 +1662135976340574720 +1662135976385575680 +1662135976430576640 +1662135976472577536 +1662135976520578560 +1662135976559579392 +1662135976607580416 +1662135976649581312 +1662135976697582336 +1662135976745583360 +1662135976787584256 +1662135976829585152 +1662135976871586048 +1662135976913586944 +1662135976955587840 +1662135977006588928 +1662135977048589824 +1662135977093590784 +1662135977138591744 +1662135977183592704 +1662135977228593664 +1662135977276594688 +1662135977318595584 +1662135977360596480 +1662135977405597440 +1662135977453598464 +1662135977495599360 +1662135977540600320 +1662135977582601216 +1662135977624602112 +1662135977681603328 +1662135977723604224 +1662135977765605120 +1662135977810606080 +1662135977858607104 +1662135977900608000 +1662135977945608960 +1662135977996610048 +1662135978041611008 +1662135978086611968 +1662135978131612928 +1662135978173613824 +1662135978212614656 +1662135978257615616 +1662135978299616512 +1662135978341617408 +1662135978383618304 +1662135978425619200 +1662135978470620160 +1662135978509620992 +1662135978563622144 +1662135978608623104 +1662135978650624000 +1662135978698625024 +1662135978737625856 +1662135978785626880 +1662135978824627712 +1662135978869628672 +1662135978911629568 +1662135978956630528 +1662135978998631424 +1662135979043632384 +1662135979091633408 +1662135979133634304 +1662135979175635200 +1662135979220636160 +1662135979262637056 +1662135979304637952 +1662135979346638848 +1662135979388639744 +1662135979439640832 +1662135979484641792 +1662135979529642752 +1662135979571643648 +1662135979613644544 +1662135979658645504 +1662135979700646400 +1662135979742647296 +1662135979784648192 +1662135979829649152 +1662135979877650176 +1662135979919651072 +1662135979964652032 +1662135980009652992 +1662135980054653952 +1662135980105655040 +1662135980147655936 +1662135980189656832 +1662135980234657792 +1662135980276658688 +1662135980318659584 +1662135980363660544 +1662135980408661504 +1662135980465662720 +1662135980507663616 +1662135980549664512 +1662135980606665728 +1662135980651666688 +1662135980696667648 +1662135980738668544 +1662135980780669440 +1662135980822670336 +1662135980867671296 +1662135980909672192 +1662135980954673152 +1662135980996674048 +1662135981041675008 +1662135981083675904 +1662135981131676928 +1662135981179677952 +1662135981221678848 +1662135981293680384 +1662135981335681280 +1662135981383682304 +1662135981425683200 +1662135981470684160 +1662135981515685120 +1662135981560686080 +1662135981608687104 +1662135981659688192 +1662135981701689088 +1662135981740689920 +1662135981782690816 +1662135981824691712 +1662135981869692672 +1662135981920693760 +1662135981965694720 +1662135982016695808 +1662135982058696704 +1662135982100697600 +1662135982142698496 +1662135982184699392 +1662135982226700288 +1662135982271701248 +1662135982319702272 +1662135982361703168 +1662135982400704000 +1662135982442704896 +1662135982490705920 +1662135982541707008 +1662135982583707904 +1662135982625708800 +1662135982667709696 +1662135982715710720 +1662135982757711616 +1662135982796712448 +1662135982841713408 +1662135982883714304 +1662135982922715136 +1662135982967716096 +1662135983009716992 +1662135983048717824 +1662135983093718784 +1662135983135719680 +1662135983183720704 +1662135983228721664 +1662135983270722560 +1662135983321723648 +1662135983366724608 +1662135983408725504 +1662135983456726528 +1662135983501727488 +1662135983549728512 +1662135983594729472 +1662135983642730496 +1662135983687731456 +1662135983729732352 +1662135983771733248 +1662135983819734272 +1662135983864735232 +1662135983909736192 +1662135983954737152 +1662135983999738112 +1662135984041739008 +1662135984083739904 +1662135984125740800 +1662135984179741952 +1662135984224742912 +1662135984269743872 +1662135984317744896 +1662135984362745856 +1662135984404746752 +1662135984446747648 +1662135984491748608 +1662135984533749504 +1662135984572750336 +1662135984614751232 +1662135984656752128 +1662135984701753088 +1662135984743753984 +1662135984782754816 +1662135984833755904 +1662135984884756992 +1662135984929757952 +1662135984980759040 +1662135985031760128 +1662135985076761088 +1662135985115761920 +1662135985166763008 +1662135985217764096 +1662135985265765120 +1662135985304765952 +1662135985346766848 +1662135985388767744 +1662135985427768576 +1662135985469769472 +1662135985508770304 +1662135985547771136 +1662135985589772032 +1662135985634772992 +1662135985676773888 +1662135985721774848 +1662135985769775872 +1662135985817776896 +1662135985865777920 +1662135985907778816 +1662135985955779840 +1662135986003780864 +1662135986051781888 +1662135986096782848 +1662135986141783808 +1662135986186784768 +1662135986234785792 +1662135986279786752 +1662135986321787648 +1662135986363788544 +1662135986414789632 +1662135986462790656 +1662135986501791488 +1662135986546792448 +1662135986591793408 +1662135986636794368 +1662135986687795456 +1662135986729796352 +1662135986780797440 +1662135986828798464 +1662135986876799488 +1662135986918800384 +1662135986963801344 +1662135987014802432 +1662135987059803392 +1662135987107804416 +1662135987152805376 +1662135987197806336 +1662135987245807360 +1662135987290808320 +1662135987332809216 +1662135987374810112 +1662135987416811008 +1662135987461811968 +1662135987500812800 +1662135987542813696 +1662135987584814592 +1662135987632815616 +1662135987674816512 +1662135987716817408 +1662135987758818304 +1662135987803819264 +1662135987845820160 +1662135987890821120 +1662135987935822080 +1662135987980823040 +1662135988022823936 +1662135988067824896 +1662135988112825856 +1662135988154826752 +1662135988196827648 +1662135988235828480 +1662135988277829376 +1662135988319830272 +1662135988361831168 +1662135988406832128 +1662135988448833024 +1662135988493833984 +1662135988535834880 +1662135988583835904 +1662135988625836800 +1662135988670837760 +1662135988715838720 +1662135988760839680 +1662135988799840512 +1662135988838841344 +1662135988880842240 +1662135988919843072 +1662135988961843968 +1662135989003844864 +1662135989042845696 +1662135989084846592 +1662135989129847552 +1662135989171848448 +1662135989210849280 +1662135989258850304 +1662135989300851200 +1662135989342852096 +1662135989384852992 +1662135989429853952 +1662135989468854784 +1662135989510855680 +1662135989552856576 +1662135989594857472 +1662135989639858432 +1662135989681859328 +1662135989723860224 +1662135989765861120 +1662135989807862016 +1662135989852862976 +1662135989897863936 +1662135989942864896 +1662135989984865792 +1662135990029866752 +1662135990065867520 +1662135990113868544 +1662135990161869568 +1662135990203870464 +1662135990245871360 +1662135990287872256 +1662135990329873152 +1662135990374874112 +1662135990422875136 +1662135990464876032 +1662135990509876992 +1662135990551877888 +1662135990605879040 +1662135990650880000 +1662135990695880960 +1662135990743881984 +1662135990785882880 +1662135990836883968 +1662135990884884992 +1662135990935886080 +1662135990980887040 +1662135991025888000 +1662135991067888896 +1662135991109889792 +1662135991151890688 +1662135991199891712 +1662135991238892544 +1662135991283893504 +1662135991328894464 +1662135991370895360 +1662135991415896320 +1662135991457897216 +1662135991502898176 +1662135991544899072 +1662135991586899968 +1662135991628900864 +1662135991670901760 +1662135991712902656 +1662135991760903680 +1662135991802904576 +1662135991844905472 +1662135991889906432 +1662135991931907328 +1662135991979908352 +1662135992021909248 +1662135992075910400 +1662135992114911232 +1662135992156912128 +1662135992195912960 +1662135992240913920 +1662135992282914816 +1662135992330915840 +1662135992378916864 +1662135992417917696 +1662135992462918656 +1662135992510919680 +1662135992552920576 +1662135992603921664 +1662135992645922560 +1662135992687923456 +1662135992729924352 +1662135992771925248 +1662135992813926144 +1662135992855927040 +1662135992909928192 +1662135992951929088 +1662135992990929920 +1662135993032930816 +1662135993083931904 +1662135993128932864 +1662135993182934016 +1662135993224934912 +1662135993281936128 +1662135993329937152 +1662135993371938048 +1662135993413938944 +1662135993458939904 +1662135993503940864 +1662135993545941760 +1662135993590942720 +1662135993632943616 +1662135993677944576 +1662135993722945536 +1662135993761946368 +1662135993806947328 +1662135993851948288 +1662135993893949184 +1662135993935950080 +1662135993980951040 +1662135994025952000 +1662135994070952960 +1662135994112953856 +1662135994157954816 +1662135994202955776 +1662135994253956864 +1662135994298957824 +1662135994340958720 +1662135994382959616 +1662135994427960576 +1662135994469961472 +1662135994514962432 +1662135994565963520 +1662135994610964480 +1662135994655965440 +1662135994694966272 +1662135994739967232 +1662135994781968128 +1662135994838969344 +1662135994883970304 +1662135994931971328 +1662135994976972288 +1662135995018973184 +1662135995060974080 +1662135995111975168 +1662135995156976128 +1662135995201977088 +1662135995243977984 +1662135995291979008 +1662135995333979904 +1662135995381980928 +1662135995429981952 +1662135995480983040 +1662135995525984000 +1662135995573985024 +1662135995615985920 +1662135995672987136 +1662135995717988096 +1662135995777989376 +1662135995822990336 +1662135995864991232 +1662135995918992384 +1662135995960993280 +1662135995999994112 +1662135996044995072 +1662135996086995968 +1662135996128996864 +1662135996179997952 +1662135996224998912 +1662135996266999808 +1662135996315000832 +1662135996357001728 +1662135996402002688 +1662135996444003584 +1662135996489004544 +1662135996528005376 +1662135996579006464 +1662135996621007360 +1662135996666008320 +1662135996705009152 +1662135996747010048 +1662135996789010944 +1662135996837011968 +1662135996888013056 +1662135996939014144 +1662135996990015232 +1662135997038016256 +1662135997086017280 +1662135997128018176 +1662135997176019200 +1662135997218020096 +1662135997260020992 +1662135997305021952 +1662135997350022912 +1662135997398023936 +1662135997437024768 +1662135997479025664 +1662135997521026560 +1662135997572027648 +1662135997620028672 +1662135997659029504 +1662135997710030592 +1662135997752031488 +1662135997794032384 +1662135997836033280 +1662135997878034176 +1662135997920035072 +1662135997965036032 +1662135998007036928 +1662135998052037888 +1662135998097038848 +1662135998139039744 +1662135998184040704 +1662135998226041600 +1662135998271042560 +1662135998316043520 +1662135998361044480 +1662135998412045568 +1662135998457046528 +1662135998499047424 +1662135998550048512 +1662135998595049472 +1662135998640050432 +1662135998682051328 +1662135998727052288 +1662135998772053248 +1662135998820054272 +1662135998865055232 +1662135998907056128 +1662135998949057024 +1662135998997058048 +1662135999039058944 +1662135999081059840 +1662135999123060736 +1662135999168061696 +1662135999216062720 +1662135999264063744 +1662135999309064704 +1662135999360065792 +1662135999402066688 +1662135999447067648 +1662135999489068544 +1662135999528069376 +1662135999579070464 +1662135999630071552 +1662135999678072576 +1662135999720073472 +1662135999759074304 +1662135999804075264 +1662135999846076160 +1662135999894077184 +1662135999939078144 +1662135999981079040 +1662136000029080064 +1662136000077081088 +1662136000125082112 +1662136000173083136 +1662136000215084032 +1662136000257084928 +1662136000299085824 +1662136000341086720 +1662136000383087616 +1662136000425088512 +1662136000473089536 +1662136000518090496 +1662136000557091328 +1662136000605092352 +1662136000650093312 +1662136000701094400 +1662136000740095232 +1662136000782096128 +1662136000827097088 +1662136000869097984 +1662136000911098880 +1662136000953099776 +1662136000992100608 +1662136001034101504 +1662136001088102656 +1662136001130103552 +1662136001172104448 +1662136001217105408 +1662136001256106240 +1662136001307107328 +1662136001352108288 +1662136001400109312 +1662136001442110208 +1662136001490111232 +1662136001535112192 +1662136001580113152 +1662136001622114048 +1662136001670115072 +1662136001709115904 +1662136001751116800 +1662136001796117760 +1662136001841118720 +1662136001895119872 +1662136001946120960 +1662136001991121920 +1662136002042123008 +1662136002084123904 +1662136002132124928 +1662136002180125952 +1662136002222126848 +1662136002267127808 +1662136002306128640 +1662136002348129536 +1662136002396130560 +1662136002441131520 +1662136002495132672 +1662136002540133632 +1662136002585134592 +1662136002633135616 +1662136002678136576 +1662136002723137536 +1662136002768138496 +1662136002813139456 +1662136002852140288 +1662136002894141184 +1662136002939142144 +1662136002990143232 +1662136003041144320 +1662136003083145216 +1662136003128146176 +1662136003179147264 +1662136003239148544 +1662136003284149504 +1662136003323150336 +1662136003371151360 +1662136003416152320 +1662136003458153216 +1662136003503154176 +1662136003545155072 +1662136003590156032 +1662136003638157056 +1662136003680157952 +1662136003722158848 +1662136003761159680 +1662136003803160576 +1662136003848161536 +1662136003899162624 +1662136003941163520 +1662136003992164608 +1662136004034165504 +1662136004088166656 +1662136004139167744 +1662136004184168704 +1662136004229169664 +1662136004268170496 +1662136004313171456 +1662136004352172288 +1662136004400173312 +1662136004439174144 +1662136004484175104 +1662136004529176064 +1662136004571176960 +1662136004619177984 +1662136004658178816 +1662136004703179776 +1662136004748180736 +1662136004793181696 +1662136004835182592 +1662136004880183552 +1662136004928184576 +1662136004985185792 +1662136005030186752 +1662136005072187648 +1662136005120188672 +1662136005168189696 +1662136005213190656 +1662136005255191552 +1662136005297192448 +1662136005339193344 +1662136005381194240 +1662136005426195200 +1662136005465196032 +1662136005507196928 +1662136005552197888 +1662136005594198784 +1662136005639199744 +1662136005681200640 +1662136005729201664 +1662136005774202624 +1662136005816203520 +1662136005861204480 +1662136005903205376 +1662136005945206272 +1662136005984207104 +1662136006029208064 +1662136006080209152 +1662136006131210240 +1662136006185211392 +1662136006230212352 +1662136006272213248 +1662136006317214208 +1662136006359215104 +1662136006401216000 +1662136006452217088 +1662136006494217984 +1662136006539218944 +1662136006581219840 +1662136006632220928 +1662136006668221696 +1662136006713222656 +1662136006755223552 +1662136006800224512 +1662136006845225472 +1662136006887226368 +1662136006929227264 +1662136006971228160 +1662136007016229120 +1662136007067230208 +1662136007118231296 +1662136007160232192 +1662136007202233088 +1662136007244233984 +1662136007286234880 +1662136007328235776 +1662136007373236736 +1662136007421237760 +1662136007466238720 +1662136007517239808 +1662136007562240768 +1662136007604241664 +1662136007652242688 +1662136007697243648 +1662136007739244544 +1662136007781245440 +1662136007826246400 +1662136007868247296 +1662136007910248192 +1662136007952249088 +1662136008000250112 +1662136008042251008 +1662136008084251904 +1662136008126252800 +1662136008174253824 +1662136008216254720 +1662136008261255680 +1662136008303256576 +1662136008342257408 +1662136008384258304 +1662136008426259200 +1662136008468260096 +1662136008513261056 +1662136008561262080 +1662136008603262976 +1662136008648263936 +1662136008696264960 +1662136008741265920 +1662136008783266816 +1662136008831267840 +1662136008873268736 +1662136008918269696 +1662136008960270592 +1662136008999271424 +1662136009041272320 +1662136009089273344 +1662136009140274432 +1662136009182275328 +1662136009224276224 +1662136009266277120 +1662136009311278080 +1662136009356279040 +1662136009395279872 +1662136009440280832 +1662136009482281728 +1662136009527282688 +1662136009578283776 +1662136009617284608 +1662136009662285568 +1662136009704286464 +1662136009752287488 +1662136009797288448 +1662136009842289408 +1662136009884290304 +1662136009926291200 +1662136009974292224 +1662136010016293120 +1662136010061294080 +1662136010109295104 +1662136010154296064 +1662136010196296960 +1662136010235297792 +1662136010280298752 +1662136010322299648 +1662136010364300544 +1662136010409301504 +1662136010451302400 +1662136010499303424 +1662136010547304448 +1662136010592305408 +1662136010637306368 +1662136010676307200 +1662136010718308096 +1662136010760308992 +1662136010808310016 +1662136010850310912 +1662136010892311808 +1662136010934312704 +1662136010982313728 +1662136011027314688 +1662136011072315648 +1662136011114316544 +1662136011159317504 +1662136011201318400 +1662136011243319296 +1662136011285320192 +1662136011327321088 +1662136011372322048 +1662136011420323072 +1662136011462323968 +1662136011507324928 +1662136011549325824 +1662136011591326720 +1662136011633327616 +1662136011687328768 +1662136011732329728 +1662136011780330752 +1662136011822331648 +1662136011870332672 +1662136011918333696 +1662136011960334592 +1662136012002335488 +1662136012047336448 +1662136012092337408 +1662136012134338304 +1662136012176339200 +1662136012218340096 +1662136012260340992 +1662136012302341888 +1662136012350342912 +1662136012395343872 +1662136012437344768 +1662136012482345728 +1662136012527346688 +1662136012575347712 +1662136012614348544 +1662136012656349440 +1662136012701350400 +1662136012740351232 +1662136012782352128 +1662136012824353024 +1662136012866353920 +1662136012914354944 +1662136012959355904 +1662136013004356864 +1662136013046357760 +1662136013091358720 +1662136013136359680 +1662136013178360576 +1662136013223361536 +1662136013262362368 +1662136013307363328 +1662136013352364288 +1662136013394365184 +1662136013436366080 +1662136013481367040 +1662136013523367936 +1662136013565368832 +1662136013607369728 +1662136013652370688 +1662136013694371584 +1662136013736372480 +1662136013790373632 +1662136013832374528 +1662136013874375424 +1662136013916376320 +1662136013961377280 +1662136014006378240 +1662136014051379200 +1662136014096380160 +1662136014144381184 +1662136014189382144 +1662136014231383040 +1662136014276384000 +1662136014321384960 +1662136014369385984 +1662136014411386880 +1662136014453387776 +1662136014501388800 +1662136014543389696 +1662136014591390720 +1662136014630391552 +1662136014672392448 +1662136014717393408 +1662136014765394432 +1662136014807395328 +1662136014858396416 +1662136014903397376 +1662136014948398336 +1662136014996399360 +1662136015041400320 +1662136015086401280 +1662136015128402176 +1662136015170403072 +1662136015218404096 +1662136015263405056 +1662136015305405952 +1662136015347406848 +1662136015404408064 +1662136015449409024 +1662136015500410112 +1662136015545411072 +1662136015584411904 +1662136015629412864 +1662136015671413760 +1662136015716414720 +1662136015761415680 +1662136015806416640 +1662136015848417536 +1662136015893418496 +1662136015938419456 +1662136015986420480 +1662136016028421376 +1662136016076422400 +1662136016121423360 +1662136016163424256 +1662136016208425216 +1662136016253426176 +1662136016295427072 +1662136016340428032 +1662136016382428928 +1662136016427429888 +1662136016484431104 +1662136016529432064 +1662136016574433024 +1662136016625434112 +1662136016667435008 +1662136016715436032 +1662136016760436992 +1662136016808438016 +1662136016850438912 +1662136016892439808 +1662136016937440768 +1662136016985441792 +1662136017027442688 +1662136017075443712 +1662136017129444864 +1662136017174445824 +1662136017222446848 +1662136017264447744 +1662136017309448704 +1662136017351449600 +1662136017402450688 +1662136017441451520 +1662136017486452480 +1662136017534453504 +1662136017579454464 +1662136017624455424 +1662136017663456256 +1662136017708457216 +1662136017750458112 +1662136017792459008 +1662136017843460096 +1662136017882460928 +1662136017924461824 +1662136017966462720 +1662136018011463680 +1662136018056464640 +1662136018107465728 +1662136018152466688 +1662136018200467712 +1662136018248468736 +1662136018290469632 +1662136018332470528 +1662136018377471488 +1662136018425472512 +1662136018467473408 +1662136018509474304 +1662136018557475328 +1662136018605476352 +1662136018647477248 +1662136018689478144 +1662136018737479168 +1662136018791480320 +1662136018833481216 +1662136018878482176 +1662136018920483072 +1662136018962483968 +1662136019010484992 +1662136019052485888 +1662136019097486848 +1662136019136487680 +1662136019190488832 +1662136019232489728 diff --git a/Examples/Monocular-Inertial/MIMIR_TimeStamps/OceanFloor_track1_light.txt b/Examples/Monocular-Inertial/MIMIR_TimeStamps/OceanFloor_track1_light.txt new file mode 100644 index 0000000000..fc436ed12e --- /dev/null +++ b/Examples/Monocular-Inertial/MIMIR_TimeStamps/OceanFloor_track1_light.txt @@ -0,0 +1,6263 @@ +1662129779504666880 +1662129779546667776 +1662129779588668672 +1662129779630669568 +1662129779675670528 +1662129779717671424 +1662129779762672384 +1662129779804673280 +1662129779849674240 +1662129779894675200 +1662129779936676096 +1662129779984677120 +1662129780026678016 +1662129780068678912 +1662129780110679808 +1662129780152680704 +1662129780194681600 +1662129780236682496 +1662129780278683392 +1662129780326684416 +1662129780368685312 +1662129780413686272 +1662129780455687168 +1662129780506688256 +1662129780548689152 +1662129780596690176 +1662129780641691136 +1662129780683692032 +1662129780728692992 +1662129780773693952 +1662129780815694848 +1662129780857695744 +1662129780911696896 +1662129780956697856 +1662129781001698816 +1662129781052699904 +1662129781097700864 +1662129781139701760 +1662129781181702656 +1662129781223703552 +1662129781268704512 +1662129781310705408 +1662129781358706432 +1662129781400707328 +1662129781442708224 +1662129781490709248 +1662129781532710144 +1662129781574711040 +1662129781616711936 +1662129781661712896 +1662129781703713792 +1662129781751714816 +1662129781796715776 +1662129781838716672 +1662129781883717632 +1662129781922718464 +1662129781970719488 +1662129782012720384 +1662129782054721280 +1662129782099722240 +1662129782141723136 +1662129782192724224 +1662129782234725120 +1662129782279726080 +1662129782324727040 +1662129782378728192 +1662129782423729152 +1662129782471730176 +1662129782513731072 +1662129782558732032 +1662129782600732928 +1662129782642733824 +1662129782687734784 +1662129782729735680 +1662129782777736704 +1662129782834737920 +1662129782876738816 +1662129782918739712 +1662129782966740736 +1662129783008741632 +1662129783053742592 +1662129783101743616 +1662129783143744512 +1662129783188745472 +1662129783233746432 +1662129783275747328 +1662129783323748352 +1662129783371749376 +1662129783410750208 +1662129783452751104 +1662129783497752064 +1662129783539752960 +1662129783584753920 +1662129783626754816 +1662129783668755712 +1662129783713756672 +1662129783761757696 +1662129783803758592 +1662129783845759488 +1662129783887760384 +1662129783932761344 +1662129783977762304 +1662129784019763200 +1662129784064764160 +1662129784106765056 +1662129784154766080 +1662129784199767040 +1662129784241767936 +1662129784292769024 +1662129784334769920 +1662129784382770944 +1662129784430771968 +1662129784472772864 +1662129784514773760 +1662129784562774784 +1662129784613775872 +1662129784655776768 +1662129784706777856 +1662129784751778816 +1662129784793779712 +1662129784838780672 +1662129784883781632 +1662129784931782656 +1662129784976783616 +1662129785018784512 +1662129785063785472 +1662129785111786496 +1662129785162787584 +1662129785210788608 +1662129785255789568 +1662129785300790528 +1662129785342791424 +1662129785387792384 +1662129785432793344 +1662129785483794432 +1662129785528795392 +1662129785576796416 +1662129785621797376 +1662129785666798336 +1662129785717799424 +1662129785762800384 +1662129785810801408 +1662129785852802304 +1662129785894803200 +1662129785936804096 +1662129785978804992 +1662129786026806016 +1662129786068806912 +1662129786113807872 +1662129786161808896 +1662129786209809920 +1662129786251810816 +1662129786296811776 +1662129786341812736 +1662129786386813696 +1662129786437814784 +1662129786485815808 +1662129786530816768 +1662129786584817920 +1662129786629818880 +1662129786671819776 +1662129786719820800 +1662129786761821696 +1662129786803822592 +1662129786845823488 +1662129786890824448 +1662129786929825280 +1662129786977826304 +1662129787025827328 +1662129787070828288 +1662129787115829248 +1662129787157830144 +1662129787205831168 +1662129787250832128 +1662129787295833088 +1662129787340834048 +1662129787388835072 +1662129787436836096 +1662129787481837056 +1662129787529838080 +1662129787574839040 +1662129787619840000 +1662129787658840832 +1662129787703841792 +1662129787748842752 +1662129787793843712 +1662129787841844736 +1662129787886845696 +1662129787931846656 +1662129787976847616 +1662129788021848576 +1662129788069849600 +1662129788111850496 +1662129788159851520 +1662129788201852416 +1662129788243853312 +1662129788288854272 +1662129788342855424 +1662129788390856448 +1662129788432857344 +1662129788480858368 +1662129788522859264 +1662129788567860224 +1662129788615861248 +1662129788660862208 +1662129788705863168 +1662129788747864064 +1662129788786864896 +1662129788831865856 +1662129788885867008 +1662129788933868032 +1662129788972868864 +1662129789020869888 +1662129789068870912 +1662129789110871808 +1662129789152872704 +1662129789197873664 +1662129789239874560 +1662129789287875584 +1662129789335876608 +1662129789377877504 +1662129789425878528 +1662129789467879424 +1662129789512880384 +1662129789563881472 +1662129789605882368 +1662129789647883264 +1662129789692884224 +1662129789737885184 +1662129789779886080 +1662129789821886976 +1662129789863887872 +1662129789908888832 +1662129789956889856 +1662129790001890816 +1662129790046891776 +1662129790085892608 +1662129790130893568 +1662129790175894528 +1662129790217895424 +1662129790259896320 +1662129790304897280 +1662129790352898304 +1662129790397899264 +1662129790442900224 +1662129790484901120 +1662129790526902016 +1662129790568902912 +1662129790610903808 +1662129790649904640 +1662129790691905536 +1662129790733906432 +1662129790775907328 +1662129790820908288 +1662129790862909184 +1662129790910910208 +1662129790949911040 +1662129790994912000 +1662129791033912832 +1662129791075913728 +1662129791120914688 +1662129791162915584 +1662129791207916544 +1662129791252917504 +1662129791294918400 +1662129791336919296 +1662129791378920192 +1662129791420921088 +1662129791465922048 +1662129791504922880 +1662129791549923840 +1662129791594924800 +1662129791636925696 +1662129791678926592 +1662129791720927488 +1662129791762928384 +1662129791804929280 +1662129791843930112 +1662129791888931072 +1662129791936932096 +1662129791981933056 +1662129792029934080 +1662129792077935104 +1662129792119936000 +1662129792155936768 +1662129792197937664 +1662129792245938688 +1662129792287939584 +1662129792338940672 +1662129792380941568 +1662129792425942528 +1662129792470943488 +1662129792512944384 +1662129792557945344 +1662129792599946240 +1662129792644947200 +1662129792683948032 +1662129792728948992 +1662129792773949952 +1662129792821950976 +1662129792866951936 +1662129792908952832 +1662129792959953920 +1662129793004954880 +1662129793049955840 +1662129793088956672 +1662129793133957632 +1662129793181958656 +1662129793223959552 +1662129793265960448 +1662129793313961472 +1662129793358962432 +1662129793409963520 +1662129793451964416 +1662129793496965376 +1662129793544966400 +1662129793586967296 +1662129793628968192 +1662129793670969088 +1662129793712969984 +1662129793754970880 +1662129793796971776 +1662129793841972736 +1662129793895973888 +1662129793937974784 +1662129793979975680 +1662129794027976704 +1662129794075977728 +1662129794117978624 +1662129794162979584 +1662129794207980544 +1662129794249981440 +1662129794291982336 +1662129794333983232 +1662129794375984128 +1662129794417985024 +1662129794459985920 +1662129794513987072 +1662129794555987968 +1662129794597988864 +1662129794639989760 +1662129794684990720 +1662129794732991744 +1662129794777992704 +1662129794822993664 +1662129794873994752 +1662129794915995648 +1662129794957996544 +1662129795002997504 +1662129795044998400 +1662129795083999232 +1662129795135000320 +1662129795177001216 +1662129795225002240 +1662129795267003136 +1662129795315004160 +1662129795366005248 +1662129795408006144 +1662129795456007168 +1662129795501008128 +1662129795543009024 +1662129795585009920 +1662129795624010752 +1662129795672011776 +1662129795717012736 +1662129795762013696 +1662129795804014592 +1662129795855015680 +1662129795903016704 +1662129795957017856 +1662129796008018944 +1662129796050019840 +1662129796098020864 +1662129796146021888 +1662129796191022848 +1662129796239023872 +1662129796284024832 +1662129796335025920 +1662129796380026880 +1662129796428027904 +1662129796470028800 +1662129796512029696 +1662129796557030656 +1662129796599031552 +1662129796641032448 +1662129796683033344 +1662129796725034240 +1662129796767035136 +1662129796812036096 +1662129796851036928 +1662129796896037888 +1662129796941038848 +1662129796992039936 +1662129797034040832 +1662129797076041728 +1662129797118042624 +1662129797163043584 +1662129797208044544 +1662129797253045504 +1662129797295046400 +1662129797337047296 +1662129797388048384 +1662129797430049280 +1662129797475050240 +1662129797526051328 +1662129797580052480 +1662129797628053504 +1662129797679054592 +1662129797718055424 +1662129797766056448 +1662129797814057472 +1662129797862058496 +1662129797907059456 +1662129797949060352 +1662129797991061248 +1662129798033062144 +1662129798075063040 +1662129798117063936 +1662129798162064896 +1662129798204065792 +1662129798246066688 +1662129798288067584 +1662129798333068544 +1662129798372069376 +1662129798420070400 +1662129798462071296 +1662129798504072192 +1662129798561073408 +1662129798609074432 +1662129798651075328 +1662129798690076160 +1662129798735077120 +1662129798777078016 +1662129798819078912 +1662129798870080000 +1662129798921081088 +1662129798966082048 +1662129799008082944 +1662129799053083904 +1662129799098084864 +1662129799140085760 +1662129799182086656 +1662129799230087680 +1662129799284088832 +1662129799329089792 +1662129799371090688 +1662129799428091904 +1662129799473092864 +1662129799515093760 +1662129799560094720 +1662129799605095680 +1662129799650096640 +1662129799692097536 +1662129799734098432 +1662129799776099328 +1662129799818100224 +1662129799863101184 +1662129799911102208 +1662129799956103168 +1662129800004104192 +1662129800046105088 +1662129800088105984 +1662129800133106944 +1662129800175107840 +1662129800223108864 +1662129800268109824 +1662129800319110912 +1662129800358111744 +1662129800400112640 +1662129800442113536 +1662129800493114624 +1662129800541115648 +1662129800589116672 +1662129800631117568 +1662129800676118528 +1662129800718119424 +1662129800772120576 +1662129800820121600 +1662129800862122496 +1662129800910123520 +1662129800955124480 +1662129801000125440 +1662129801048126464 +1662129801090127360 +1662129801150128640 +1662129801192129536 +1662129801234130432 +1662129801276131328 +1662129801321132288 +1662129801363133184 +1662129801405134080 +1662129801447134976 +1662129801495136000 +1662129801543137024 +1662129801588137984 +1662129801636139008 +1662129801681139968 +1662129801723140864 +1662129801765141760 +1662129801807142656 +1662129801855143680 +1662129801900144640 +1662129801948145664 +1662129801993146624 +1662129802044147712 +1662129802083148544 +1662129802131149568 +1662129802176150528 +1662129802224151552 +1662129802272152576 +1662129802311153408 +1662129802353154304 +1662129802398155264 +1662129802443156224 +1662129802488157184 +1662129802533158144 +1662129802584159232 +1662129802635160320 +1662129802677161216 +1662129802728162304 +1662129802773163264 +1662129802818164224 +1662129802860165120 +1662129802911166208 +1662129802950167040 +1662129802992167936 +1662129803040168960 +1662129803085169920 +1662129803136171008 +1662129803178171904 +1662129803220172800 +1662129803274173952 +1662129803316174848 +1662129803364175872 +1662129803415176960 +1662129803460177920 +1662129803499178752 +1662129803547179776 +1662129803592180736 +1662129803634181632 +1662129803676182528 +1662129803721183488 +1662129803760184320 +1662129803814185472 +1662129803856186368 +1662129803898187264 +1662129803943188224 +1662129803997189376 +1662129804039190272 +1662129804084191232 +1662129804126192128 +1662129804171193088 +1662129804216194048 +1662129804258194944 +1662129804312196096 +1662129804354196992 +1662129804402198016 +1662129804444198912 +1662129804495200000 +1662129804540200960 +1662129804582201856 +1662129804636203008 +1662129804678203904 +1662129804726204928 +1662129804768205824 +1662129804813206784 +1662129804855207680 +1662129804900208640 +1662129804951209728 +1662129804996210688 +1662129805041211648 +1662129805089212672 +1662129805140213760 +1662129805182214656 +1662129805227215616 +1662129805272216576 +1662129805314217472 +1662129805356218368 +1662129805398219264 +1662129805449220352 +1662129805494221312 +1662129805533222144 +1662129805575223040 +1662129805620224000 +1662129805662224896 +1662129805707225856 +1662129805764227072 +1662129805803227904 +1662129805842228736 +1662129805893229824 +1662129805938230784 +1662129805989231872 +1662129806031232768 +1662129806076233728 +1662129806124234752 +1662129806166235648 +1662129806205236480 +1662129806256237568 +1662129806295238400 +1662129806337239296 +1662129806379240192 +1662129806433241344 +1662129806475242240 +1662129806520243200 +1662129806565244160 +1662129806610245120 +1662129806652246016 +1662129806691246848 +1662129806736247808 +1662129806787248896 +1662129806826249728 +1662129806871250688 +1662129806916251648 +1662129806970252800 +1662129807012253696 +1662129807054254592 +1662129807096255488 +1662129807144256512 +1662129807189257472 +1662129807234258432 +1662129807282259456 +1662129807336260608 +1662129807378261504 +1662129807432262656 +1662129807480263680 +1662129807528264704 +1662129807576265728 +1662129807618266624 +1662129807657267456 +1662129807702268416 +1662129807753269504 +1662129807798270464 +1662129807840271360 +1662129807885272320 +1662129807927273216 +1662129807978274304 +1662129808017275136 +1662129808059276032 +1662129808104276992 +1662129808146277888 +1662129808197278976 +1662129808239279872 +1662129808278280704 +1662129808323281664 +1662129808374282752 +1662129808419283712 +1662129808470284800 +1662129808515285760 +1662129808557286656 +1662129808602287616 +1662129808644288512 +1662129808689289472 +1662129808734290432 +1662129808779291392 +1662129808824292352 +1662129808878293504 +1662129808920294400 +1662129808965295360 +1662129809007296256 +1662129809052297216 +1662129809094298112 +1662129809142299136 +1662129809190300160 +1662129809232301056 +1662129809277302016 +1662129809322302976 +1662129809367303936 +1662129809418305024 +1662129809460305920 +1662129809508306944 +1662129809553307904 +1662129809598308864 +1662129809646309888 +1662129809688310784 +1662129809733311744 +1662129809784312832 +1662129809832313856 +1662129809877314816 +1662129809925315840 +1662129809967316736 +1662129810012317696 +1662129810057318656 +1662129810099319552 +1662129810144320512 +1662129810186321408 +1662129810231322368 +1662129810276323328 +1662129810318324224 +1662129810360325120 +1662129810405326080 +1662129810447326976 +1662129810489327872 +1662129810543329024 +1662129810588329984 +1662129810639331072 +1662129810687332096 +1662129810732333056 +1662129810780334080 +1662129810819334912 +1662129810864335872 +1662129810909336832 +1662129810954337792 +1662129810999338752 +1662129811041339648 +1662129811086340608 +1662129811128341504 +1662129811170342400 +1662129811209343232 +1662129811263344384 +1662129811308345344 +1662129811359346432 +1662129811401347328 +1662129811446348288 +1662129811491349248 +1662129811533350144 +1662129811578351104 +1662129811626352128 +1662129811668353024 +1662129811710353920 +1662129811752354816 +1662129811794355712 +1662129811839356672 +1662129811881357568 +1662129811923358464 +1662129811974359552 +1662129812019360512 +1662129812067361536 +1662129812109362432 +1662129812151363328 +1662129812193364224 +1662129812235365120 +1662129812277366016 +1662129812322366976 +1662129812364367872 +1662129812409368832 +1662129812451369728 +1662129812499370752 +1662129812547371776 +1662129812589372672 +1662129812634373632 +1662129812679374592 +1662129812724375552 +1662129812778376704 +1662129812829377792 +1662129812874378752 +1662129812922379776 +1662129812967380736 +1662129813009381632 +1662129813057382656 +1662129813099383552 +1662129813147384576 +1662129813189385472 +1662129813231386368 +1662129813273387264 +1662129813318388224 +1662129813357389056 +1662129813402390016 +1662129813444390912 +1662129813489391872 +1662129813531392768 +1662129813579393792 +1662129813624394752 +1662129813666395648 +1662129813705396480 +1662129813747397376 +1662129813792398336 +1662129813834399232 +1662129813876400128 +1662129813918401024 +1662129813966402048 +1662129814011403008 +1662129814059404032 +1662129814104404992 +1662129814146405888 +1662129814191406848 +1662129814242407936 +1662129814284408832 +1662129814332409856 +1662129814371410688 +1662129814416411648 +1662129814467412736 +1662129814509413632 +1662129814551414528 +1662129814593415424 +1662129814635416320 +1662129814674417152 +1662129814722418176 +1662129814764419072 +1662129814818420224 +1662129814863421184 +1662129814908422144 +1662129814953423104 +1662129815001424128 +1662129815046425088 +1662129815091426048 +1662129815136427008 +1662129815181427968 +1662129815223428864 +1662129815265429760 +1662129815310430720 +1662129815352431616 +1662129815394432512 +1662129815436433408 +1662129815481434368 +1662129815526435328 +1662129815574436352 +1662129815625437440 +1662129815676438528 +1662129815721439488 +1662129815769440512 +1662129815814441472 +1662129815856442368 +1662129815910443520 +1662129815952444416 +1662129815997445376 +1662129816039446272 +1662129816087447296 +1662129816129448192 +1662129816171449088 +1662129816216450048 +1662129816264451072 +1662129816315452160 +1662129816360453120 +1662129816411454208 +1662129816456455168 +1662129816498456064 +1662129816540456960 +1662129816582457856 +1662129816627458816 +1662129816669459712 +1662129816717460736 +1662129816759461632 +1662129816813462784 +1662129816858463744 +1662129816900464640 +1662129816945465600 +1662129816996466688 +1662129817041467648 +1662129817083468544 +1662129817125469440 +1662129817179470592 +1662129817218471424 +1662129817266472448 +1662129817311473408 +1662129817359474432 +1662129817401475328 +1662129817443476224 +1662129817485477120 +1662129817527478016 +1662129817569478912 +1662129817611479808 +1662129817668481024 +1662129817713481984 +1662129817764483072 +1662129817812484096 +1662129817866485248 +1662129817908486144 +1662129817950487040 +1662129817992487936 +1662129818043489024 +1662129818094490112 +1662129818139491072 +1662129818181491968 +1662129818223492864 +1662129818268493824 +1662129818313494784 +1662129818367495936 +1662129818412496896 +1662129818454497792 +1662129818499498752 +1662129818544499712 +1662129818586500608 +1662129818631501568 +1662129818673502464 +1662129818718503424 +1662129818760504320 +1662129818802505216 +1662129818850506240 +1662129818892507136 +1662129818934508032 +1662129818982509056 +1662129819030510080 +1662129819075511040 +1662129819120512000 +1662129819162512896 +1662129819207513856 +1662129819261515008 +1662129819306515968 +1662129819354516992 +1662129819399517952 +1662129819447518976 +1662129819495520000 +1662129819534520832 +1662129819579521792 +1662129819621522688 +1662129819669523712 +1662129819714524672 +1662129819756525568 +1662129819801526528 +1662129819846527488 +1662129819888528384 +1662129819933529344 +1662129819978530304 +1662129820020531200 +1662129820062532096 +1662129820104532992 +1662129820152534016 +1662129820197534976 +1662129820239535872 +1662129820281536768 +1662129820323537664 +1662129820365538560 +1662129820410539520 +1662129820458540544 +1662129820500541440 +1662129820542542336 +1662129820587543296 +1662129820638544384 +1662129820689545472 +1662129820737546496 +1662129820782547456 +1662129820830548480 +1662129820881549568 +1662129820932550656 +1662129820983551744 +1662129821028552704 +1662129821070553600 +1662129821112554496 +1662129821157555456 +1662129821205556480 +1662129821256557568 +1662129821301558528 +1662129821343559424 +1662129821394560512 +1662129821451561728 +1662129821493562624 +1662129821535563520 +1662129821589564672 +1662129821634565632 +1662129821682566656 +1662129821724567552 +1662129821778568704 +1662129821826569728 +1662129821871570688 +1662129821913571584 +1662129821955572480 +1662129821997573376 +1662129822039574272 +1662129822084575232 +1662129822144576512 +1662129822192577536 +1662129822234578432 +1662129822276579328 +1662129822318580224 +1662129822363581184 +1662129822411582208 +1662129822453583104 +1662129822498584064 +1662129822540584960 +1662129822582585856 +1662129822624586752 +1662129822669587712 +1662129822708588544 +1662129822750589440 +1662129822792590336 +1662129822843591424 +1662129822885592320 +1662129822939593472 +1662129822981594368 +1662129823023595264 +1662129823062596096 +1662129823101596928 +1662129823143597824 +1662129823185598720 +1662129823233599744 +1662129823278600704 +1662129823332601856 +1662129823380602880 +1662129823425603840 +1662129823473604864 +1662129823521605888 +1662129823560606720 +1662129823605607680 +1662129823650608640 +1662129823698609664 +1662129823740610560 +1662129823791611648 +1662129823836612608 +1662129823878613504 +1662129823923614464 +1662129823971615488 +1662129824016616448 +1662129824067617536 +1662129824112618496 +1662129824154619392 +1662129824208620544 +1662129824253621504 +1662129824298622464 +1662129824340623360 +1662129824388624384 +1662129824430625280 +1662129824475626240 +1662129824514627072 +1662129824556627968 +1662129824607629056 +1662129824655630080 +1662129824703631104 +1662129824745632000 +1662129824790632960 +1662129824832633856 +1662129824880634880 +1662129824925635840 +1662129824970636800 +1662129825018637824 +1662129825063638784 +1662129825108639744 +1662129825153640704 +1662129825195641600 +1662129825249642752 +1662129825300643840 +1662129825345644800 +1662129825387645696 +1662129825435646720 +1662129825477647616 +1662129825522648576 +1662129825570649600 +1662129825615650560 +1662129825660651520 +1662129825702652416 +1662129825747653376 +1662129825792654336 +1662129825837655296 +1662129825876656128 +1662129825918657024 +1662129825960657920 +1662129826005658880 +1662129826047659776 +1662129826104660992 +1662129826152662016 +1662129826197662976 +1662129826236663808 +1662129826278664704 +1662129826323665664 +1662129826365666560 +1662129826416667648 +1662129826458668544 +1662129826506669568 +1662129826551670528 +1662129826599671552 +1662129826644672512 +1662129826695673600 +1662129826743674624 +1662129826785675520 +1662129826836676608 +1662129826887677696 +1662129826941678848 +1662129826992679936 +1662129827031680768 +1662129827079681792 +1662129827121682688 +1662129827166683648 +1662129827217684736 +1662129827262685696 +1662129827304686592 +1662129827349687552 +1662129827400688640 +1662129827451689728 +1662129827490690560 +1662129827544691712 +1662129827589692672 +1662129827631693568 +1662129827676694528 +1662129827730695680 +1662129827769696512 +1662129827811697408 +1662129827856698368 +1662129827901699328 +1662129827943700224 +1662129827985701120 +1662129828027702016 +1662129828072702976 +1662129828114703872 +1662129828162704896 +1662129828204705792 +1662129828246706688 +1662129828303707904 +1662129828345708800 +1662129828387709696 +1662129828432710656 +1662129828471711488 +1662129828513712384 +1662129828558713344 +1662129828612714496 +1662129828657715456 +1662129828699716352 +1662129828738717184 +1662129828780718080 +1662129828831719168 +1662129828876720128 +1662129828918721024 +1662129828963721984 +1662129829008722944 +1662129829050723840 +1662129829095724800 +1662129829134725632 +1662129829176726528 +1662129829224727552 +1662129829266728448 +1662129829311729408 +1662129829350730240 +1662129829392731136 +1662129829437732096 +1662129829479732992 +1662129829533734144 +1662129829578735104 +1662129829620736000 +1662129829671737088 +1662129829719738112 +1662129829761739008 +1662129829806739968 +1662129829854740992 +1662129829899741952 +1662129829947742976 +1662129829989743872 +1662129830034744832 +1662129830079745792 +1662129830121746688 +1662129830163747584 +1662129830205748480 +1662129830247749376 +1662129830289750272 +1662129830328751104 +1662129830376752128 +1662129830427753216 +1662129830469754112 +1662129830514755072 +1662129830565756160 +1662129830610757120 +1662129830652758016 +1662129830703759104 +1662129830745760000 +1662129830793761024 +1662129830844762112 +1662129830886763008 +1662129830928763904 +1662129830973764864 +1662129831015765760 +1662129831057766656 +1662129831099767552 +1662129831144768512 +1662129831186769408 +1662129831231770368 +1662129831276771328 +1662129831318772224 +1662129831357773056 +1662129831405774080 +1662129831447774976 +1662129831495776000 +1662129831537776896 +1662129831591778048 +1662129831636779008 +1662129831681779968 +1662129831729780992 +1662129831786782208 +1662129831834783232 +1662129831882784256 +1662129831921785088 +1662129831963785984 +1662129832005786880 +1662129832050787840 +1662129832101788928 +1662129832149789952 +1662129832188790784 +1662129832233791744 +1662129832275792640 +1662129832323793664 +1662129832368794624 +1662129832410795520 +1662129832452796416 +1662129832494797312 +1662129832536798208 +1662129832581799168 +1662129832626800128 +1662129832668801024 +1662129832710801920 +1662129832758802944 +1662129832800803840 +1662129832854804992 +1662129832896805888 +1662129832941806848 +1662129832989807872 +1662129833034808832 +1662129833076809728 +1662129833124810752 +1662129833166811648 +1662129833223812864 +1662129833265813760 +1662129833310814720 +1662129833355815680 +1662129833406816768 +1662129833448817664 +1662129833493818624 +1662129833541819648 +1662129833583820544 +1662129833628821504 +1662129833673822464 +1662129833715823360 +1662129833760824320 +1662129833799825152 +1662129833841826048 +1662129833889827072 +1662129833937828096 +1662129833985829120 +1662129834030830080 +1662129834069830912 +1662129834117831936 +1662129834162832896 +1662129834210833920 +1662129834255834880 +1662129834303835904 +1662129834348836864 +1662129834387837696 +1662129834432838656 +1662129834480839680 +1662129834528840704 +1662129834570841600 +1662129834609842432 +1662129834651843328 +1662129834693844224 +1662129834735845120 +1662129834786846208 +1662129834834847232 +1662129834876848128 +1662129834924849152 +1662129834966850048 +1662129835011851008 +1662129835056851968 +1662129835101852928 +1662129835158854144 +1662129835200855040 +1662129835245856000 +1662129835287856896 +1662129835341858048 +1662129835383858944 +1662129835428859904 +1662129835476860928 +1662129835521861888 +1662129835566862848 +1662129835605863680 +1662129835647864576 +1662129835698865664 +1662129835746866688 +1662129835788867584 +1662129835836868608 +1662129835878869504 +1662129835920870400 +1662129835965871360 +1662129836013872384 +1662129836052873216 +1662129836094874112 +1662129836142875136 +1662129836190876160 +1662129836238877184 +1662129836280878080 +1662129836328879104 +1662129836367879936 +1662129836415880960 +1662129836457881856 +1662129836499882752 +1662129836544883712 +1662129836586884608 +1662129836628885504 +1662129836679886592 +1662129836730887680 +1662129836772888576 +1662129836817889536 +1662129836862890496 +1662129836913891584 +1662129836958892544 +1662129837006893568 +1662129837057894656 +1662129837096895488 +1662129837135896320 +1662129837177897216 +1662129837219898112 +1662129837264899072 +1662129837309900032 +1662129837351900928 +1662129837393901824 +1662129837444902912 +1662129837483903744 +1662129837528904704 +1662129837573905664 +1662129837615906560 +1662129837657907456 +1662129837702908416 +1662129837747909376 +1662129837792910336 +1662129837843911424 +1662129837885912320 +1662129837930913280 +1662129837975914240 +1662129838020915200 +1662129838062916096 +1662129838104916992 +1662129838149917952 +1662129838191918848 +1662129838236919808 +1662129838278920704 +1662129838320921600 +1662129838374922752 +1662129838419923712 +1662129838464924672 +1662129838512925696 +1662129838554926592 +1662129838596927488 +1662129838638928384 +1662129838686929408 +1662129838728930304 +1662129838770931200 +1662129838812932096 +1662129838854932992 +1662129838896933888 +1662129838941934848 +1662129838983935744 +1662129839028936704 +1662129839070937600 +1662129839112938496 +1662129839154939392 +1662129839199940352 +1662129839244941312 +1662129839286942208 +1662129839328943104 +1662129839370944000 +1662129839421945088 +1662129839463945984 +1662129839508946944 +1662129839550947840 +1662129839589948672 +1662129839631949568 +1662129839673950464 +1662129839715951360 +1662129839757952256 +1662129839802953216 +1662129839844954112 +1662129839895955200 +1662129839940956160 +1662129839982957056 +1662129840024957952 +1662129840075959040 +1662129840126960128 +1662129840171961088 +1662129840213961984 +1662129840255962880 +1662129840297963776 +1662129840339964672 +1662129840381965568 +1662129840426966528 +1662129840468967424 +1662129840513968384 +1662129840564969472 +1662129840609970432 +1662129840660971520 +1662129840708972544 +1662129840759973632 +1662129840801974528 +1662129840843975424 +1662129840888976384 +1662129840933977344 +1662129840975978240 +1662129841020979200 +1662129841071980288 +1662129841116981248 +1662129841164982272 +1662129841203983104 +1662129841248984064 +1662129841302985216 +1662129841344986112 +1662129841392987136 +1662129841434988032 +1662129841479988992 +1662129841527990016 +1662129841569990912 +1662129841617991936 +1662129841662992896 +1662129841707993856 +1662129841749994752 +1662129841791995648 +1662129841833996544 +1662129841875997440 +1662129841914998272 +1662129841956999168 +1662129841999000064 +1662129842041000960 +1662129842086001920 +1662129842131002880 +1662129842188004096 +1662129842233005056 +1662129842278006016 +1662129842326007040 +1662129842368007936 +1662129842419009024 +1662129842458009856 +1662129842500010752 +1662129842542011648 +1662129842584012544 +1662129842626013440 +1662129842680014592 +1662129842719015424 +1662129842773016576 +1662129842818017536 +1662129842860018432 +1662129842905019392 +1662129842947020288 +1662129842992021248 +1662129843040022272 +1662129843079023104 +1662129843121024000 +1662129843166024960 +1662129843208025856 +1662129843250026752 +1662129843292027648 +1662129843337028608 +1662129843382029568 +1662129843433030656 +1662129843481031680 +1662129843526032640 +1662129843574033664 +1662129843625034752 +1662129843667035648 +1662129843709036544 +1662129843751037440 +1662129843793038336 +1662129843835039232 +1662129843880040192 +1662129843922041088 +1662129843973042176 +1662129844018043136 +1662129844066044160 +1662129844108045056 +1662129844150045952 +1662129844204047104 +1662129844255048192 +1662129844297049088 +1662129844339049984 +1662129844381050880 +1662129844423051776 +1662129844462052608 +1662129844504053504 +1662129844552054528 +1662129844597055488 +1662129844642056448 +1662129844687057408 +1662129844732058368 +1662129844771059200 +1662129844813060096 +1662129844855060992 +1662129844906062080 +1662129844948062976 +1662129844996064000 +1662129845035064832 +1662129845083065856 +1662129845137067008 +1662129845179067904 +1662129845227068928 +1662129845272069888 +1662129845314070784 +1662129845356071680 +1662129845401072640 +1662129845443073536 +1662129845485074432 +1662129845527075328 +1662129845572076288 +1662129845617077248 +1662129845662078208 +1662129845704079104 +1662129845746080000 +1662129845788080896 +1662129845836081920 +1662129845878082816 +1662129845926083840 +1662129845974084864 +1662129846019085824 +1662129846067086848 +1662129846112087808 +1662129846157088768 +1662129846202089728 +1662129846244090624 +1662129846286091520 +1662129846328092416 +1662129846385093632 +1662129846424094464 +1662129846469095424 +1662129846508096256 +1662129846553097216 +1662129846598098176 +1662129846649099264 +1662129846697100288 +1662129846739101184 +1662129846787102208 +1662129846832103168 +1662129846874104064 +1662129846919105024 +1662129846964105984 +1662129847006106880 +1662129847051107840 +1662129847105108992 +1662129847156110080 +1662129847201111040 +1662129847246112000 +1662129847288112896 +1662129847336113920 +1662129847384114944 +1662129847423115776 +1662129847468116736 +1662129847519117824 +1662129847567118848 +1662129847612119808 +1662129847654120704 +1662129847702121728 +1662129847744122624 +1662129847783123456 +1662129847831124480 +1662129847873125376 +1662129847921126400 +1662129847963127296 +1662129848005128192 +1662129848053129216 +1662129848107130368 +1662129848152131328 +1662129848197132288 +1662129848242133248 +1662129848284134144 +1662129848332135168 +1662129848380136192 +1662129848422137088 +1662129848467138048 +1662129848509138944 +1662129848551139840 +1662129848593140736 +1662129848632141568 +1662129848674142464 +1662129848719143424 +1662129848764144384 +1662129848812145408 +1662129848857146368 +1662129848896147200 +1662129848941148160 +1662129848992149248 +1662129849034150144 +1662129849076151040 +1662129849127152128 +1662129849169153024 +1662129849223154176 +1662129849277155328 +1662129849325156352 +1662129849367157248 +1662129849418158336 +1662129849466159360 +1662129849514160384 +1662129849556161280 +1662129849604162304 +1662129849652163328 +1662129849694164224 +1662129849736165120 +1662129849781166080 +1662129849832167168 +1662129849877168128 +1662129849922169088 +1662129849964169984 +1662129850009170944 +1662129850051171840 +1662129850093172736 +1662129850138173696 +1662129850180174592 +1662129850222175488 +1662129850264176384 +1662129850315177472 +1662129850360178432 +1662129850399179264 +1662129850444180224 +1662129850489181184 +1662129850531182080 +1662129850576183040 +1662129850621184000 +1662129850669185024 +1662129850714185984 +1662129850759186944 +1662129850804187904 +1662129850846188800 +1662129850894189824 +1662129850936190720 +1662129850987191808 +1662129851029192704 +1662129851074193664 +1662129851119194624 +1662129851164195584 +1662129851209196544 +1662129851254197504 +1662129851299198464 +1662129851338199296 +1662129851380200192 +1662129851422201088 +1662129851470202112 +1662129851515203072 +1662129851554203904 +1662129851596204800 +1662129851647205888 +1662129851695206912 +1662129851737207808 +1662129851785208832 +1662129851830209792 +1662129851872210688 +1662129851917211648 +1662129851959212544 +1662129852001213440 +1662129852049214464 +1662129852100215552 +1662129852148216576 +1662129852190217472 +1662129852229218304 +1662129852271219200 +1662129852313220096 +1662129852355220992 +1662129852409222144 +1662129852451223040 +1662129852496224000 +1662129852538224896 +1662129852583225856 +1662129852625226752 +1662129852676227840 +1662129852724228864 +1662129852766229760 +1662129852811230720 +1662129852859231744 +1662129852907232768 +1662129852955233792 +1662129852997234688 +1662129853042235648 +1662129853090236672 +1662129853138237696 +1662129853189238784 +1662129853237239808 +1662129853279240704 +1662129853324241664 +1662129853366242560 +1662129853408243456 +1662129853453244416 +1662129853501245440 +1662129853543246336 +1662129853591247360 +1662129853636248320 +1662129853678249216 +1662129853723250176 +1662129853771251200 +1662129853816252160 +1662129853873253376 +1662129853924254464 +1662129853969255424 +1662129854011256320 +1662129854056257280 +1662129854098258176 +1662129854140259072 +1662129854185260032 +1662129854233261056 +1662129854284262144 +1662129854329263104 +1662129854374264064 +1662129854422265088 +1662129854473266176 +1662129854521267200 +1662129854560268032 +1662129854605268992 +1662129854644269824 +1662129854686270720 +1662129854728271616 +1662129854782272768 +1662129854827273728 +1662129854869274624 +1662129854911275520 +1662129854962276608 +1662129855010277632 +1662129855055278592 +1662129855100279552 +1662129855142280448 +1662129855187281408 +1662129855235282432 +1662129855283283456 +1662129855328284416 +1662129855370285312 +1662129855409286144 +1662129855454287104 +1662129855499288064 +1662129855541288960 +1662129855580289792 +1662129855625290752 +1662129855670291712 +1662129855712292608 +1662129855754293504 +1662129855799294464 +1662129855841295360 +1662129855886296320 +1662129855937297408 +1662129855976298240 +1662129856018299136 +1662129856066300160 +1662129856111301120 +1662129856156302080 +1662129856204303104 +1662129856255304192 +1662129856297305088 +1662129856339305984 +1662129856381306880 +1662129856426307840 +1662129856465308672 +1662129856507309568 +1662129856549310464 +1662129856594311424 +1662129856636312320 +1662129856678313216 +1662129856720314112 +1662129856768315136 +1662129856813316096 +1662129856855316992 +1662129856897317888 +1662129856939318784 +1662129856984319744 +1662129857029320704 +1662129857074321664 +1662129857122322688 +1662129857167323648 +1662129857215324672 +1662129857260325632 +1662129857302326528 +1662129857350327552 +1662129857395328512 +1662129857437329408 +1662129857479330304 +1662129857521331200 +1662129857566332160 +1662129857614333184 +1662129857656334080 +1662129857698334976 +1662129857743335936 +1662129857785336832 +1662129857827337728 +1662129857875338752 +1662129857917339648 +1662129857959340544 +1662129858001341440 +1662129858049342464 +1662129858088343296 +1662129858127344128 +1662129858169345024 +1662129858211345920 +1662129858259346944 +1662129858301347840 +1662129858352348928 +1662129858403350016 +1662129858448350976 +1662129858496352000 +1662129858541352960 +1662129858589353984 +1662129858637355008 +1662129858688356096 +1662129858727356928 +1662129858769357824 +1662129858814358784 +1662129858856359680 +1662129858898360576 +1662129858943361536 +1662129858985362432 +1662129859042363648 +1662129859087364608 +1662129859126365440 +1662129859171366400 +1662129859213367296 +1662129859255368192 +1662129859300369152 +1662129859342370048 +1662129859390371072 +1662129859432371968 +1662129859477372928 +1662129859528374016 +1662129859570374912 +1662129859615375872 +1662129859657376768 +1662129859699377664 +1662129859750378752 +1662129859792379648 +1662129859834380544 +1662129859879381504 +1662129859921382400 +1662129859963383296 +1662129860008384256 +1662129860053385216 +1662129860095386112 +1662129860140387072 +1662129860182387968 +1662129860233389056 +1662129860275389952 +1662129860320390912 +1662129860368391936 +1662129860419393024 +1662129860464393984 +1662129860506394880 +1662129860548395776 +1662129860590396672 +1662129860641397760 +1662129860683398656 +1662129860731399680 +1662129860776400640 +1662129860818401536 +1662129860869402624 +1662129860917403648 +1662129860959404544 +1662129861007405568 +1662129861055406592 +1662129861097407488 +1662129861142408448 +1662129861184409344 +1662129861229410304 +1662129861274411264 +1662129861319412224 +1662129861364413184 +1662129861415414272 +1662129861457415168 +1662129861496416000 +1662129861538416896 +1662129861586417920 +1662129861625418752 +1662129861667419648 +1662129861712420608 +1662129861754421504 +1662129861796422400 +1662129861838423296 +1662129861886424320 +1662129861937425408 +1662129861982426368 +1662129862024427264 +1662129862066428160 +1662129862114429184 +1662129862159430144 +1662129862201431040 +1662129862243431936 +1662129862291432960 +1662129862336433920 +1662129862378434816 +1662129862423435776 +1662129862465436672 +1662129862516437760 +1662129862561438720 +1662129862603439616 +1662129862648440576 +1662129862687441408 +1662129862729442304 +1662129862777443328 +1662129862825444352 +1662129862867445248 +1662129862912446208 +1662129862960447232 +1662129863005448192 +1662129863056449280 +1662129863101450240 +1662129863140451072 +1662129863182451968 +1662129863224452864 +1662129863266453760 +1662129863317454848 +1662129863359455744 +1662129863407456768 +1662129863455457792 +1662129863497458688 +1662129863542459648 +1662129863584460544 +1662129863626461440 +1662129863674462464 +1662129863722463488 +1662129863764464384 +1662129863806465280 +1662129863845466112 +1662129863890467072 +1662129863932467968 +1662129863977468928 +1662129864019469824 +1662129864061470720 +1662129864106471680 +1662129864154472704 +1662129864202473728 +1662129864244474624 +1662129864286475520 +1662129864331476480 +1662129864382477568 +1662129864427478528 +1662129864472479488 +1662129864517480448 +1662129864559481344 +1662129864601482240 +1662129864646483200 +1662129864694484224 +1662129864733485056 +1662129864778486016 +1662129864829487104 +1662129864880488192 +1662129864922489088 +1662129864964489984 +1662129865006490880 +1662129865054491904 +1662129865099492864 +1662129865141493760 +1662129865183494656 +1662129865222495488 +1662129865270496512 +1662129865312497408 +1662129865351498240 +1662129865393499136 +1662129865438500096 +1662129865489501184 +1662129865534502144 +1662129865579503104 +1662129865624504064 +1662129865666504960 +1662129865708505856 +1662129865753506816 +1662129865804507904 +1662129865846508800 +1662129865894509824 +1662129865939510784 +1662129865981511680 +1662129866023512576 +1662129866077513728 +1662129866125514752 +1662129866167515648 +1662129866212516608 +1662129866257517568 +1662129866308518656 +1662129866353519616 +1662129866398520576 +1662129866440521472 +1662129866485522432 +1662129866530523392 +1662129866578524416 +1662129866620525312 +1662129866662526208 +1662129866707527168 +1662129866752528128 +1662129866794529024 +1662129866836529920 +1662129866875530752 +1662129866920531712 +1662129866974532864 +1662129867022533888 +1662129867064534784 +1662129867106535680 +1662129867151536640 +1662129867190537472 +1662129867244538624 +1662129867289539584 +1662129867331540480 +1662129867385541632 +1662129867427542528 +1662129867472543488 +1662129867517544448 +1662129867562545408 +1662129867607546368 +1662129867649547264 +1662129867697548288 +1662129867742549248 +1662129867787550208 +1662129867829551104 +1662129867868551936 +1662129867916552960 +1662129867961553920 +1662129868009554944 +1662129868054555904 +1662129868096556800 +1662129868150557952 +1662129868192558848 +1662129868234559744 +1662129868279560704 +1662129868327561728 +1662129868378562816 +1662129868423563776 +1662129868465564672 +1662129868507565568 +1662129868549566464 +1662129868591567360 +1662129868633568256 +1662129868675569152 +1662129868723570176 +1662129868768571136 +1662129868822572288 +1662129868867573248 +1662129868909574144 +1662129868957575168 +1662129869002576128 +1662129869050577152 +1662129869092578048 +1662129869137579008 +1662129869182579968 +1662129869224580864 +1662129869266581760 +1662129869314582784 +1662129869356583680 +1662129869401584640 +1662129869449585664 +1662129869491586560 +1662129869533587456 +1662129869575588352 +1662129869614589184 +1662129869659590144 +1662129869701591040 +1662129869749592064 +1662129869788592896 +1662129869830593792 +1662129869875594752 +1662129869917595648 +1662129869962596608 +1662129870010597632 +1662129870055598592 +1662129870097599488 +1662129870142600448 +1662129870184601344 +1662129870226602240 +1662129870271603200 +1662129870316604160 +1662129870355604992 +1662129870409606144 +1662129870451607040 +1662129870502608128 +1662129870541608960 +1662129870586609920 +1662129870628610816 +1662129870673611776 +1662129870718612736 +1662129870763613696 +1662129870808614656 +1662129870850615552 +1662129870892616448 +1662129870943617536 +1662129870985618432 +1662129871033619456 +1662129871078620416 +1662129871129621504 +1662129871171622400 +1662129871216623360 +1662129871258624256 +1662129871306625280 +1662129871348626176 +1662129871390627072 +1662129871432627968 +1662129871474628864 +1662129871525629952 +1662129871573630976 +1662129871615631872 +1662129871657632768 +1662129871702633728 +1662129871744634624 +1662129871789635584 +1662129871837636608 +1662129871885637632 +1662129871930638592 +1662129871972639488 +1662129872020640512 +1662129872065641472 +1662129872107642368 +1662129872149643264 +1662129872191644160 +1662129872239645184 +1662129872287646208 +1662129872332647168 +1662129872374648064 +1662129872419649024 +1662129872464649984 +1662129872509650944 +1662129872557651968 +1662129872602652928 +1662129872644653824 +1662129872689654784 +1662129872731655680 +1662129872773656576 +1662129872827657728 +1662129872875658752 +1662129872926659840 +1662129872977660928 +1662129873025661952 +1662129873070662912 +1662129873124664064 +1662129873178665216 +1662129873223666176 +1662129873271667200 +1662129873328668416 +1662129873370669312 +1662129873415670272 +1662129873460671232 +1662129873505672192 +1662129873547673088 +1662129873592674048 +1662129873634674944 +1662129873679675904 +1662129873721676800 +1662129873763677696 +1662129873808678656 +1662129873853679616 +1662129873898680576 +1662129873940681472 +1662129873982682368 +1662129874024683264 +1662129874072684288 +1662129874123685376 +1662129874168686336 +1662129874210687232 +1662129874255688192 +1662129874297689088 +1662129874348690176 +1662129874393691136 +1662129874435692032 +1662129874477692928 +1662129874522693888 +1662129874567694848 +1662129874609695744 +1662129874651696640 +1662129874693697536 +1662129874735698432 +1662129874780699392 +1662129874822700288 +1662129874867701248 +1662129874921702400 +1662129874966703360 +1662129875011704320 +1662129875053705216 +1662129875095706112 +1662129875137707008 +1662129875179707904 +1662129875221708800 +1662129875266709760 +1662129875311710720 +1662129875356711680 +1662129875395712512 +1662129875437713408 +1662129875482714368 +1662129875524715264 +1662129875569716224 +1662129875611717120 +1662129875650717952 +1662129875692718848 +1662129875743719936 +1662129875788720896 +1662129875830721792 +1662129875872722688 +1662129875917723648 +1662129875959724544 +1662129876001725440 +1662129876052726528 +1662129876103727616 +1662129876148728576 +1662129876190729472 +1662129876238730496 +1662129876286731520 +1662129876328732416 +1662129876373733376 +1662129876415734272 +1662129876463735296 +1662129876508736256 +1662129876550737152 +1662129876592738048 +1662129876634738944 +1662129876679739904 +1662129876727740928 +1662129876775741952 +1662129876817742848 +1662129876859743744 +1662129876904744704 +1662129876943745536 +1662129876985746432 +1662129877030747392 +1662129877075748352 +1662129877120749312 +1662129877165750272 +1662129877222751488 +1662129877270752512 +1662129877312753408 +1662129877357754368 +1662129877399755264 +1662129877441756160 +1662129877483757056 +1662129877528758016 +1662129877567758848 +1662129877609759744 +1662129877651760640 +1662129877696761600 +1662129877735762432 +1662129877783763456 +1662129877831764480 +1662129877873765376 +1662129877924766464 +1662129877969767424 +1662129878014768384 +1662129878053769216 +1662129878095770112 +1662129878140771072 +1662129878185772032 +1662129878227772928 +1662129878266773760 +1662129878311774720 +1662129878353775616 +1662129878401776640 +1662129878446777600 +1662129878488778496 +1662129878530779392 +1662129878578780416 +1662129878617781248 +1662129878665782272 +1662129878707783168 +1662129878752784128 +1662129878794785024 +1662129878845786112 +1662129878890787072 +1662129878932787968 +1662129878974788864 +1662129879025789952 +1662129879073790976 +1662129879115791872 +1662129879166792960 +1662129879214793984 +1662129879256794880 +1662129879295795712 +1662129879337796608 +1662129879382797568 +1662129879427798528 +1662129879469799424 +1662129879514800384 +1662129879559801344 +1662129879604802304 +1662129879652803328 +1662129879700804352 +1662129879742805248 +1662129879784806144 +1662129879832807168 +1662129879877808128 +1662129879925809152 +1662129879967810048 +1662129880009810944 +1662129880060812032 +1662129880105812992 +1662129880144813824 +1662129880189814784 +1662129880231815680 +1662129880279816704 +1662129880321817600 +1662129880366818560 +1662129880408819456 +1662129880456820480 +1662129880498821376 +1662129880540822272 +1662129880585823232 +1662129880624824064 +1662129880669825024 +1662129880711825920 +1662129880756826880 +1662129880801827840 +1662129880843828736 +1662129880885829632 +1662129880933830656 +1662129880981831680 +1662129881029832704 +1662129881074833664 +1662129881116834560 +1662129881158835456 +1662129881203836416 +1662129881245837312 +1662129881293838336 +1662129881335839232 +1662129881383840256 +1662129881425841152 +1662129881470842112 +1662129881524843264 +1662129881569844224 +1662129881611845120 +1662129881656846080 +1662129881704847104 +1662129881749848064 +1662129881794849024 +1662129881836849920 +1662129881887851008 +1662129881929851904 +1662129881977852928 +1662129882019853824 +1662129882064854784 +1662129882118855936 +1662129882163856896 +1662129882211857920 +1662129882253858816 +1662129882298859776 +1662129882340860672 +1662129882382861568 +1662129882421862400 +1662129882463863296 +1662129882508864256 +1662129882553865216 +1662129882601866240 +1662129882643867136 +1662129882685868032 +1662129882733869056 +1662129882781870080 +1662129882826871040 +1662129882871872000 +1662129882913872896 +1662129882955873792 +1662129882997874688 +1662129883036875520 +1662129883078876416 +1662129883132877568 +1662129883174878464 +1662129883216879360 +1662129883267880448 +1662129883309881344 +1662129883351882240 +1662129883399883264 +1662129883444884224 +1662129883483885056 +1662129883525885952 +1662129883576887040 +1662129883624888064 +1662129883675889152 +1662129883723890176 +1662129883762891008 +1662129883810892032 +1662129883861893120 +1662129883903894016 +1662129883948894976 +1662129883996896000 +1662129884038896896 +1662129884092898048 +1662129884137899008 +1662129884185900032 +1662129884230900992 +1662129884281902080 +1662129884320902912 +1662129884368903936 +1662129884407904768 +1662129884452905728 +1662129884497906688 +1662129884548907776 +1662129884593908736 +1662129884635909632 +1662129884686910720 +1662129884737911808 +1662129884782912768 +1662129884827913728 +1662129884872914688 +1662129884923915776 +1662129884968916736 +1662129885010917632 +1662129885049918464 +1662129885091919360 +1662129885142920448 +1662129885187921408 +1662129885229922304 +1662129885277923328 +1662129885322924288 +1662129885367925248 +1662129885409926144 +1662129885454927104 +1662129885505928192 +1662129885550929152 +1662129885595930112 +1662129885643931136 +1662129885685932032 +1662129885730932992 +1662129885772933888 +1662129885826935040 +1662129885877936128 +1662129885919937024 +1662129885961937920 +1662129886006938880 +1662129886060940032 +1662129886105940992 +1662129886147941888 +1662129886192942848 +1662129886234943744 +1662129886276944640 +1662129886318945536 +1662129886378946816 +1662129886423947776 +1662129886465948672 +1662129886510949632 +1662129886558950656 +1662129886603951616 +1662129886645952512 +1662129886687953408 +1662129886732954368 +1662129886777955328 +1662129886819956224 +1662129886861957120 +1662129886909958144 +1662129886951959040 +1662129886996960000 +1662129887038960896 +1662129887080961792 +1662129887134962944 +1662129887173963776 +1662129887218964736 +1662129887263965696 +1662129887308966656 +1662129887353967616 +1662129887398968576 +1662129887449969664 +1662129887491970560 +1662129887533971456 +1662129887578972416 +1662129887623973376 +1662129887665974272 +1662129887710975232 +1662129887758976256 +1662129887797977088 +1662129887839977984 +1662129887881978880 +1662129887929979904 +1662129887974980864 +1662129888019981824 +1662129888061982720 +1662129888112983808 +1662129888151984640 +1662129888199985664 +1662129888244986624 +1662129888286987520 +1662129888331988480 +1662129888376989440 +1662129888418990336 +1662129888460991232 +1662129888508992256 +1662129888553993216 +1662129888595994112 +1662129888637995008 +1662129888679995904 +1662129888721996800 +1662129888763997696 +1662129888808998656 +1662129888850999552 +1662129888893000448 +1662129888935001344 +1662129888980002304 +1662129889025003264 +1662129889064004096 +1662129889112005120 +1662129889157006080 +1662129889202007040 +1662129889241007872 +1662129889289008896 +1662129889331009792 +1662129889376010752 +1662129889424011776 +1662129889466012672 +1662129889508013568 +1662129889559014656 +1662129889604015616 +1662129889643016448 +1662129889685017344 +1662129889730018304 +1662129889772019200 +1662129889826020352 +1662129889865021184 +1662129889904022016 +1662129889952023040 +1662129889997024000 +1662129890039024896 +1662129890081025792 +1662129890123026688 +1662129890171027712 +1662129890213028608 +1662129890255029504 +1662129890297030400 +1662129890339031296 +1662129890381032192 +1662129890423033088 +1662129890471034112 +1662129890513035008 +1662129890558035968 +1662129890603036928 +1662129890648037888 +1662129890702039040 +1662129890750040064 +1662129890789040896 +1662129890840041984 +1662129890882042880 +1662129890927043840 +1662129890972044800 +1662129891020045824 +1662129891062046720 +1662129891116047872 +1662129891164048896 +1662129891209049856 +1662129891257050880 +1662129891299051776 +1662129891344052736 +1662129891386053632 +1662129891428054528 +1662129891467055360 +1662129891509056256 +1662129891554057216 +1662129891599058176 +1662129891644059136 +1662129891686060032 +1662129891743061248 +1662129891785062144 +1662129891824062976 +1662129891863063808 +1662129891911064832 +1662129891956065792 +1662129891998066688 +1662129892040067584 +1662129892088068608 +1662129892133069568 +1662129892175070464 +1662129892217071360 +1662129892259072256 +1662129892304073216 +1662129892346074112 +1662129892391075072 +1662129892436076032 +1662129892484077056 +1662129892523077888 +1662129892565078784 +1662129892610079744 +1662129892655080704 +1662129892697081600 +1662129892745082624 +1662129892787083520 +1662129892835084544 +1662129892880085504 +1662129892931086592 +1662129892973087488 +1662129893015088384 +1662129893057089280 +1662129893096090112 +1662129893138091008 +1662129893183091968 +1662129893228092928 +1662129893276093952 +1662129893327095040 +1662129893369095936 +1662129893414096896 +1662129893459097856 +1662129893501098752 +1662129893546099712 +1662129893600100864 +1662129893645101824 +1662129893687102720 +1662129893735103744 +1662129893774104576 +1662129893816105472 +1662129893858106368 +1662129893900107264 +1662129893948108288 +1662129893990109184 +1662129894035110144 +1662129894080111104 +1662129894128112128 +1662129894170113024 +1662129894215113984 +1662129894257114880 +1662129894299115776 +1662129894341116672 +1662129894386117632 +1662129894425118464 +1662129894467119360 +1662129894515120384 +1662129894560121344 +1662129894611122432 +1662129894650123264 +1662129894695124224 +1662129894737125120 +1662129894782126080 +1662129894833127168 +1662129894884128256 +1662129894929129216 +1662129894977130240 +1662129895034131456 +1662129895085132544 +1662129895130133504 +1662129895172134400 +1662129895214135296 +1662129895262136320 +1662129895304137216 +1662129895343138048 +1662129895385138944 +1662129895427139840 +1662129895466140672 +1662129895511141632 +1662129895568142848 +1662129895616143872 +1662129895661144832 +1662129895709145856 +1662129895760146944 +1662129895808147968 +1662129895850148864 +1662129895895149824 +1662129895934150656 +1662129895979151616 +1662129896033152768 +1662129896075153664 +1662129896126154752 +1662129896171155712 +1662129896216156672 +1662129896258157568 +1662129896303158528 +1662129896348159488 +1662129896390160384 +1662129896438161408 +1662129896486162432 +1662129896534163456 +1662129896582164480 +1662129896621165312 +1662129896669166336 +1662129896714167296 +1662129896756168192 +1662129896801169152 +1662129896849170176 +1662129896897171200 +1662129896945172224 +1662129896990173184 +1662129897032174080 +1662129897077175040 +1662129897122176000 +1662129897170177024 +1662129897212177920 +1662129897254178816 +1662129897299179776 +1662129897341180672 +1662129897380181504 +1662129897428182528 +1662129897479183616 +1662129897521184512 +1662129897566185472 +1662129897605186304 +1662129897647187200 +1662129897695188224 +1662129897734189056 +1662129897776189952 +1662129897821190912 +1662129897863191808 +1662129897908192768 +1662129897956193792 +1662129897998194688 +1662129898037195520 +1662129898085196544 +1662129898127197440 +1662129898169198336 +1662129898220199424 +1662129898262200320 +1662129898307201280 +1662129898349202176 +1662129898397203200 +1662129898448204288 +1662129898493205248 +1662129898538206208 +1662129898586207232 +1662129898646208512 +1662129898694209536 +1662129898736210432 +1662129898784211456 +1662129898829212416 +1662129898877213440 +1662129898919214336 +1662129898970215424 +1662129899015216384 +1662129899063217408 +1662129899111218432 +1662129899156219392 +1662129899204220416 +1662129899246221312 +1662129899291222272 +1662129899333223168 +1662129899378224128 +1662129899420225024 +1662129899462225920 +1662129899504226816 +1662129899549227776 +1662129899591228672 +1662129899636229632 +1662129899687230720 +1662129899732231680 +1662129899774232576 +1662129899816233472 +1662129899858234368 +1662129899900235264 +1662129899945236224 +1662129899993237248 +1662129900041238272 +1662129900083239168 +1662129900137240320 +1662129900188241408 +1662129900233242368 +1662129900284243456 +1662129900329244416 +1662129900371245312 +1662129900410246144 +1662129900449246976 +1662129900497248000 +1662129900539248896 +1662129900584249856 +1662129900635250944 +1662129900683251968 +1662129900725252864 +1662129900770253824 +1662129900821254912 +1662129900863255808 +1662129900905256704 +1662129900956257792 +1662129900998258688 +1662129901040259584 +1662129901082260480 +1662129901136261632 +1662129901178262528 +1662129901217263360 +1662129901262264320 +1662129901304265216 +1662129901352266240 +1662129901403267328 +1662129901448268288 +1662129901493269248 +1662129901535270144 +1662129901577271040 +1662129901631272192 +1662129901676273152 +1662129901715273984 +1662129901760274944 +1662129901799275776 +1662129901844276736 +1662129901886277632 +1662129901928278528 +1662129901973279488 +1662129902015280384 +1662129902057281280 +1662129902099282176 +1662129902141283072 +1662129902183283968 +1662129902225284864 +1662129902270285824 +1662129902318286848 +1662129902363287808 +1662129902408288768 +1662129902459289856 +1662129902507290880 +1662129902555291904 +1662129902597292800 +1662129902651293952 +1662129902696294912 +1662129902738295808 +1662129902789296896 +1662129902831297792 +1662129902882298880 +1662129902936300032 +1662129902978300928 +1662129903020301824 +1662129903062302720 +1662129903110303744 +1662129903155304704 +1662129903197305600 +1662129903239306496 +1662129903281307392 +1662129903323308288 +1662129903365309184 +1662129903410310144 +1662129903455311104 +1662129903494311936 +1662129903536312832 +1662129903578313728 +1662129903617314560 +1662129903662315520 +1662129903704316416 +1662129903749317376 +1662129903791318272 +1662129903833319168 +1662129903875320064 +1662129903920321024 +1662129903962321920 +1662129904019323136 +1662129904061324032 +1662129904106324992 +1662129904151325952 +1662129904199326976 +1662129904241327872 +1662129904289328896 +1662129904331329792 +1662129904379330816 +1662129904421331712 +1662129904463332608 +1662129904505333504 +1662129904547334400 +1662129904592335360 +1662129904634336256 +1662129904679337216 +1662129904721338112 +1662129904766339072 +1662129904805339904 +1662129904847340800 +1662129904889341696 +1662129904931342592 +1662129904976343552 +1662129905021344512 +1662129905063345408 +1662129905105346304 +1662129905156347392 +1662129905195348224 +1662129905231348992 +1662129905276349952 +1662129905318350848 +1662129905363351808 +1662129905405352704 +1662129905450353664 +1662129905492354560 +1662129905537355520 +1662129905591356672 +1662129905633357568 +1662129905687358720 +1662129905738359808 +1662129905780360704 +1662129905825361664 +1662129905867362560 +1662129905918363648 +1662129905960364544 +1662129906005365504 +1662129906047366400 +1662129906089367296 +1662129906131368192 +1662129906176369152 +1662129906224370176 +1662129906266371072 +1662129906311372032 +1662129906362373120 +1662129906404374016 +1662129906449374976 +1662129906494375936 +1662129906536376832 +1662129906578377728 +1662129906623378688 +1662129906668379648 +1662129906707380480 +1662129906749381376 +1662129906803382528 +1662129906845383424 +1662129906887384320 +1662129906932385280 +1662129906974386176 +1662129907019387136 +1662129907064388096 +1662129907106388992 +1662129907151389952 +1662129907196390912 +1662129907238391808 +1662129907286392832 +1662129907331393792 +1662129907370394624 +1662129907412395520 +1662129907454396416 +1662129907499397376 +1662129907541398272 +1662129907583399168 +1662129907625400064 +1662129907670401024 +1662129907712401920 +1662129907760402944 +1662129907811404032 +1662129907853404928 +1662129907898405888 +1662129907937406720 +1662129907982407680 +1662129908027408640 +1662129908072409600 +1662129908123410688 +1662129908168411648 +1662129908216412672 +1662129908258413568 +1662129908303414528 +1662129908345415424 +1662129908387416320 +1662129908441417472 +1662129908498418688 +1662129908549419776 +1662129908591420672 +1662129908639421696 +1662129908687422720 +1662129908729423616 +1662129908771424512 +1662129908816425472 +1662129908858426368 +1662129908915427584 +1662129908960428544 +1662129909005429504 +1662129909050430464 +1662129909095431424 +1662129909140432384 +1662129909179433216 +1662129909221434112 +1662129909266435072 +1662129909305435904 +1662129909347436800 +1662129909392437760 +1662129909434438656 +1662129909479439616 +1662129909521440512 +1662129909572441600 +1662129909611442432 +1662129909653443328 +1662129909698444288 +1662129909740445184 +1662129909782446080 +1662129909824446976 +1662129909866447872 +1662129909905448704 +1662129909959449856 +1662129910001450752 +1662129910049451776 +1662129910091452672 +1662129910136453632 +1662129910181454592 +1662129910223455488 +1662129910265456384 +1662129910313457408 +1662129910364458496 +1662129910409459456 +1662129910448460288 +1662129910496461312 +1662129910541462272 +1662129910589463296 +1662129910634464256 +1662129910679465216 +1662129910718466048 +1662129910760466944 +1662129910808467968 +1662129910850468864 +1662129910892469760 +1662129910934470656 +1662129910985471744 +1662129911030472704 +1662129911072473600 +1662129911114474496 +1662129911162475520 +1662129911204476416 +1662129911255477504 +1662129911306478592 +1662129911348479488 +1662129911390480384 +1662129911429481216 +1662129911474482176 +1662129911519483136 +1662129911561484032 +1662129911606484992 +1662129911651485952 +1662129911693486848 +1662129911732487680 +1662129911774488576 +1662129911828489728 +1662129911876490752 +1662129911924491776 +1662129911975492864 +1662129912020493824 +1662129912062494720 +1662129912107495680 +1662129912155496704 +1662129912197497600 +1662129912239498496 +1662129912281499392 +1662129912326500352 +1662129912368501248 +1662129912413502208 +1662129912452503040 +1662129912497504000 +1662129912539504896 +1662129912584505856 +1662129912626506752 +1662129912671507712 +1662129912710508544 +1662129912755509504 +1662129912797510400 +1662129912839511296 +1662129912881512192 +1662129912926513152 +1662129912974514176 +1662129913019515136 +1662129913067516160 +1662129913121517312 +1662129913169518336 +1662129913211519232 +1662129913253520128 +1662129913301521152 +1662129913349522176 +1662129913391523072 +1662129913436524032 +1662129913484525056 +1662129913529526016 +1662129913574526976 +1662129913616527872 +1662129913667528960 +1662129913709529856 +1662129913751530752 +1662129913793531648 +1662129913844532736 +1662129913889533696 +1662129913931534592 +1662129913979535616 +1662129914030536704 +1662129914078537728 +1662129914123538688 +1662129914168539648 +1662129914219540736 +1662129914267541760 +1662129914318542848 +1662129914363543808 +1662129914411544832 +1662129914453545728 +1662129914495546624 +1662129914540547584 +1662129914588548608 +1662129914633549568 +1662129914681550592 +1662129914729551616 +1662129914777552640 +1662129914825553664 +1662129914867554560 +1662129914909555456 +1662129914960556544 +1662129915002557440 +1662129915047558400 +1662129915089559296 +1662129915134560256 +1662129915176561152 +1662129915218562048 +1662129915260562944 +1662129915302563840 +1662129915353564928 +1662129915395565824 +1662129915440566784 +1662129915485567744 +1662129915533568768 +1662129915575569664 +1662129915617570560 +1662129915659571456 +1662129915704572416 +1662129915752573440 +1662129915797574400 +1662129915839575296 +1662129915881576192 +1662129915929577216 +1662129915971578112 +1662129916016579072 +1662129916067580160 +1662129916118581248 +1662129916160582144 +1662129916205583104 +1662129916244583936 +1662129916295585024 +1662129916349586176 +1662129916394587136 +1662129916442588160 +1662129916487589120 +1662129916535590144 +1662129916586591232 +1662129916631592192 +1662129916673593088 +1662129916721594112 +1662129916766595072 +1662129916811596032 +1662129916868597248 +1662129916913598208 +1662129916958599168 +1662129917000600064 +1662129917051601152 +1662129917096602112 +1662129917147603200 +1662129917192604160 +1662129917234605056 +1662129917276605952 +1662129917318606848 +1662129917360607744 +1662129917402608640 +1662129917450609664 +1662129917504610816 +1662129917549611776 +1662129917594612736 +1662129917639613696 +1662129917681614592 +1662129917732615680 +1662129917780616704 +1662129917825617664 +1662129917873618688 +1662129917921619712 +1662129917960620544 +1662129918005621504 +1662129918044622336 +1662129918089623296 +1662129918137624320 +1662129918182625280 +1662129918239626496 +1662129918278627328 +1662129918320628224 +1662129918362629120 +1662129918407630080 +1662129918455631104 +1662129918506632192 +1662129918554633216 +1662129918596634112 +1662129918641635072 +1662129918692636160 +1662129918740637184 +1662129918782638080 +1662129918824638976 +1662129918869639936 +1662129918917640960 +1662129918968642048 +1662129919013643008 +1662129919055643904 +1662129919100644864 +1662129919145645824 +1662129919187646720 +1662129919226647552 +1662129919280648704 +1662129919325649664 +1662129919367650560 +1662129919415651584 +1662129919463652608 +1662129919505653504 +1662129919556654592 +1662129919601655552 +1662129919649656576 +1662129919694657536 +1662129919736658432 +1662129919781659392 +1662129919823660288 +1662129919865661184 +1662129919910662144 +1662129919952663040 +1662129919991663872 +1662129920033664768 +1662129920081665792 +1662129920126666752 +1662129920168667648 +1662129920219668736 +1662129920261669632 +1662129920303670528 +1662129920348671488 +1662129920396672512 +1662129920444673536 +1662129920483674368 +1662129920534675456 +1662129920582676480 +1662129920627677440 +1662129920669678336 +1662129920711679232 +1662129920753680128 +1662129920798681088 +1662129920846682112 +1662129920891683072 +1662129920933683968 +1662129920975684864 +1662129921020685824 +1662129921062686720 +1662129921107687680 +1662129921149688576 +1662129921191689472 +1662129921233690368 +1662129921278691328 +1662129921329692416 +1662129921368693248 +1662129921410694144 +1662129921461695232 +1662129921506696192 +1662129921551697152 +1662129921593698048 +1662129921635698944 +1662129921677699840 +1662129921728700928 +1662129921773701888 +1662129921812702720 +1662129921854703616 +1662129921893704448 +1662129921941705472 +1662129921986706432 +1662129922028707328 +1662129922070708224 +1662129922115709184 +1662129922157710080 +1662129922202711040 +1662129922253712128 +1662129922298713088 +1662129922340713984 +1662129922391715072 +1662129922442716160 +1662129922490717184 +1662129922541718272 +1662129922583719168 +1662129922625720064 +1662129922670721024 +1662129922715721984 +1662129922757722880 +1662129922808723968 +1662129922850724864 +1662129922892725760 +1662129922937726720 +1662129922982727680 +1662129923027728640 +1662129923069729536 +1662129923111730432 +1662129923153731328 +1662129923201732352 +1662129923252733440 +1662129923297734400 +1662129923345735424 +1662129923396736512 +1662129923441737472 +1662129923483738368 +1662129923528739328 +1662129923570740224 +1662129923612741120 +1662129923657742080 +1662129923696742912 +1662129923738743808 +1662129923786744832 +1662129923834745856 +1662129923879746816 +1662129923930747904 +1662129923981748992 +1662129924020749824 +1662129924062750720 +1662129924101751552 +1662129924146752512 +1662129924200753664 +1662129924239754496 +1662129924287755520 +1662129924329756416 +1662129924368757248 +1662129924413758208 +1662129924461759232 +1662129924503760128 +1662129924545761024 +1662129924593762048 +1662129924641763072 +1662129924683763968 +1662129924725764864 +1662129924776765952 +1662129924827767040 +1662129924869767936 +1662129924914768896 +1662129924959769856 +1662129925001770752 +1662129925043771648 +1662129925085772544 +1662129925127773440 +1662129925172774400 +1662129925217775360 +1662129925259776256 +1662129925298777088 +1662129925343778048 +1662129925385778944 +1662129925430779904 +1662129925469780736 +1662129925511781632 +1662129925559782656 +1662129925607783680 +1662129925652784640 +1662129925697785600 +1662129925748786688 +1662129925790787584 +1662129925835788544 +1662129925883789568 +1662129925925790464 +1662129925970791424 +1662129926012792320 +1662129926054793216 +1662129926096794112 +1662129926138795008 +1662129926180795904 +1662129926225796864 +1662129926267797760 +1662129926312798720 +1662129926351799552 +1662129926393800448 +1662129926438801408 +1662129926489802496 +1662129926537803520 +1662129926579804416 +1662129926621805312 +1662129926675806464 +1662129926720807424 +1662129926762808320 +1662129926807809280 +1662129926852810240 +1662129926900811264 +1662129926951812352 +1662129926996813312 +1662129927044814336 +1662129927095815424 +1662129927146816512 +1662129927188817408 +1662129927233818368 +1662129927275819264 +1662129927320820224 +1662129927362821120 +1662129927407822080 +1662129927455823104 +1662129927497824000 +1662129927542824960 +1662129927587825920 +1662129927632826880 +1662129927680827904 +1662129927728828928 +1662129927779830016 +1662129927833831168 +1662129927878832128 +1662129927920833024 +1662129927962833920 +1662129928007834880 +1662129928049835776 +1662129928103836928 +1662129928145837824 +1662129928187838720 +1662129928229839616 +1662129928271840512 +1662129928316841472 +1662129928364842496 +1662129928409843456 +1662129928457844480 +1662129928493845248 +1662129928544846336 +1662129928586847232 +1662129928631848192 +1662129928676849152 +1662129928724850176 +1662129928763851008 +1662129928808851968 +1662129928847852800 +1662129928892853760 +1662129928940854784 +1662129928982855680 +1662129929024856576 +1662129929066857472 +1662129929108858368 +1662129929150859264 +1662129929195860224 +1662129929237861120 +1662129929279862016 +1662129929321862912 +1662129929363863808 +1662129929402864640 +1662129929447865600 +1662129929498866688 +1662129929540867584 +1662129929582868480 +1662129929627869440 +1662129929681870592 +1662129929729871616 +1662129929780872704 +1662129929825873664 +1662129929867874560 +1662129929918875648 +1662129929963876608 +1662129930008877568 +1662129930050878464 +1662129930092879360 +1662129930134880256 +1662129930182881280 +1662129930227882240 +1662129930269883136 +1662129930317884160 +1662129930362885120 +1662129930413886208 +1662129930458887168 +1662129930503888128 +1662129930551889152 +1662129930593890048 +1662129930635890944 +1662129930677891840 +1662129930719892736 +1662129930767893760 +1662129930818894848 +1662129930869895936 +1662129930914896896 +1662129930965897984 +1662129931010898944 +1662129931052899840 +1662129931100900864 +1662129931142901760 +1662129931184902656 +1662129931223903488 +1662129931265904384 +1662129931307905280 +1662129931346906112 +1662129931388907008 +1662129931433907968 +1662129931478908928 +1662129931526909952 +1662129931571910912 +1662129931619911936 +1662129931670913024 +1662129931721914112 +1662129931766915072 +1662129931820916224 +1662129931862917120 +1662129931910918144 +1662129931952919040 +1662129931997920000 +1662129932042920960 +1662129932084921856 +1662129932132922880 +1662129932177923840 +1662129932225924864 +1662129932267925760 +1662129932315926784 +1662129932363927808 +1662129932405928704 +1662129932447929600 +1662129932489930496 +1662129932537931520 +1662129932579932416 +1662129932621933312 +1662129932666934272 +1662129932711935232 +1662129932756936192 +1662129932807937280 +1662129932846938112 +1662129932885938944 +1662129932933939968 +1662129932984941056 +1662129933029942016 +1662129933068942848 +1662129933113943808 +1662129933155944704 +1662129933203945728 +1662129933245946624 +1662129933284947456 +1662129933326948352 +1662129933371949312 +1662129933416950272 +1662129933464951296 +1662129933506952192 +1662129933551953152 +1662129933593954048 +1662129933635954944 +1662129933686956032 +1662129933731956992 +1662129933773957888 +1662129933821958912 +1662129933863959808 +1662129933908960768 +1662129933956961792 +1662129933998962688 +1662129934040963584 +1662129934085964544 +1662129934130965504 +1662129934181966592 +1662129934226967552 +1662129934268968448 +1662129934313969408 +1662129934364970496 +1662129934409971456 +1662129934451972352 +1662129934508973568 +1662129934556974592 +1662129934604975616 +1662129934646976512 +1662129934688977408 +1662129934736978432 +1662129934778979328 +1662129934820980224 +1662129934862981120 +1662129934904982016 +1662129934946982912 +1662129934988983808 +1662129935033984768 +1662129935078985728 +1662129935120986624 +1662129935162987520 +1662129935204988416 +1662129935246989312 +1662129935294990336 +1662129935348991488 +1662129935399992576 +1662129935441993472 +1662129935483994368 +1662129935528995328 +1662129935570996224 +1662129935615997184 +1662129935657998080 +1662129935696998912 +1662129935738999808 +1662129935781000704 +1662129935826001664 +1662129935868002560 +1662129935910003456 +1662129935955004416 +1662129936000005376 +1662129936048006400 +1662129936099007488 +1662129936141008384 +1662129936192009472 +1662129936240010496 +1662129936285011456 +1662129936327012352 +1662129936369013248 +1662129936414014208 +1662129936471015424 +1662129936513016320 +1662129936564017408 +1662129936609018368 +1662129936654019328 +1662129936696020224 +1662129936738021120 +1662129936783022080 +1662129936825022976 +1662129936867023872 +1662129936912024832 +1662129936951025664 +1662129936993026560 +1662129937035027456 +1662129937086028544 +1662129937131029504 +1662129937176030464 +1662129937218031360 +1662129937260032256 +1662129937305033216 +1662129937353034240 +1662129937395035136 +1662129937437036032 +1662129937479036928 +1662129937524037888 +1662129937569038848 +1662129937608039680 +1662129937653040640 +1662129937701041664 +1662129937752042752 +1662129937797043712 +1662129937839044608 +1662129937881045504 +1662129937923046400 +1662129937974047488 +1662129938019048448 +1662129938073049600 +1662129938118050560 +1662129938169051648 +1662129938211052544 +1662129938259053568 +1662129938304054528 +1662129938349055488 +1662129938391056384 +1662129938436057344 +1662129938484058368 +1662129938532059392 +1662129938574060288 +1662129938619061248 +1662129938661062144 +1662129938703063040 +1662129938745063936 +1662129938787064832 +1662129938832065792 +1662129938871066624 +1662129938913067520 +1662129938961068544 +1662129939006069504 +1662129939048070400 +1662129939096071424 +1662129939135072256 +1662129939186073344 +1662129939231074304 +1662129939273075200 +1662129939315076096 +1662129939360077056 +1662129939408078080 +1662129939450078976 +1662129939492079872 +1662129939534080768 +1662129939579081728 +1662129939621082624 +1662129939669083648 +1662129939714084608 +1662129939759085568 +1662129939804086528 +1662129939843087360 +1662129939888088320 +1662129939933089280 +1662129939975090176 +1662129940017091072 +1662129940062092032 +1662129940107092992 +1662129940149093888 +1662129940191094784 +1662129940236095744 +1662129940275096576 +1662129940317097472 +1662129940359098368 +1662129940404099328 +1662129940452100352 +1662129940500101376 +1662129940539102208 +1662129940581103104 +1662129940629104128 +1662129940671105024 +1662129940716105984 +1662129940764107008 +1662129940812108032 +1662129940854108928 +1662129940896109824 +1662129940938110720 +1662129940980111616 +1662129941019112448 +1662129941061113344 +1662129941103114240 +1662129941148115200 +1662129941187116032 +1662129941235117056 +1662129941277117952 +1662129941322118912 +1662129941364119808 +1662129941406120704 +1662129941448121600 +1662129941496122624 +1662129941541123584 +1662129941586124544 +1662129941628125440 +1662129941685126656 +1662129941733127680 +1662129941778128640 +1662129941823129600 +1662129941865130496 +1662129941910131456 +1662129941967132672 +1662129942012133632 +1662129942051134464 +1662129942093135360 +1662129942135136256 +1662129942174137088 +1662129942216137984 +1662129942258138880 +1662129942297139712 +1662129942339140608 +1662129942390141696 +1662129942429142528 +1662129942471143424 +1662129942513144320 +1662129942558145280 +1662129942600146176 +1662129942639147008 +1662129942681147904 +1662129942723148800 +1662129942771149824 +1662129942810150656 +1662129942864151808 +1662129942906152704 +1662129942957153792 +1662129943005154816 +1662129943047155712 +1662129943086156544 +1662129943128157440 +1662129943167158272 +1662129943215159296 +1662129943257160192 +1662129943299161088 +1662129943344162048 +1662129943395163136 +1662129943440164096 +1662129943482164992 +1662129943527165952 +1662129943578167040 +1662129943623168000 +1662129943671169024 +1662129943710169856 +1662129943752170752 +1662129943797171712 +1662129943845172736 +1662129943893173760 +1662129943935174656 +1662129943977175552 +1662129944022176512 +1662129944064177408 +1662129944109178368 +1662129944151179264 +1662129944199180288 +1662129944247181312 +1662129944295182336 +1662129944337183232 +1662129944379184128 +1662129944421185024 +1662129944466185984 +1662129944511186944 +1662129944553187840 +1662129944595188736 +1662129944643189760 +1662129944685190656 +1662129944730191616 +1662129944772192512 +1662129944814193408 +1662129944859194368 +1662129944904195328 +1662129944946196224 +1662129944997197312 +1662129945039198208 +1662129945087199232 +1662129945135200256 +1662129945177201152 +1662129945222202112 +1662129945273203200 +1662129945324204288 +1662129945375205376 +1662129945426206464 +1662129945468207360 +1662129945510208256 +1662129945558209280 +1662129945609210368 +1662129945654211328 +1662129945696212224 +1662129945738213120 +1662129945783214080 +1662129945825214976 +1662129945873216000 +1662129945927217152 +1662129945966217984 +1662129946014219008 +1662129946059219968 +1662129946107220992 +1662129946155222016 +1662129946197222912 +1662129946242223872 +1662129946290224896 +1662129946332225792 +1662129946377226752 +1662129946425227776 +1662129946479228928 +1662129946521229824 +1662129946563230720 +1662129946608231680 +1662129946650232576 +1662129946692233472 +1662129946737234432 +1662129946782235392 +1662129946824236288 +1662129946866237184 +1662129946911238144 +1662129946956239104 +1662129946998240000 +1662129947040240896 +1662129947082241792 +1662129947124242688 +1662129947169243648 +1662129947211244544 +1662129947250245376 +1662129947292246272 +1662129947346247424 +1662129947391248384 +1662129947433249280 +1662129947478250240 +1662129947526251264 +1662129947574252288 +1662129947619253248 +1662129947667254272 +1662129947709255168 +1662129947754256128 +1662129947796257024 +1662129947841257984 +1662129947895259136 +1662129947940260096 +1662129947982260992 +1662129948033262080 +1662129948084263168 +1662129948129264128 +1662129948174265088 +1662129948219266048 +1662129948261266944 +1662129948312268032 +1662129948360269056 +1662129948402269952 +1662129948441270784 +1662129948486271744 +1662129948528272640 +1662129948570273536 +1662129948618274560 +1662129948660275456 +1662129948702276352 +1662129948750277376 +1662129948798278400 +1662129948840279296 +1662129948885280256 +1662129948927281152 +1662129948969282048 +1662129949011282944 +1662129949056283904 +1662129949095284736 +1662129949137285632 +1662129949185286656 +1662129949230287616 +1662129949272288512 +1662129949314289408 +1662129949356290304 +1662129949401291264 +1662129949443292160 +1662129949488293120 +1662129949533294080 +1662129949575294976 +1662129949617295872 +1662129949668296960 +1662129949710297856 +1662129949758298880 +1662129949800299776 +1662129949842300672 +1662129949884301568 +1662129949929302528 +1662129949977303552 +1662129950022304512 +1662129950067305472 +1662129950106306304 +1662129950148307200 +1662129950193308160 +1662129950235309056 +1662129950283310080 +1662129950328311040 +1662129950370311936 +1662129950415312896 +1662129950463313920 +1662129950505314816 +1662129950559315968 +1662129950601316864 +1662129950661318144 +1662129950706319104 +1662129950763320320 +1662129950808321280 +1662129950850322176 +1662129950892323072 +1662129950931323904 +1662129950982324992 +1662129951027325952 +1662129951069326848 +1662129951111327744 +1662129951156328704 +1662129951198329600 +1662129951240330496 +1662129951291331584 +1662129951333332480 +1662129951384333568 +1662129951429334528 +1662129951471335424 +1662129951516336384 +1662129951561337344 +1662129951606338304 +1662129951648339200 +1662129951693340160 +1662129951735341056 +1662129951780342016 +1662129951825342976 +1662129951867343872 +1662129951909344768 +1662129951954345728 +1662129951996346624 +1662129952044347648 +1662129952086348544 +1662129952128349440 +1662129952179350528 +1662129952221351424 +1662129952263352320 +1662129952305353216 +1662129952350354176 +1662129952386354944 +1662129952434355968 +1662129952479356928 +1662129952524357888 +1662129952572358912 +1662129952617359872 +1662129952665360896 +1662129952707361792 +1662129952752362752 +1662129952797363712 +1662129952842364672 +1662129952887365632 +1662129952929366528 +1662129952971367424 +1662129953016368384 +1662129953058369280 +1662129953106370304 +1662129953154371328 +1662129953199372288 +1662129953247373312 +1662129953298374400 +1662129953340375296 +1662129953394376448 +1662129953436377344 +1662129953475378176 +1662129953514379008 +1662129953568380160 +1662129953613381120 +1662129953655382016 +1662129953700382976 +1662129953739383808 +1662129953781384704 +1662129953826385664 +1662129953865386496 +1662129953907387392 +1662129953955388416 +1662129954000389376 +1662129954051390464 +1662129954093391360 +1662129954138392320 +1662129954183393280 +1662129954225394176 +1662129954267395072 +1662129954306395904 +1662129954354396928 +1662129954399397888 +1662129954441398784 +1662129954489399808 +1662129954531400704 +1662129954579401728 +1662129954630402816 +1662129954672403712 +1662129954714404608 +1662129954756405504 +1662129954798406400 +1662129954840407296 +1662129954888408320 +1662129954930409216 +1662129954975410176 +1662129955023411200 +1662129955071412224 +1662129955116413184 +1662129955158414080 +1662129955206415104 +1662129955254416128 +1662129955299417088 +1662129955344418048 +1662129955386418944 +1662129955428419840 +1662129955473420800 +1662129955518421760 +1662129955560422656 +1662129955608423680 +1662129955659424768 +1662129955701425664 +1662129955746426624 +1662129955800427776 +1662129955845428736 +1662129955887429632 +1662129955929430528 +1662129955968431360 +1662129956010432256 +1662129956052433152 +1662129956094434048 +1662129956139435008 +1662129956184435968 +1662129956226436864 +1662129956268437760 +1662129956313438720 +1662129956358439680 +1662129956406440704 +1662129956445441536 +1662129956490442496 +1662129956535443456 +1662129956583444480 +1662129956634445568 +1662129956676446464 +1662129956718447360 +1662129956760448256 +1662129956802449152 +1662129956850450176 +1662129956889451008 +1662129956931451904 +1662129956973452800 +1662129957015453696 +1662129957057454592 +1662129957102455552 +1662129957150456576 +1662129957198457600 +1662129957240458496 +1662129957288459520 +1662129957330460416 +1662129957378461440 +1662129957420462336 +1662129957462463232 +1662129957510464256 +1662129957555465216 +1662129957597466112 +1662129957642467072 +1662129957687468032 +1662129957729468928 +1662129957777469952 +1662129957825470976 +1662129957867471872 +1662129957912472832 +1662129957954473728 +1662129957999474688 +1662129958044475648 +1662129958089476608 +1662129958131477504 +1662129958191478784 +1662129958233479680 +1662129958278480640 +1662129958320481536 +1662129958362482432 +1662129958407483392 +1662129958452484352 +1662129958500485376 +1662129958545486336 +1662129958581487104 +1662129958626488064 +1662129958668488960 +1662129958710489856 +1662129958752490752 +1662129958797491712 +1662129958842492672 +1662129958884493568 +1662129958929494528 +1662129958971495424 +1662129959013496320 +1662129959055497216 +1662129959100498176 +1662129959142499072 +1662129959187500032 +1662129959229500928 +1662129959271501824 +1662129959313502720 +1662129959355503616 +1662129959397504512 +1662129959448505600 +1662129959499506688 +1662129959544507648 +1662129959589508608 +1662129959634509568 +1662129959679510528 +1662129959721511424 +1662129959766512384 +1662129959817513472 +1662129959859514368 +1662129959910515456 +1662129959955516416 +1662129959997517312 +1662129960039518208 +1662129960081519104 +1662129960123520000 +1662129960174521088 +1662129960219522048 +1662129960267523072 +1662129960309523968 +1662129960363525120 +1662129960405526016 +1662129960447526912 +1662129960489527808 +1662129960531528704 +1662129960576529664 +1662129960624530688 +1662129960666531584 +1662129960708532480 +1662129960750533376 +1662129960792534272 +1662129960831535104 +1662129960876536064 +1662129960921537024 +1662129960966537984 +1662129961005538816 +1662129961047539712 +1662129961092540672 +1662129961134541568 +1662129961179542528 +1662129961221543424 +1662129961263544320 +1662129961305545216 +1662129961350546176 +1662129961401547264 +1662129961443548160 +1662129961482548992 +1662129961524549888 +1662129961572550912 +1662129961614551808 +1662129961656552704 +1662129961698553600 +1662129961740554496 +1662129961779555328 +1662129961818556160 +1662129961860557056 +1662129961908558080 +1662129961953559040 +1662129961995559936 +1662129962037560832 +1662129962082561792 +1662129962124562688 +1662129962163563520 +1662129962205564416 +1662129962247565312 +1662129962289566208 +1662129962334567168 +1662129962385568256 +1662129962445569536 +1662129962496570624 +1662129962538571520 +1662129962583572480 +1662129962628573440 +1662129962676574464 +1662129962715575296 +1662129962757576192 +1662129962802577152 +1662129962847578112 +1662129962892579072 +1662129962943580160 +1662129962988581120 +1662129963039582208 +1662129963081583104 +1662129963126584064 +1662129963174585088 +1662129963216585984 +1662129963264587008 +1662129963306587904 +1662129963348588800 +1662129963390589696 +1662129963435590656 +1662129963477591552 +1662129963519592448 +1662129963561593344 +1662129963603594240 +1662129963648595200 +1662129963687596032 +1662129963729596928 +1662129963771597824 +1662129963822598912 +1662129963867599872 +1662129963909600768 +1662129963954601728 +1662129964005602816 +1662129964047603712 +1662129964101604864 +1662129964143605760 +1662129964188606720 +1662129964230607616 +1662129964275608576 +1662129964317609472 +1662129964359610368 +1662129964401611264 +1662129964446612224 +1662129964497613312 +1662129964539614208 +1662129964581615104 +1662129964626616064 +1662129964671617024 +1662129964713617920 +1662129964755618816 +1662129964800619776 +1662129964842620672 +1662129964887621632 +1662129964929622528 +1662129964977623552 +1662129965019624448 +1662129965067625472 +1662129965112626432 +1662129965157627392 +1662129965199628288 +1662129965253629440 +1662129965295630336 +1662129965334631168 +1662129965382632192 +1662129965427633152 +1662129965472634112 +1662129965514635008 +1662129965559635968 +1662129965604636928 +1662129965649637888 +1662129965694638848 +1662129965736639744 +1662129965784640768 +1662129965829641728 +1662129965880642816 +1662129965922643712 +1662129965964644608 +1662129966012645632 +1662129966054646528 +1662129966093647360 +1662129966138648320 +1662129966183649280 +1662129966228650240 +1662129966273651200 +1662129966324652288 +1662129966375653376 +1662129966420654336 +1662129966471655424 +1662129966516656384 +1662129966561657344 +1662129966606658304 +1662129966651659264 +1662129966696660224 +1662129966738661120 +1662129966780662016 +1662129966828663040 +1662129966870663936 +1662129966912664832 +1662129966954665728 +1662129966996666624 +1662129967041667584 +1662129967086668544 +1662129967128669440 +1662129967170670336 +1662129967209671168 +1662129967257672192 +1662129967296673024 +1662129967338673920 +1662129967386674944 +1662129967425675776 +1662129967467676672 +1662129967518677760 +1662129967560678656 +1662129967602679552 +1662129967647680512 +1662129967689681408 +1662129967731682304 +1662129967773683200 +1662129967818684160 +1662129967860685056 +1662129967905686016 +1662129967947686912 +1662129967992687872 +1662129968037688832 +1662129968088689920 +1662129968127690752 +1662129968172691712 +1662129968220692736 +1662129968271693824 +1662129968313694720 +1662129968355695616 +1662129968394696448 +1662129968433697280 +1662129968475698176 +1662129968517699072 +1662129968571700224 +1662129968622701312 +1662129968673702400 +1662129968715703296 +1662129968757704192 +1662129968805705216 +1662129968850706176 +1662129968895707136 +1662129968937708032 +1662129968979708928 +1662129969021709824 +1662129969063710720 +1662129969105711616 +1662129969162712832 +1662129969201713664 +1662129969252714752 +1662129969297715712 +1662129969339716608 +1662129969381717504 +1662129969423718400 +1662129969465719296 +1662129969513720320 +1662129969555721216 +1662129969600722176 +1662129969648723200 +1662129969690724096 +1662129969738725120 +1662129969783726080 +1662129969825726976 +1662129969870727936 +1662129969918728960 +1662129969966729984 +1662129970008730880 +1662129970059731968 +1662129970104732928 +1662129970149733888 +1662129970194734848 +1662129970242735872 +1662129970284736768 +1662129970335737856 +1662129970377738752 +1662129970419739648 +1662129970461740544 +1662129970503741440 +1662129970545742336 +1662129970590743296 +1662129970635744256 +1662129970677745152 +1662129970719746048 +1662129970764747008 +1662129970806747904 +1662129970851748864 +1662129970896749824 +1662129970941750784 +1662129970995751936 +1662129971043752960 +1662129971088753920 +1662129971136754944 +1662129971178755840 +1662129971220756736 +1662129971265757696 +1662129971313758720 +1662129971355759616 +1662129971403760640 +1662129971445761536 +1662129971496762624 +1662129971538763520 +1662129971583764480 +1662129971643765760 +1662129971682766592 +1662129971724767488 +1662129971769768448 +1662129971811769344 +1662129971859770368 +1662129971901771264 +1662129971943772160 +1662129971982772992 +1662129972024773888 +1662129972066774784 +1662129972108775680 +1662129972153776640 +1662129972195777536 +1662129972240778496 +1662129972285779456 +1662129972327780352 +1662129972369781248 +1662129972414782208 +1662129972456783104 +1662129972501784064 +1662129972540784896 +1662129972582785792 +1662129972627786752 +1662129972669787648 +1662129972717788672 +1662129972762789632 +1662129972804790528 +1662129972852791552 +1662129972894792448 +1662129972939793408 +1662129972981794304 +1662129973020795136 +1662129973062796032 +1662129973113797120 +1662129973155798016 +1662129973197798912 +1662129973239799808 +1662129973281800704 +1662129973323801600 +1662129973368802560 +1662129973416803584 +1662129973461804544 +1662129973506805504 +1662129973548806400 +1662129973590807296 +1662129973632808192 +1662129973674809088 +1662129973722810112 +1662129973773811200 +1662129973818812160 +1662129973866813184 +1662129973911814144 +1662129973953815040 +1662129973998816000 +1662129974040816896 +1662129974082817792 +1662129974124818688 +1662129974169819648 +1662129974211820544 +1662129974253821440 +1662129974295822336 +1662129974349823488 +1662129974391824384 +1662129974436825344 +1662129974481826304 +1662129974523827200 +1662129974580828416 +1662129974622829312 +1662129974667830272 +1662129974709831168 +1662129974754832128 +1662129974799833088 +1662129974844834048 +1662129974886834944 +1662129974940836096 +1662129974985837056 +1662129975027837952 +1662129975072838912 +1662129975114839808 +1662129975156840704 +1662129975201841664 +1662129975249842688 +1662129975291843584 +1662129975336844544 +1662129975384845568 +1662129975426846464 +1662129975471847424 +1662129975510848256 +1662129975561849344 +1662129975606850304 +1662129975657851392 +1662129975702852352 +1662129975747853312 +1662129975789854208 +1662129975834855168 +1662129975873856000 +1662129975918856960 +1662129975972858112 +1662129976017859072 +1662129976065860096 +1662129976110861056 +1662129976152861952 +1662129976197862912 +1662129976245863936 +1662129976287864832 +1662129976329865728 +1662129976377866752 +1662129976422867712 +1662129976473868800 +1662129976512869632 +1662129976557870592 +1662129976602871552 +1662129976644872448 +1662129976689873408 +1662129976731874304 +1662129976770875136 +1662129976812876032 +1662129976857876992 +1662129976896877824 +1662129976938878720 +1662129976983879680 +1662129977025880576 +1662129977070881536 +1662129977115882496 +1662129977154883328 +1662129977199884288 +1662129977250885376 +1662129977295886336 +1662129977334887168 +1662129977373888000 +1662129977415888896 +1662129977457889792 +1662129977499890688 +1662129977541891584 +1662129977583892480 +1662129977625893376 +1662129977670894336 +1662129977715895296 +1662129977757896192 +1662129977799897088 +1662129977844898048 +1662129977886898944 +1662129977937900032 +1662129977982900992 +1662129978030902016 +1662129978072902912 +1662129978111903744 +1662129978153904640 +1662129978201905664 +1662129978249906688 +1662129978297907712 +1662129978339908608 +1662129978381909504 +1662129978426910464 +1662129978477911552 +1662129978525912576 +1662129978567913472 +1662129978606914304 +1662129978648915200 +1662129978690916096 +1662129978732916992 +1662129978777917952 +1662129978822918912 +1662129978870919936 +1662129978921921024 +1662129978966921984 +1662129979014923008 +1662129979062924032 +1662129979104924928 +1662129979146925824 +1662129979188926720 +1662129979230927616 +1662129979272928512 +1662129979314929408 +1662129979353930240 +1662129979395931136 +1662129979437932032 +1662129979476932864 +1662129979521933824 +1662129979566934784 +1662129979611935744 +1662129979656936704 +1662129979704937728 +1662129979746938624 +1662129979788939520 +1662129979836940544 +1662129979875941376 +1662129979917942272 +1662129979956943104 +1662129980007944192 +1662129980052945152 +1662129980094946048 +1662129980139947008 +1662129980190948096 +1662129980232948992 +1662129980274949888 +1662129980316950784 +1662129980358951680 +1662129980400952576 +1662129980442953472 +1662129980490954496 +1662129980535955456 +1662129980577956352 +1662129980616957184 +1662129980661958144 +1662129980703959040 +1662129980745959936 +1662129980793960960 +1662129980841961984 +1662129980883962880 +1662129980928963840 +1662129980976964864 +1662129981027965952 +1662129981072966912 +1662129981117967872 +1662129981159968768 +1662129981201969664 +1662129981246970624 +1662129981285971456 +1662129981327972352 +1662129981378973440 +1662129981423974400 +1662129981462975232 +1662129981501976064 +1662129981543976960 +1662129981582977792 +1662129981624978688 +1662129981669979648 +1662129981711980544 +1662129981750981376 +1662129981792982272 +1662129981834983168 +1662129981876984064 +1662129981933985280 +1662129981975986176 +1662129982017987072 +1662129982059987968 +1662129982104988928 +1662129982146989824 +1662129982185990656 +1662129982230991616 +1662129982272992512 +1662129982314993408 +1662129982356994304 +1662129982401995264 +1662129982452996352 +1662129982494997248 +1662129982533998080 +1662129982575998976 +1662129982620999936 +1662129982669000960 +1662129982720002048 +1662129982774003200 +1662129982816004096 +1662129982858004992 +1662129982900005888 +1662129982942006784 +1662129982987007744 +1662129983029008640 +1662129983071009536 +1662129983131010816 +1662129983173011712 +1662129983221012736 +1662129983269013760 +1662129983311014656 +1662129983353015552 +1662129983398016512 +1662129983443017472 +1662129983488018432 +1662129983533019392 +1662129983575020288 +1662129983620021248 +1662129983668022272 +1662129983710023168 +1662129983752024064 +1662129983791024896 +1662129983833025792 +1662129983872026624 +1662129983917027584 +1662129983959028480 +1662129984013029632 +1662129984058030592 +1662129984100031488 +1662129984142032384 +1662129984181033216 +1662129984226034176 +1662129984274035200 +1662129984319036160 +1662129984367037184 +1662129984409038080 +1662129984457039104 +1662129984496039936 +1662129984541040896 +1662129984583041792 +1662129984628042752 +1662129984670043648 +1662129984724044800 +1662129984766045696 +1662129984811046656 +1662129984850047488 +1662129984892048384 +1662129984937049344 +1662129984979050240 +1662129985024051200 +1662129985069052160 +1662129985108052992 +1662129985150053888 +1662129985195054848 +1662129985243055872 +1662129985297057024 +1662129985342057984 +1662129985387058944 +1662129985432059904 +1662129985480060928 +1662129985525061888 +1662129985567062784 +1662129985615063808 +1662129985660064768 +1662129985711065856 +1662129985753066752 +1662129985792067584 +1662129985837068544 +1662129985879069440 +1662129985927070464 +1662129985975071488 +1662129986017072384 +1662129986065073408 +1662129986104074240 +1662129986149075200 +1662129986194076160 +1662129986233076992 +1662129986275077888 +1662129986320078848 +1662129986362079744 +1662129986404080640 +1662129986446081536 +1662129986488082432 +1662129986527083264 +1662129986569084160 +1662129986614085120 +1662129986665086208 +1662129986707087104 +1662129986755088128 +1662129986800089088 +1662129986842089984 +1662129986881090816 +1662129986923091712 +1662129986968092672 +1662129987013093632 +1662129987055094528 +1662129987097095424 +1662129987139096320 +1662129987178097152 +1662129987220098048 +1662129987268099072 +1662129987310099968 +1662129987352100864 +1662129987394101760 +1662129987439102720 +1662129987481103616 +1662129987529104640 +1662129987574105600 +1662129987622106624 +1662129987664107520 +1662129987706108416 +1662129987745109248 +1662129987790110208 +1662129987835111168 +1662129987880112128 +1662129987922113024 +1662129987961113856 +1662129988006114816 +1662129988048115712 +1662129988090116608 +1662129988132117504 +1662129988180118528 +1662129988225119488 +1662129988267120384 +1662129988309121280 +1662129988348122112 +1662129988390123008 +1662129988432123904 +1662129988474124800 +1662129988513125632 +1662129988561126656 +1662129988600127488 +1662129988648128512 +1662129988696129536 +1662129988738130432 +1662129988780131328 +1662129988831132416 +1662129988873133312 +1662129988921134336 +1662129988966135296 +1662129989011136256 +1662129989053137152 +1662129989092137984 +1662129989134138880 +1662129989179139840 +1662129989227140864 +1662129989269141760 +1662129989311142656 +1662129989356143616 +1662129989401144576 +1662129989443145472 +1662129989491146496 +1662129989533147392 +1662129989587148544 +1662129989629149440 +1662129989683150592 +1662129989725151488 +1662129989770152448 +1662129989812153344 +1662129989857154304 +1662129989899155200 +1662129989944156160 +1662129989986157056 +1662129990037158144 +1662129990079159040 +1662129990118159872 +1662129990160160768 +1662129990208161792 +1662129990253162752 +1662129990298163712 +1662129990334164480 +1662129990379165440 +1662129990421166336 +1662129990466167296 +1662129990508168192 +1662129990550169088 +1662129990601170176 +1662129990646171136 +1662129990691172096 +1662129990736173056 +1662129990781174016 +1662129990823174912 +1662129990865175808 +1662129990907176704 +1662129990949177600 +1662129990988178432 +1662129991027179264 +1662129991072180224 +1662129991111181056 +1662129991150181888 +1662129991192182784 +1662129991234183680 +1662129991276184576 +1662129991321185536 +1662129991366186496 +1662129991420187648 +1662129991462188544 +1662129991501189376 +1662129991540190208 +1662129991579191040 +1662129991621191936 +1662129991663192832 +1662129991708193792 +1662129991750194688 +1662129991792195584 +1662129991834196480 +1662129991882197504 +1662129991924198400 +1662129991966199296 +1662129992008200192 +1662129992047201024 +1662129992089201920 +1662129992131202816 +1662129992170203648 +1662129992209204480 +1662129992251205376 +1662129992290206208 +1662129992335207168 +1662129992380208128 +1662129992422209024 +1662129992464209920 +1662129992506210816 +1662129992551211776 +1662129992599212800 +1662129992641213696 +1662129992686214656 +1662129992731215616 +1662129992773216512 +1662129992821217536 +1662129992860218368 +1662129992905219328 +1662129992947220224 +1662129992989221120 +1662129993031222016 +1662129993073222912 +1662129993115223808 +1662129993163224832 +1662129993208225792 +1662129993250226688 +1662129993298227712 +1662129993355228928 +1662129993397229824 +1662129993439230720 +1662129993481231616 +1662129993523232512 +1662129993562233344 +1662129993607234304 +1662129993649235200 +1662129993691236096 +1662129993733236992 +1662129993775237888 +1662129993826238976 +1662129993877240064 +1662129993922241024 +1662129993976242176 +1662129994027243264 +1662129994072244224 +1662129994114245120 +1662129994156246016 +1662129994198246912 +1662129994243247872 +1662129994285248768 +1662129994327249664 +1662129994372250624 +1662129994414251520 +1662129994456252416 +1662129994498253312 +1662129994537254144 +1662129994579255040 +1662129994627256064 +1662129994672257024 +1662129994717257984 +1662129994759258880 +1662129994798259712 +1662129994843260672 +1662129994882261504 +1662129994924262400 +1662129994966263296 +1662129995008264192 +1662129995056265216 +1662129995104266240 +1662129995155267328 +1662129995197268224 +1662129995242269184 +1662129995287270144 +1662129995329271040 +1662129995371271936 +1662129995419272960 +1662129995458273792 +1662129995500274688 +1662129995545275648 +1662129995593276672 +1662129995635277568 +1662129995677278464 +1662129995719279360 +1662129995761280256 +1662129995803281152 +1662129995845282048 +1662129995887282944 +1662129995932283904 +1662129995983284992 +1662129996025285888 +1662129996067286784 +1662129996115287808 +1662129996157288704 +1662129996202289664 +1662129996244290560 +1662129996295291648 +1662129996340292608 +1662129996397293824 +1662129996442294784 +1662129996493295872 +1662129996538296832 +1662129996580297728 +1662129996622298624 +1662129996667299584 +1662129996712300544 +1662129996754301440 +1662129996796302336 +1662129996838303232 +1662129996880304128 +1662129996928305152 +1662129996970306048 +1662129997009306880 +1662129997054307840 +1662129997102308864 +1662129997147309824 +1662129997192310784 +1662129997234311680 +1662129997279312640 +1662129997321313536 +1662129997363314432 +1662129997405315328 +1662129997447316224 +1662129997489317120 +1662129997531318016 +1662129997573318912 +1662129997615319808 +1662129997657320704 +1662129997702321664 +1662129997741322496 +1662129997783323392 +1662129997828324352 +1662129997870325248 +1662129997912326144 +1662129997954327040 +1662129997999328000 +1662129998050329088 +1662129998098330112 +1662129998140331008 +1662129998188332032 +1662129998230332928 +1662129998275333888 +1662129998320334848 +1662129998365335808 +1662129998407336704 +1662129998446337536 +1662129998491338496 +1662129998542339584 +1662129998584340480 +1662129998626341376 +1662129998668342272 +1662129998713343232 +1662129998764344320 +1662129998806345216 +1662129998845346048 +1662129998887346944 +1662129998926347776 +1662129998968348672 +1662129999010349568 +1662129999052350464 +1662129999094351360 +1662129999139352320 +1662129999181353216 +1662129999226354176 +1662129999274355200 +1662129999316356096 +1662129999358356992 +1662129999406358016 +1662129999448358912 +1662129999496359936 +1662129999538360832 +1662129999577361664 +1662129999616362496 +1662129999658363392 +1662129999697364224 +1662129999739365120 +1662129999778365952 +1662129999817366784 +1662129999874368000 +1662129999916368896 +1662129999958369792 +1662130000012370944 +1662130000057371904 +1662130000099372800 +1662130000147373824 +1662130000189374720 +1662130000240375808 +1662130000282376704 +1662130000327377664 +1662130000375378688 +1662130000420379648 +1662130000462380544 +1662130000504381440 +1662130000546382336 +1662130000588383232 +1662130000630384128 +1662130000672385024 +1662130000714385920 +1662130000762386944 +1662130000807387904 +1662130000855388928 +1662130000903389952 +1662130000948390912 +1662130000987391744 +1662130001029392640 +1662130001071393536 +1662130001113394432 +1662130001161395456 +1662130001203396352 +1662130001245397248 +1662130001299398400 +1662130001341399296 +1662130001389400320 +1662130001428401152 +1662130001479402240 +1662130001524403200 +1662130001572404224 +1662130001620405248 +1662130001662406144 +1662130001704407040 +1662130001746407936 +1662130001788408832 +1662130001830409728 +1662130001872410624 +1662130001911411456 +1662130001953412352 +1662130001995413248 +1662130002037414144 +1662130002079415040 +1662130002124416000 +1662130002169416960 +1662130002214417920 +1662130002256418816 +1662130002301419776 +1662130002349420800 +1662130002394421760 +1662130002436422656 +1662130002481423616 +1662130002523424512 +1662130002568425472 +1662130002610426368 +1662130002652427264 +1662130002697428224 +1662130002739429120 +1662130002781430016 +1662130002826430976 +1662130002874432000 +1662130002916432896 +1662130002955433728 +1662130003000434688 +1662130003039435520 +1662130003081436416 +1662130003126437376 +1662130003171438336 +1662130003213439232 +1662130003255440128 +1662130003297441024 +1662130003339441920 +1662130003381442816 +1662130003423443712 +1662130003465444608 +1662130003507445504 +1662130003549446400 +1662130003591447296 +1662130003639448320 +1662130003681449216 +1662130003723450112 +1662130003768451072 +1662130003813452032 +1662130003855452928 +1662130003900453888 +1662130003948454912 +1662130003993455872 +1662130004035456768 +1662130004077457664 +1662130004122458624 +1662130004164459520 +1662130004209460480 +1662130004257461504 +1662130004302462464 +1662130004344463360 +1662130004398464512 +1662130004437465344 +1662130004485466368 +1662130004530467328 +1662130004578468352 +1662130004626469376 +1662130004665470208 +1662130004710471168 +1662130004749472000 +1662130004791472896 +1662130004833473792 +1662130004875474688 +1662130004917475584 +1662130004959476480 +1662130005013477632 +1662130005058478592 +1662130005103479552 +1662130005145480448 +1662130005184481280 +1662130005223482112 +1662130005265483008 +1662130005319484160 +1662130005361485056 +1662130005406486016 +1662130005448486912 +1662130005496487936 +1662130005538488832 +1662130005580489728 +1662130005628490752 +1662130005679491840 +1662130005721492736 +1662130005763493632 +1662130005817494784 +1662130005859495680 +1662130005901496576 +1662130005952497664 +1662130005991498496 +1662130006030499328 +1662130006075500288 +1662130006126501376 +1662130006171502336 +1662130006213503232 +1662130006261504256 +1662130006303505152 +1662130006342505984 +1662130006390507008 +1662130006432507904 +1662130006480508928 +1662130006522509824 +1662130006573510912 +1662130006615511808 +1662130006660512768 +1662130006702513664 +1662130006744514560 +1662130006786515456 +1662130006828516352 +1662130006867517184 +1662130006912518144 +1662130006960519168 +1662130006999520000 +1662130007041520896 +1662130007083521792 +1662130007128522752 +1662130007179523840 +1662130007227524864 +1662130007272525824 +1662130007317526784 +1662130007356527616 +1662130007398528512 +1662130007440529408 +1662130007485530368 +1662130007527531264 +1662130007572532224 +1662130007614533120 +1662130007665534208 +1662130007707535104 +1662130007749536000 +1662130007800537088 +1662130007848538112 +1662130007893539072 +1662130007938540032 +1662130007977540864 +1662130008022541824 +1662130008064542720 +1662130008115543808 +1662130008160544768 +1662130008208545792 +1662130008253546752 +1662130008295547648 +1662130008340548608 +1662130008385549568 +1662130008424550400 +1662130008466551296 +1662130008508552192 +1662130008547553024 +1662130008589553920 +1662130008634554880 +1662130008676555776 +1662130008724556800 +1662130008763557632 +1662130008805558528 +1662130008847559424 +1662130008895560448 +1662130008937561344 +1662130008982562304 +1662130009024563200 +1662130009063564032 +1662130009111565056 +1662130009153565952 +1662130009198566912 +1662130009240567808 +1662130009282568704 +1662130009327569664 +1662130009375570688 +1662130009417571584 +1662130009468572672 +1662130009519573760 +1662130009561574656 +1662130009603575552 +1662130009645576448 +1662130009687577344 +1662130009732578304 +1662130009774579200 +1662130009816580096 +1662130009864581120 +1662130009912582144 +1662130009954583040 +1662130009996583936 +1662130010038584832 +1662130010080585728 +1662130010128586752 +1662130010170587648 +1662130010209588480 +1662130010248589312 +1662130010290590208 +1662130010332591104 +1662130010386592256 +1662130010434593280 +1662130010476594176 +1662130010521595136 +1662130010560595968 +1662130010602596864 +1662130010650597888 +1662130010695598848 +1662130010737599744 +1662130010788600832 +1662130010830601728 +1662130010875602688 +1662130010920603648 +1662130010968604672 +1662130011013605632 +1662130011058606592 +1662130011100607488 +1662130011142608384 +1662130011190609408 +1662130011229610240 +1662130011286611456 +1662130011331612416 +1662130011373613312 +1662130011415614208 +1662130011463615232 +1662130011508616192 +1662130011550617088 +1662130011592617984 +1662130011637618944 +1662130011679619840 +1662130011724620800 +1662130011766621696 +1662130011811622656 +1662130011856623616 +1662130011904624640 +1662130011946625536 +1662130011988626432 +1662130012030627328 +1662130012072628224 +1662130012114629120 +1662130012156630016 +1662130012198630912 +1662130012237631744 +1662130012279632640 +1662130012321633536 +1662130012369634560 +1662130012414635520 +1662130012456636416 +1662130012513637632 +1662130012555638528 +1662130012606639616 +1662130012648640512 +1662130012690641408 +1662130012732642304 +1662130012777643264 +1662130012819644160 +1662130012867645184 +1662130012912646144 +1662130012954647040 +1662130013002648064 +1662130013053649152 +1662130013095650048 +1662130013140651008 +1662130013185651968 +1662130013230652928 +1662130013275653888 +1662130013317654784 +1662130013365655808 +1662130013407656704 +1662130013455657728 +1662130013494658560 +1662130013542659584 +1662130013584660480 +1662130013626661376 +1662130013668662272 +1662130013713663232 +1662130013767664384 +1662130013812665344 +1662130013851666176 +1662130013902667264 +1662130013941668096 +1662130013983668992 +1662130014028669952 +1662130014070670848 +1662130014112671744 +1662130014154672640 +1662130014208673792 +1662130014259674880 +1662130014301675776 +1662130014352676864 +1662130014400677888 +1662130014442678784 +1662130014484679680 +1662130014523680512 +1662130014565681408 +1662130014610682368 +1662130014652683264 +1662130014700684288 +1662130014742685184 +1662130014787686144 +1662130014832687104 +1662130014874688000 +1662130014919688960 +1662130014976690176 +1662130015024691200 +1662130015072692224 +1662130015114693120 +1662130015156694016 +1662130015201694976 +1662130015240695808 +1662130015279696640 +1662130015321697536 +1662130015369698560 +1662130015420699648 +1662130015462700544 +1662130015504701440 +1662130015552702464 +1662130015594703360 +1662130015636704256 +1662130015678705152 +1662130015720706048 +1662130015768707072 +1662130015819708160 +1662130015861709056 +1662130015903709952 +1662130015945710848 +1662130015996711936 +1662130016038712832 +1662130016080713728 +1662130016128714752 +1662130016179715840 +1662130016221716736 +1662130016263717632 +1662130016308718592 +1662130016362719744 +1662130016401720576 +1662130016443721472 +1662130016482722304 +1662130016527723264 +1662130016569724160 +1662130016611725056 +1662130016668726272 +1662130016710727168 +1662130016761728256 +1662130016812729344 +1662130016854730240 +1662130016896731136 +1662130016938732032 +1662130016977732864 +1662130017022733824 +1662130017061734656 +1662130017103735552 +1662130017154736640 +1662130017202737664 +1662130017247738624 +1662130017289739520 +1662130017334740480 +1662130017379741440 +1662130017421742336 +1662130017469743360 +1662130017517744384 +1662130017559745280 +1662130017601746176 +1662130017649747200 +1662130017691748096 +1662130017733748992 +1662130017781750016 +1662130017826750976 +1662130017877752064 +1662130017922753024 +1662130017964753920 +1662130018006754816 +1662130018045755648 +1662130018093756672 +1662130018147757824 +1662130018189758720 +1662130018228759552 +1662130018273760512 +1662130018318761472 +1662130018357762304 +1662130018402763264 +1662130018447764224 +1662130018489765120 +1662130018528765952 +1662130018573766912 +1662130018618767872 +1662130018660768768 +1662130018702769664 +1662130018744770560 +1662130018795771648 +1662130018837772544 +1662130018888773632 +1662130018936774656 +1662130018978775552 +1662130019032776704 +1662130019077777664 +1662130019116778496 +1662130019161779456 +1662130019209780480 +1662130019248781312 +1662130019287782144 +1662130019335783168 +1662130019383784192 +1662130019425785088 +1662130019473786112 +1662130019515787008 +1662130019557787904 +1662130019596788736 +1662130019644789760 +1662130019683790592 +1662130019728791552 +1662130019776792576 +1662130019821793536 +1662130019863794432 +1662130019905795328 +1662130019950796288 +1662130019992797184 +1662130020055798528 +1662130020097799424 +1662130020145800448 +1662130020190801408 +1662130020232802304 +1662130020274803200 +1662130020316804096 +1662130020364805120 +1662130020412806144 +1662130020454807040 +1662130020505808128 +1662130020550809088 +1662130020592809984 +1662130020634810880 +1662130020682811904 +1662130020724812800 +1662130020769813760 +1662130020811814656 +1662130020859815680 +1662130020904816640 +1662130020946817536 +1662130021000818688 +1662130021045819648 +1662130021093820672 +1662130021138821632 +1662130021180822528 +1662130021222823424 +1662130021267824384 +1662130021315825408 +1662130021357826304 +1662130021399827200 +1662130021441828096 +1662130021483828992 +1662130021522829824 +1662130021570830848 +1662130021615831808 +1662130021666832896 +1662130021720834048 +1662130021768835072 +1662130021822836224 +1662130021873837312 +1662130021921838336 +1662130021969839360 +1662130022014840320 +1662130022059841280 +1662130022104842240 +1662130022143843072 +1662130022188844032 +1662130022230844928 +1662130022278845952 +1662130022323846912 +1662130022374848000 +1662130022416848896 +1662130022467849984 +1662130022512850944 +1662130022554851840 +1662130022599852800 +1662130022638853632 +1662130022680854528 +1662130022722855424 +1662130022764856320 +1662130022812857344 +1662130022854858240 +1662130022896859136 +1662130022947860224 +1662130022989861120 +1662130023034862080 +1662130023076862976 +1662130023112863744 +1662130023157864704 +1662130023199865600 +1662130023244866560 +1662130023292867584 +1662130023334868480 +1662130023376869376 +1662130023418870272 +1662130023463871232 +1662130023505872128 +1662130023556873216 +1662130023607874304 +1662130023655875328 +1662130023697876224 +1662130023739877120 +1662130023787878144 +1662130023829879040 +1662130023877880064 +1662130023925881088 +1662130023970882048 +1662130024012882944 +1662130024054883840 +1662130024096884736 +1662130024150885888 +1662130024195886848 +1662130024240887808 +1662130024279888640 +1662130024324889600 +1662130024369890560 +1662130024414891520 +1662130024456892416 +1662130024501893376 +1662130024546894336 +1662130024597895424 +1662130024645896448 +1662130024690897408 +1662130024732898304 +1662130024774899200 +1662130024816900096 +1662130024858900992 +1662130024903901952 +1662130024948902912 +1662130024999904000 +1662130025041904896 +1662130025080905728 +1662130025128906752 +1662130025170907648 +1662130025224908800 +1662130025263909632 +1662130025302910464 +1662130025353911552 +1662130025398912512 +1662130025443913472 +1662130025485914368 +1662130025527915264 +1662130025569916160 +1662130025611917056 +1662130025647917824 +1662130025689918720 +1662130025734919680 +1662130025776920576 +1662130025824921600 +1662130025866922496 +1662130025908923392 +1662130025947924224 +1662130025989925120 +1662130026031926016 +1662130026076926976 +1662130026118927872 +1662130026163928832 +1662130026202929664 +1662130026244930560 +1662130026289931520 +1662130026337932544 +1662130026382933504 +1662130026424934400 +1662130026466935296 +1662130026508936192 +1662130026553937152 +1662130026595938048 +1662130026640939008 +1662130026682939904 +1662130026721940736 +1662130026763941632 +1662130026811942656 +1662130026856943616 +1662130026904944640 +1662130026955945728 +1662130026994946560 +1662130027039947520 +1662130027081948416 +1662130027117949184 +1662130027165950208 +1662130027207951104 +1662130027249952000 +1662130027297953024 +1662130027351954176 +1662130027396955136 +1662130027444956160 +1662130027489957120 +1662130027537958144 +1662130027579959040 +1662130027621959936 +1662130027660960768 +1662130027711961856 +1662130027753962752 +1662130027795963648 +1662130027837964544 +1662130027885965568 +1662130027930966528 +1662130027975967488 +1662130028026968576 +1662130028068969472 +1662130028113970432 +1662130028161971456 +1662130028209972480 +1662130028257973504 +1662130028296974336 +1662130028341975296 +1662130028383976192 +1662130028428977152 +1662130028473978112 +1662130028521979136 +1662130028563980032 +1662130028605980928 +1662130028647981824 +1662130028689982720 +1662130028731983616 +1662130028779984640 +1662130028815985408 +1662130028863986432 +1662130028908987392 +1662130028956988416 +1662130028998989312 +1662130029043990272 +1662130029085991168 +1662130029136992256 +1662130029178993152 +1662130029226994176 +1662130029271995136 +1662130029307995904 +1662130029352996864 +1662130029388997632 +1662130029433998592 +1662130029475999488 +1662130029518000384 +1662130029560001280 +1662130029605002240 +1662130029650003200 +1662130029692004096 +1662130029740005120 +1662130029782006016 +1662130029827006976 +1662130029872007936 +1662130029914008832 +1662130029959009792 +1662130030004010752 +1662130030058011904 +1662130030100012800 +1662130030145013760 +1662130030193014784 +1662130030238015744 +1662130030277016576 +1662130030319017472 +1662130030364018432 +1662130030406019328 +1662130030448020224 +1662130030496021248 +1662130030538022144 +1662130030583023104 +1662130030628024064 +1662130030676025088 +1662130030721026048 +1662130030763026944 +1662130030811027968 +1662130030856028928 +1662130030904029952 +1662130030952030976 +1662130030997031936 +1662130031045032960 +1662130031087033856 +1662130031126034688 +1662130031171035648 +1662130031213036544 +1662130031261037568 +1662130031306038528 +1662130031354039552 +1662130031396040448 +1662130031441041408 +1662130031480042240 +1662130031522043136 +1662130031567044096 +1662130031615045120 +1662130031660046080 +1662130031702046976 +1662130031744047872 +1662130031786048768 +1662130031831049728 +1662130031879050752 +1662130031921051648 +1662130031972052736 +1662130032020053760 +1662130032059054592 +1662130032110055680 +1662130032152056576 +1662130032191057408 +1662130032233058304 +1662130032278059264 +1662130032326060288 +1662130032368061184 +1662130032410062080 +1662130032452062976 +1662130032491063808 +1662130032530064640 +1662130032575065600 +1662130032617066496 +1662130032659067392 +1662130032701068288 +1662130032743069184 +1662130032782070016 +1662130032827070976 +1662130032869071872 +1662130032917072896 +1662130032959073792 +1662130033004074752 +1662130033046075648 +1662130033088076544 +1662130033133077504 +1662130033181078528 +1662130033226079488 +1662130033271080448 +1662130033319081472 +1662130033364082432 +1662130033406083328 +1662130033445084160 +1662130033493085184 +1662130033535086080 +1662130033577086976 +1662130033619087872 +1662130033661088768 +1662130033709089792 +1662130033751090688 +1662130033796091648 +1662130033838092544 +1662130033889093632 +1662130033931094528 +1662130033976095488 +1662130034018096384 +1662130034066097408 +1662130034108098304 +1662130034150099200 +1662130034195100160 +1662130034240101120 +1662130034285102080 +1662130034324102912 +1662130034366103808 +1662130034411104768 +1662130034453105664 +1662130034501106688 +1662130034543107584 +1662130034579108352 +1662130034621109248 +1662130034663110144 +1662130034708111104 +1662130034756112128 +1662130034798113024 +1662130034846114048 +1662130034888114944 +1662130034930115840 +1662130034969116672 +1662130035017117696 +1662130035059118592 +1662130035104119552 +1662130035149120512 +1662130035194121472 +1662130035236122368 +1662130035278123264 +1662130035323124224 +1662130035362125056 +1662130035404125952 +1662130035452126976 +1662130035500128000 +1662130035551129088 +1662130035593129984 +1662130035638130944 +1662130035686131968 +1662130035734132992 +1662130035776133888 +1662130035821134848 +1662130035863135744 +1662130035911136768 +1662130035953137664 +1662130036004138752 +1662130036046139648 +1662130036094140672 +1662130036139141632 +1662130036190142720 +1662130036235143680 +1662130036277144576 +1662130036328145664 +1662130036370146560 +1662130036415147520 +1662130036463148544 +1662130036502149376 +1662130036547150336 +1662130036586151168 +1662130036628152064 +1662130036676153088 +1662130036718153984 +1662130036760154880 +1662130036802155776 +1662130036844156672 +1662130036889157632 +1662130036931158528 +1662130036982159616 +1662130037021160448 +1662130037063161344 +1662130037105162240 +1662130037141163008 +1662130037183163904 +1662130037228164864 +1662130037270165760 +1662130037312166656 +1662130037354167552 +1662130037405168640 +1662130037450169600 +1662130037495170560 +1662130037537171456 +1662130037576172288 +1662130037627173376 +1662130037672174336 +1662130037711175168 +1662130037753176064 +1662130037795176960 +1662130037837177856 +1662130037885178880 +1662130037930179840 +1662130037972180736 +1662130038020181760 +1662130038059182592 +1662130038110183680 +1662130038161184768 +1662130038203185664 +1662130038251186688 +1662130038296187648 +1662130038341188608 +1662130038392189696 +1662130038434190592 +1662130038476191488 +1662130038524192512 +1662130038566193408 +1662130038614194432 +1662130038665195520 +1662130038713196544 +1662130038758197504 +1662130038800198400 +1662130038839199232 +1662130038881200128 +1662130038935201280 +1662130038980202240 +1662130039022203136 +1662130039064204032 +1662130039109204992 +1662130039154205952 +1662130039196206848 +1662130039241207808 +1662130039286208768 +1662130039325209600 +1662130039364210432 +1662130039412211456 +1662130039457212416 +1662130039499213312 +1662130039544214272 +1662130039592215296 +1662130039637216256 +1662130039679217152 +1662130039724218112 +1662130039769219072 +1662130039811219968 +1662130039853220864 +1662130039901221888 +1662130039946222848 +1662130039988223744 +1662130040027224576 +1662130040078225664 +1662130040132226816 +1662130040174227712 +1662130040213228544 +1662130040255229440 +1662130040294230272 +1662130040336231168 +1662130040375232000 +1662130040420232960 +1662130040468233984 +1662130040516235008 +1662130040558235904 +1662130040603236864 +1662130040648237824 +1662130040693238784 +1662130040738239744 +1662130040789240832 +1662130040828241664 +1662130040870242560 +1662130040912243456 +1662130040954244352 +1662130040999245312 +1662130041044246272 +1662130041089247232 +1662130041128248064 +1662130041170248960 +1662130041212249856 +1662130041254250752 +1662130041299251712 +1662130041341252608 +1662130041383253504 +1662130041428254464 +1662130041467255296 +1662130041518256384 +1662130041563257344 +1662130041608258304 +1662130041653259264 +1662130041698260224 +1662130041749261312 +1662130041785262080 +1662130041830263040 +1662130041872263936 +1662130041914264832 +1662130041971266048 +1662130042013266944 +1662130042061267968 +1662130042103268864 +1662130042145269760 +1662130042187270656 +1662130042238271744 +1662130042283272704 +1662130042334273792 +1662130042376274688 +1662130042418275584 +1662130042460276480 +1662130042517277696 +1662130042559278592 +1662130042601279488 +1662130042643280384 +1662130042691281408 +1662130042733282304 +1662130042775283200 +1662130042817284096 +1662130042859284992 +1662130042907286016 +1662130042955287040 +1662130043000288000 +1662130043054289152 +1662130043096290048 +1662130043135290880 +1662130043177291776 +1662130043228292864 +1662130043270293760 +1662130043312294656 +1662130043363295744 +1662130043405296640 +1662130043447297536 +1662130043501298688 +1662130043549299712 +1662130043594300672 +1662130043633301504 +1662130043678302464 +1662130043720303360 +1662130043759304192 +1662130043813305344 +1662130043858306304 +1662130043900307200 +1662130043945308160 +1662130043984308992 +1662130044026309888 +1662130044065310720 +1662130044110311680 +1662130044152312576 +1662130044194313472 +1662130044257314816 +1662130044293315584 +1662130044341316608 +1662130044383317504 +1662130044428318464 +1662130044470319360 +1662130044512320256 +1662130044557321216 +1662130044599322112 +1662130044647323136 +1662130044689324032 +1662130044734324992 +1662130044785326080 +1662130044827326976 +1662130044869327872 +1662130044911328768 +1662130044950329600 +1662130045001330688 +1662130045043331584 +1662130045091332608 +1662130045133333504 +1662130045175334400 +1662130045226335488 +1662130045268336384 +1662130045313337344 +1662130045355338240 +1662130045400339200 +1662130045448340224 +1662130045493341184 +1662130045544342272 +1662130045586343168 +1662130045628344064 +1662130045673345024 +1662130045715345920 +1662130045757346816 +1662130045799347712 +1662130045844348672 +1662130045886349568 +1662130045931350528 +1662130045973351424 +1662130046012352256 +1662130046054353152 +1662130046099354112 +1662130046138354944 +1662130046177355776 +1662130046219356672 +1662130046258357504 +1662130046300358400 +1662130046351359488 +1662130046396360448 +1662130046438361344 +1662130046477362176 +1662130046522363136 +1662130046561363968 +1662130046600364800 +1662130046642365696 +1662130046684366592 +1662130046726367488 +1662130046765368320 +1662130046807369216 +1662130046852370176 +1662130046900371200 +1662130046948372224 +1662130046990373120 +1662130047041374208 +1662130047086375168 +1662130047128376064 +1662130047170376960 +1662130047227378176 +1662130047269379072 +1662130047311379968 +1662130047356380928 +1662130047398381824 +1662130047443382784 +1662130047485383680 +1662130047530384640 +1662130047578385664 +1662130047626386688 +1662130047674387712 +1662130047725388800 +1662130047776389888 +1662130047815390720 +1662130047854391552 +1662130047896392448 +1662130047947393536 +1662130047995394560 +1662130048040395520 +1662130048088396544 +1662130048133397504 +1662130048181398528 +1662130048226399488 +1662130048274400512 +1662130048316401408 +1662130048364402432 +1662130048412403456 +1662130048460404480 +1662130048502405376 +1662130048553406464 +1662130048595407360 +1662130048643408384 +1662130048685409280 +1662130048736410368 +1662130048778411264 +1662130048829412352 +1662130048871413248 +1662130048916414208 +1662130048955415040 +1662130049003416064 +1662130049045416960 +1662130049090417920 +1662130049132418816 +1662130049180419840 +1662130049225420800 +1662130049270421760 +1662130049312422656 +1662130049375424000 +1662130049417424896 +1662130049462425856 +1662130049507426816 +1662130049552427776 +1662130049594428672 +1662130049633429504 +1662130049675430400 +1662130049726431488 +1662130049768432384 +1662130049810433280 +1662130049852434176 +1662130049897435136 +1662130049936435968 +1662130049984436992 +1662130050026437888 +1662130050068438784 +1662130050110439680 +1662130050155440640 +1662130050200441600 +1662130050245442560 +1662130050287443456 +1662130050329444352 +1662130050368445184 +1662130050410446080 +1662130050452446976 +1662130050500448000 +1662130050545448960 +1662130050587449856 +1662130050629450752 +1662130050674451712 +1662130050716452608 +1662130050761453568 +1662130050800454400 +1662130050845455360 +1662130050896456448 +1662130050941457408 +1662130050986458368 +1662130051031459328 +1662130051076460288 +1662130051118461184 +1662130051163462144 +1662130051211463168 +1662130051253464064 +1662130051298465024 +1662130051340465920 +1662130051385466880 +1662130051430467840 +1662130051478468864 +1662130051526469888 +1662130051571470848 +1662130051619471872 +1662130051664472832 +1662130051709473792 +1662130051751474688 +1662130051796475648 +1662130051838476544 +1662130051883477504 +1662130051925478400 +1662130051967479296 +1662130052006480128 +1662130052048481024 +1662130052090481920 +1662130052132482816 +1662130052180483840 +1662130052231484928 +1662130052273485824 +1662130052321486848 +1662130052363487744 +1662130052408488704 +1662130052453489664 +1662130052498490624 +1662130052546491648 +1662130052588492544 +1662130052639493632 +1662130052687494656 +1662130052729495552 +1662130052771496448 +1662130052816497408 +1662130052867498496 +1662130052912499456 +1662130052957500416 +1662130053008501504 +1662130053062502656 +1662130053107503616 +1662130053155504640 +1662130053197505536 +1662130053239506432 +1662130053281507328 +1662130053320508160 +1662130053362509056 +1662130053404509952 +1662130053446510848 +1662130053488511744 +1662130053536512768 +1662130053575513600 +1662130053629514752 +1662130053668515584 +1662130053713516544 +1662130053755517440 +1662130053800518400 +1662130053851519488 +1662130053896520448 +1662130053941521408 +1662130053983522304 +1662130054028523264 +1662130054073524224 +1662130054118525184 +1662130054160526080 +1662130054208527104 +1662130054250528000 +1662130054298529024 +1662130054346530048 +1662130054385530880 +1662130054427531776 +1662130054472532736 +1662130054514533632 +1662130054556534528 +1662130054604535552 +1662130054646536448 +1662130054694537472 +1662130054748538624 +1662130054796539648 +1662130054838540544 +1662130054880541440 +1662130054928542464 +1662130054976543488 +1662130055018544384 +1662130055060545280 +1662130055105546240 +1662130055153547264 +1662130055201548288 +1662130055246549248 +1662130055294550272 +1662130055342551296 +1662130055387552256 +1662130055429553152 +1662130055471554048 +1662130055510554880 +1662130055552555776 +1662130055594556672 +1662130055636557568 +1662130055693558784 +1662130055735559680 +1662130055777560576 +1662130055819561472 +1662130055861562368 +1662130055906563328 +1662130055948564224 +1662130055987565056 +1662130056032566016 +1662130056077566976 +1662130056119567872 +1662130056161568768 +1662130056203569664 +1662130056251570688 +1662130056290571520 +1662130056338572544 +1662130056386573568 +1662130056431574528 +1662130056476575488 +1662130056518576384 +1662130056563577344 +1662130056611578368 +1662130056656579328 +1662130056701580288 +1662130056743581184 +1662130056785582080 +1662130056827582976 +1662130056869583872 +1662130056914584832 +1662130056965585920 +1662130057010586880 +1662130057058587904 +1662130057106588928 +1662130057151589888 +1662130057193590784 +1662130057244591872 +1662130057286592768 +1662130057328593664 +1662130057376594688 +1662130057421595648 +1662130057466596608 +1662130057514597632 +1662130057553598464 +1662130057598599424 +1662130057646600448 +1662130057688601344 +1662130057730602240 +1662130057775603200 +1662130057823604224 +1662130057868605184 +1662130057910606080 +1662130057955607040 +1662130057994607872 +1662130058039608832 +1662130058084609792 +1662130058132610816 +1662130058180611840 +1662130058228612864 +1662130058279613952 +1662130058321614848 +1662130058363615744 +1662130058405616640 +1662130058450617600 +1662130058492618496 +1662130058537619456 +1662130058579620352 +1662130058624621312 diff --git a/Examples/Monocular-Inertial/MIMIR_TimeStamps/SandPipe_track0_dark.txt b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SandPipe_track0_dark.txt new file mode 100644 index 0000000000..656025a687 --- /dev/null +++ b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SandPipe_track0_dark.txt @@ -0,0 +1,2741 @@ +1662063934494348032 +1662063934536348928 +1662063934587350016 +1662063934629350912 +1662063934671351808 +1662063934713352704 +1662063934758353664 +1662063934803354624 +1662063934848355584 +1662063934893356544 +1662063934938357504 +1662063934977358336 +1662063935022359296 +1662063935064360192 +1662063935103361024 +1662063935145361920 +1662063935187362816 +1662063935229363712 +1662063935268364544 +1662063935310365440 +1662063935352366336 +1662063935394367232 +1662063935436368128 +1662063935478369024 +1662063935535370240 +1662063935577371136 +1662063935619372032 +1662063935670373120 +1662063935712374016 +1662063935757374976 +1662063935799375872 +1662063935844376832 +1662063935886377728 +1662063935931378688 +1662063935973379584 +1662063936015380480 +1662063936057381376 +1662063936099382272 +1662063936141383168 +1662063936180384000 +1662063936222384896 +1662063936267385856 +1662063936312386816 +1662063936360387840 +1662063936405388800 +1662063936447389696 +1662063936489390592 +1662063936531391488 +1662063936573392384 +1662063936615393280 +1662063936657394176 +1662063936699395072 +1662063936744396032 +1662063936786396928 +1662063936828397824 +1662063936870398720 +1662063936909399552 +1662063936948400384 +1662063936990401280 +1662063937038402304 +1662063937089403392 +1662063937134404352 +1662063937182405376 +1662063937224406272 +1662063937269407232 +1662063937314408192 +1662063937356409088 +1662063937401410048 +1662063937449411072 +1662063937488411904 +1662063937539412992 +1662063937584413952 +1662063937638415104 +1662063937677415936 +1662063937719416832 +1662063937761417728 +1662063937803418624 +1662063937842419456 +1662063937887420416 +1662063937935421440 +1662063937977422336 +1662063938019423232 +1662063938061424128 +1662063938106425088 +1662063938148425984 +1662063938193426944 +1662063938238427904 +1662063938283428864 +1662063938325429760 +1662063938370430720 +1662063938412431616 +1662063938457432576 +1662063938499433472 +1662063938544434432 +1662063938586435328 +1662063938631436288 +1662063938676437248 +1662063938718438144 +1662063938760439040 +1662063938802439936 +1662063938850440960 +1662063938898441984 +1662063938943442944 +1662063938988443904 +1662063939036444928 +1662063939078445824 +1662063939126446848 +1662063939165447680 +1662063939210448640 +1662063939252449536 +1662063939300450560 +1662063939342451456 +1662063939387452416 +1662063939429453312 +1662063939471454208 +1662063939510455040 +1662063939552455936 +1662063939594456832 +1662063939639457792 +1662063939681458688 +1662063939723459584 +1662063939765460480 +1662063939807461376 +1662063939852462336 +1662063939894463232 +1662063939939464192 +1662063939981465088 +1662063940026466048 +1662063940068466944 +1662063940113467904 +1662063940158468864 +1662063940209469952 +1662063940257470976 +1662063940299471872 +1662063940341472768 +1662063940383473664 +1662063940422474496 +1662063940464475392 +1662063940506476288 +1662063940548477184 +1662063940590478080 +1662063940632478976 +1662063940674479872 +1662063940716480768 +1662063940767481856 +1662063940806482688 +1662063940851483648 +1662063940899484672 +1662063940941485568 +1662063940989486592 +1662063941034487552 +1662063941079488512 +1662063941124489472 +1662063941169490432 +1662063941214491392 +1662063941262492416 +1662063941304493312 +1662063941346494208 +1662063941391495168 +1662063941436496128 +1662063941475496960 +1662063941517497856 +1662063941562498816 +1662063941604499712 +1662063941646500608 +1662063941688501504 +1662063941736502528 +1662063941784503552 +1662063941832504576 +1662063941874505472 +1662063941922506496 +1662063941964507392 +1662063942009508352 +1662063942051509248 +1662063942093510144 +1662063942138511104 +1662063942180512000 +1662063942222512896 +1662063942267513856 +1662063942309514752 +1662063942351515648 +1662063942396516608 +1662063942447517696 +1662063942498518784 +1662063942543519744 +1662063942585520640 +1662063942630521600 +1662063942672522496 +1662063942714523392 +1662063942762524416 +1662063942807525376 +1662063942852526336 +1662063942897527296 +1662063942942528256 +1662063942984529152 +1662063943029530112 +1662063943074531072 +1662063943116531968 +1662063943167533056 +1662063943206533888 +1662063943248534784 +1662063943287535616 +1662063943329536512 +1662063943374537472 +1662063943416538368 +1662063943458539264 +1662063943503540224 +1662063943545541120 +1662063943584541952 +1662063943629542912 +1662063943671543808 +1662063943710544640 +1662063943752545536 +1662063943794546432 +1662063943836547328 +1662063943884548352 +1662063943935549440 +1662063943977550336 +1662063944019551232 +1662063944061552128 +1662063944103553024 +1662063944145553920 +1662063944184554752 +1662063944229555712 +1662063944277556736 +1662063944319557632 +1662063944361558528 +1662063944418559744 +1662063944463560704 +1662063944508561664 +1662063944553562624 +1662063944595563520 +1662063944640564480 +1662063944682565376 +1662063944733566464 +1662063944778567424 +1662063944823568384 +1662063944865569280 +1662063944910570240 +1662063944955571200 +1662063944997572096 +1662063945039572992 +1662063945081573888 +1662063945126574848 +1662063945171575808 +1662063945213576704 +1662063945255577600 +1662063945297578496 +1662063945339579392 +1662063945381580288 +1662063945420581120 +1662063945465582080 +1662063945507582976 +1662063945549583872 +1662063945588584704 +1662063945642585856 +1662063945690586880 +1662063945732587776 +1662063945780588800 +1662063945822589696 +1662063945867590656 +1662063945912591616 +1662063945954592512 +1662063945999593472 +1662063946041594368 +1662063946089595392 +1662063946131596288 +1662063946173597184 +1662063946215598080 +1662063946263599104 +1662063946302599936 +1662063946344600832 +1662063946392601856 +1662063946437602816 +1662063946479603712 +1662063946524604672 +1662063946566605568 +1662063946608606464 +1662063946650607360 +1662063946692608256 +1662063946731609088 +1662063946776610048 +1662063946818610944 +1662063946863611904 +1662063946908612864 +1662063946950613760 +1662063946992614656 +1662063947037615616 +1662063947076616448 +1662063947124617472 +1662063947163618304 +1662063947205619200 +1662063947247620096 +1662063947292621056 +1662063947337622016 +1662063947382622976 +1662063947430624000 +1662063947472624896 +1662063947517625856 +1662063947565626880 +1662063947604627712 +1662063947649628672 +1662063947694629632 +1662063947736630528 +1662063947787631616 +1662063947832632576 +1662063947871633408 +1662063947913634304 +1662063947955635200 +1662063947997636096 +1662063948045637120 +1662063948087638016 +1662063948129638912 +1662063948171639808 +1662063948213640704 +1662063948270641920 +1662063948309642752 +1662063948354643712 +1662063948402644736 +1662063948444645632 +1662063948486646528 +1662063948534647552 +1662063948576648448 +1662063948621649408 +1662063948663650304 +1662063948699651072 +1662063948741651968 +1662063948783652864 +1662063948831653888 +1662063948879654912 +1662063948924655872 +1662063948966656768 +1662063949008657664 +1662063949050658560 +1662063949092659456 +1662063949134660352 +1662063949176661248 +1662063949215662080 +1662063949263663104 +1662063949305664000 +1662063949347664896 +1662063949389665792 +1662063949431666688 +1662063949473667584 +1662063949518668544 +1662063949563669504 +1662063949602670336 +1662063949641671168 +1662063949686672128 +1662063949728673024 +1662063949770673920 +1662063949812674816 +1662063949854675712 +1662063949902676736 +1662063949941677568 +1662063949986678528 +1662063950031679488 +1662063950073680384 +1662063950112681216 +1662063950154682112 +1662063950199683072 +1662063950244684032 +1662063950289684992 +1662063950334685952 +1662063950382686976 +1662063950430688000 +1662063950472688896 +1662063950520689920 +1662063950562690816 +1662063950604691712 +1662063950646692608 +1662063950688693504 +1662063950733694464 +1662063950778695424 +1662063950823696384 +1662063950865697280 +1662063950907698176 +1662063950949699072 +1662063951003700224 +1662063951042701056 +1662063951084701952 +1662063951135703040 +1662063951177703936 +1662063951222704896 +1662063951267705856 +1662063951309706752 +1662063951357707776 +1662063951402708736 +1662063951447709696 +1662063951495710720 +1662063951537711616 +1662063951585712640 +1662063951627713536 +1662063951672714496 +1662063951717715456 +1662063951759716352 +1662063951807717376 +1662063951849718272 +1662063951891719168 +1662063951933720064 +1662063951975720960 +1662063952017721856 +1662063952062722816 +1662063952104723712 +1662063952149724672 +1662063952194725632 +1662063952242726656 +1662063952287727616 +1662063952335728640 +1662063952380729600 +1662063952425730560 +1662063952470731520 +1662063952512732416 +1662063952551733248 +1662063952590734080 +1662063952635735040 +1662063952680736000 +1662063952722736896 +1662063952767737856 +1662063952809738752 +1662063952851739648 +1662063952890740480 +1662063952932741376 +1662063952980742400 +1662063953022743296 +1662063953067744256 +1662063953112745216 +1662063953154746112 +1662063953199747072 +1662063953241747968 +1662063953280748800 +1662063953325749760 +1662063953370750720 +1662063953415751680 +1662063953457752576 +1662063953502753536 +1662063953544754432 +1662063953586755328 +1662063953628756224 +1662063953676757248 +1662063953718758144 +1662063953763759104 +1662063953808760064 +1662063953850760960 +1662063953892761856 +1662063953934762752 +1662063953979763712 +1662063954024764672 +1662063954066765568 +1662063954108766464 +1662063954150767360 +1662063954192768256 +1662063954240769280 +1662063954282770176 +1662063954330771200 +1662063954375772160 +1662063954414772992 +1662063954456773888 +1662063954501774848 +1662063954543775744 +1662063954588776704 +1662063954633777664 +1662063954678778624 +1662063954720779520 +1662063954765780480 +1662063954807781376 +1662063954849782272 +1662063954891783168 +1662063954933784064 +1662063954975784960 +1662063955017785856 +1662063955065786880 +1662063955113787904 +1662063955155788800 +1662063955197789696 +1662063955242790656 +1662063955284791552 +1662063955329792512 +1662063955374793472 +1662063955425794560 +1662063955464795392 +1662063955509796352 +1662063955548797184 +1662063955590798080 +1662063955629798912 +1662063955671799808 +1662063955713800704 +1662063955755801600 +1662063955800802560 +1662063955854803712 +1662063955896804608 +1662063955938805504 +1662063955986806528 +1662063956031807488 +1662063956079808512 +1662063956121809408 +1662063956163810304 +1662063956205811200 +1662063956247812096 +1662063956289812992 +1662063956331813888 +1662063956376814848 +1662063956415815680 +1662063956457816576 +1662063956502817536 +1662063956547818496 +1662063956589819392 +1662063956637820416 +1662063956679821312 +1662063956718822144 +1662063956766823168 +1662063956814824192 +1662063956865825280 +1662063956910826240 +1662063956952827136 +1662063956997828096 +1662063957039828992 +1662063957084829952 +1662063957126830848 +1662063957171831808 +1662063957216832768 +1662063957261833728 +1662063957303834624 +1662063957348835584 +1662063957387836416 +1662063957429837312 +1662063957474838272 +1662063957522839296 +1662063957564840192 +1662063957603841024 +1662063957645841920 +1662063957690842880 +1662063957732843776 +1662063957777844736 +1662063957819845632 +1662063957864846592 +1662063957912847616 +1662063957954848512 +1662063957996849408 +1662063958041850368 +1662063958083851264 +1662063958131852288 +1662063958176853248 +1662063958224854272 +1662063958269855232 +1662063958320856320 +1662063958365857280 +1662063958407858176 +1662063958452859136 +1662063958494860032 +1662063958536860928 +1662063958584861952 +1662063958626862848 +1662063958668863744 +1662063958713864704 +1662063958752865536 +1662063958803866624 +1662063958848867584 +1662063958893868544 +1662063958941869568 +1662063958992870656 +1662063959034871552 +1662063959079872512 +1662063959121873408 +1662063959166874368 +1662063959208875264 +1662063959253876224 +1662063959301877248 +1662063959355878400 +1662063959397879296 +1662063959436880128 +1662063959478881024 +1662063959529882112 +1662063959574883072 +1662063959616883968 +1662063959658884864 +1662063959700885760 +1662063959742886656 +1662063959784887552 +1662063959829888512 +1662063959871889408 +1662063959913890304 +1662063959955891200 +1662063959997892096 +1662063960039892992 +1662063960084893952 +1662063960129894912 +1662063960174895872 +1662063960216896768 +1662063960258897664 +1662063960300898560 +1662063960342899456 +1662063960387900416 +1662063960429901312 +1662063960474902272 +1662063960525903360 +1662063960567904256 +1662063960606905088 +1662063960648905984 +1662063960687906816 +1662063960732907776 +1662063960774908672 +1662063960816909568 +1662063960861910528 +1662063960906911488 +1662063960948912384 +1662063960990913280 +1662063961032914176 +1662063961074915072 +1662063961119916032 +1662063961164916992 +1662063961209917952 +1662063961254918912 +1662063961299919872 +1662063961344920832 +1662063961389921792 +1662063961428922624 +1662063961470923520 +1662063961515924480 +1662063961563925504 +1662063961608926464 +1662063961650927360 +1662063961689928192 +1662063961728929024 +1662063961776930048 +1662063961821931008 +1662063961863931904 +1662063961908932864 +1662063961956933888 +1662063961998934784 +1662063962040935680 +1662063962088936704 +1662063962136937728 +1662063962178938624 +1662063962223939584 +1662063962271940608 +1662063962316941568 +1662063962367942656 +1662063962409943552 +1662063962451944448 +1662063962496945408 +1662063962547946496 +1662063962592947456 +1662063962640948480 +1662063962682949376 +1662063962724950272 +1662063962769951232 +1662063962814952192 +1662063962871953408 +1662063962913954304 +1662063962958955264 +1662063963006956288 +1662063963045957120 +1662063963090958080 +1662063963132958976 +1662063963183960064 +1662063963225960960 +1662063963267961856 +1662063963309962752 +1662063963354963712 +1662063963396964608 +1662063963435965440 +1662063963483966464 +1662063963531967488 +1662063963579968512 +1662063963621969408 +1662063963663970304 +1662063963711971328 +1662063963759972352 +1662063963801973248 +1662063963840974080 +1662063963885975040 +1662063963927975936 +1662063963972976896 +1662063964017977856 +1662063964059978752 +1662063964101979648 +1662063964143980544 +1662063964185981440 +1662063964227982336 +1662063964275983360 +1662063964320984320 +1662063964359985152 +1662063964401986048 +1662063964440986880 +1662063964479987712 +1662063964524988672 +1662063964566989568 +1662063964608990464 +1662063964653991424 +1662063964701992448 +1662063964749993472 +1662063964794994432 +1662063964836995328 +1662063964878996224 +1662063964923997184 +1662063964968998144 +1662063965010999040 +1662063965052999936 +1662063965098000896 +1662063965155002112 +1662063965197003008 +1662063965245004032 +1662063965287004928 +1662063965332005888 +1662063965377006848 +1662063965422007808 +1662063965461008640 +1662063965506009600 +1662063965545010432 +1662063965593011456 +1662063965635012352 +1662063965677013248 +1662063965719014144 +1662063965761015040 +1662063965809016064 +1662063965851016960 +1662063965893017856 +1662063965935018752 +1662063965980019712 +1662063966028020736 +1662063966073021696 +1662063966115022592 +1662063966160023552 +1662063966205024512 +1662063966250025472 +1662063966295026432 +1662063966337027328 +1662063966382028288 +1662063966427029248 +1662063966472030208 +1662063966514031104 +1662063966559032064 +1662063966601032960 +1662063966646033920 +1662063966688034816 +1662063966736035840 +1662063966781036800 +1662063966823037696 +1662063966868038656 +1662063966919039744 +1662063966964040704 +1662063967009041664 +1662063967054042624 +1662063967096043520 +1662063967138044416 +1662063967183045376 +1662063967225046272 +1662063967267047168 +1662063967309048064 +1662063967351048960 +1662063967393049856 +1662063967435050752 +1662063967477051648 +1662063967525052672 +1662063967570053632 +1662063967612054528 +1662063967654055424 +1662063967702056448 +1662063967741057280 +1662063967786058240 +1662063967828059136 +1662063967867059968 +1662063967909060864 +1662063967954061824 +1662063968002062848 +1662063968047063808 +1662063968089064704 +1662063968137065728 +1662063968179066624 +1662063968230067712 +1662063968275068672 +1662063968320069632 +1662063968365070592 +1662063968410071552 +1662063968455072512 +1662063968497073408 +1662063968539074304 +1662063968584075264 +1662063968623076096 +1662063968665076992 +1662063968710077952 +1662063968761079040 +1662063968803079936 +1662063968848080896 +1662063968893081856 +1662063968938082816 +1662063968983083776 +1662063969025084672 +1662063969073085696 +1662063969115086592 +1662063969157087488 +1662063969205088512 +1662063969253089536 +1662063969295090432 +1662063969346091520 +1662063969391092480 +1662063969433093376 +1662063969478094336 +1662063969523095296 +1662063969565096192 +1662063969610097152 +1662063969655098112 +1662063969700099072 +1662063969739099904 +1662063969781100800 +1662063969826101760 +1662063969868102656 +1662063969913103616 +1662063969967104768 +1662063970009105664 +1662063970051106560 +1662063970093107456 +1662063970132108288 +1662063970180109312 +1662063970228110336 +1662063970267111168 +1662063970309112064 +1662063970360113152 +1662063970405114112 +1662063970447115008 +1662063970492115968 +1662063970531116800 +1662063970576117760 +1662063970615118592 +1662063970660119552 +1662063970711120640 +1662063970750121472 +1662063970792122368 +1662063970834123264 +1662063970876124160 +1662063970918125056 +1662063970960125952 +1662063971002126848 +1662063971044127744 +1662063971089128704 +1662063971131129600 +1662063971176130560 +1662063971218131456 +1662063971260132352 +1662063971299133184 +1662063971341134080 +1662063971389135104 +1662063971431136000 +1662063971473136896 +1662063971515137792 +1662063971557138688 +1662063971605139712 +1662063971650140672 +1662063971692141568 +1662063971740142592 +1662063971782143488 +1662063971827144448 +1662063971869145344 +1662063971914146304 +1662063971956147200 +1662063971998148096 +1662063972040148992 +1662063972088150016 +1662063972142151168 +1662063972187152128 +1662063972232153088 +1662063972271153920 +1662063972316154880 +1662063972358155776 +1662063972400156672 +1662063972448157696 +1662063972490158592 +1662063972535159552 +1662063972577160448 +1662063972622161408 +1662063972661162240 +1662063972703163136 +1662063972754164224 +1662063972802165248 +1662063972853166336 +1662063972895167232 +1662063972937168128 +1662063972982169088 +1662063973024169984 +1662063973072171008 +1662063973114171904 +1662063973156172800 +1662063973201173760 +1662063973252174848 +1662063973300175872 +1662063973348176896 +1662063973402178048 +1662063973444178944 +1662063973486179840 +1662063973525180672 +1662063973564181504 +1662063973618182656 +1662063973660183552 +1662063973699184384 +1662063973744185344 +1662063973789186304 +1662063973834187264 +1662063973876188160 +1662063973921189120 +1662063973963190016 +1662063974014191104 +1662063974056192000 +1662063974095192832 +1662063974137193728 +1662063974176194560 +1662063974218195456 +1662063974260196352 +1662063974302197248 +1662063974350198272 +1662063974389199104 +1662063974440200192 +1662063974482201088 +1662063974527202048 +1662063974572203008 +1662063974614203904 +1662063974659204864 +1662063974704205824 +1662063974749206784 +1662063974797207808 +1662063974839208704 +1662063974881209600 +1662063974929210624 +1662063974971211520 +1662063975016212480 +1662063975064213504 +1662063975106214400 +1662063975154215424 +1662063975196216320 +1662063975238217216 +1662063975280218112 +1662063975325219072 +1662063975370220032 +1662063975412220928 +1662063975454221824 +1662063975493222656 +1662063975532223488 +1662063975577224448 +1662063975619225344 +1662063975661226240 +1662063975703227136 +1662063975748228096 +1662063975790228992 +1662063975832229888 +1662063975874230784 +1662063975910231552 +1662063975955232512 +1662063975994233344 +1662063976036234240 +1662063976084235264 +1662063976126236160 +1662063976168237056 +1662063976219238144 +1662063976261239040 +1662063976303239936 +1662063976345240832 +1662063976387241728 +1662063976429242624 +1662063976471243520 +1662063976519244544 +1662063976561245440 +1662063976603246336 +1662063976648247296 +1662063976693248256 +1662063976735249152 +1662063976780250112 +1662063976822251008 +1662063976867251968 +1662063976909252864 +1662063976954253824 +1662063977002254848 +1662063977044255744 +1662063977089256704 +1662063977134257664 +1662063977176258560 +1662063977218259456 +1662063977263260416 +1662063977305261312 +1662063977347262208 +1662063977389263104 +1662063977434264064 +1662063977476264960 +1662063977521265920 +1662063977563266816 +1662063977617267968 +1662063977659268864 +1662063977704269824 +1662063977761271040 +1662063977806272000 +1662063977854273024 +1662063977896273920 +1662063977938274816 +1662063977977275648 +1662063978022276608 +1662063978067277568 +1662063978112278528 +1662063978151279360 +1662063978196280320 +1662063978238281216 +1662063978286282240 +1662063978340283392 +1662063978397284608 +1662063978445285632 +1662063978484286464 +1662063978529287424 +1662063978571288320 +1662063978616289280 +1662063978658290176 +1662063978703291136 +1662063978745292032 +1662063978784292864 +1662063978826293760 +1662063978868294656 +1662063978913295616 +1662063978961296640 +1662063979003297536 +1662063979051298560 +1662063979093299456 +1662063979138300416 +1662063979186301440 +1662063979228302336 +1662063979267303168 +1662063979318304256 +1662063979363305216 +1662063979408306176 +1662063979453307136 +1662063979495308032 +1662063979534308864 +1662063979585309952 +1662063979627310848 +1662063979669311744 +1662063979711312640 +1662063979756313600 +1662063979798314496 +1662063979843315456 +1662063979888316416 +1662063979930317312 +1662063979978318336 +1662063980020319232 +1662063980065320192 +1662063980110321152 +1662063980158322176 +1662063980200323072 +1662063980239323904 +1662063980284324864 +1662063980326325760 +1662063980368326656 +1662063980410327552 +1662063980455328512 +1662063980503329536 +1662063980545330432 +1662063980587331328 +1662063980635332352 +1662063980683333376 +1662063980722334208 +1662063980764335104 +1662063980806336000 +1662063980854337024 +1662063980896337920 +1662063980947339008 +1662063980992339968 +1662063981034340864 +1662063981073341696 +1662063981118342656 +1662063981157343488 +1662063981199344384 +1662063981250345472 +1662063981292346368 +1662063981337347328 +1662063981379348224 +1662063981421349120 +1662063981472350208 +1662063981517351168 +1662063981574352384 +1662063981616353280 +1662063981667354368 +1662063981712355328 +1662063981757356288 +1662063981796357120 +1662063981841358080 +1662063981889359104 +1662063981931360000 +1662063981982361088 +1662063982024361984 +1662063982066362880 +1662063982114363904 +1662063982159364864 +1662063982201365760 +1662063982240366592 +1662063982288367616 +1662063982333368576 +1662063982384369664 +1662063982426370560 +1662063982465371392 +1662063982519372544 +1662063982561373440 +1662063982606374400 +1662063982648375296 +1662063982693376256 +1662063982738377216 +1662063982780378112 +1662063982822379008 +1662063982867379968 +1662063982909380864 +1662063982954381824 +1662063982993382656 +1662063983035383552 +1662063983080384512 +1662063983122385408 +1662063983173386496 +1662063983212387328 +1662063983257388288 +1662063983296389120 +1662063983338390016 +1662063983386391040 +1662063983434392064 +1662063983479393024 +1662063983524393984 +1662063983566394880 +1662063983608395776 +1662063983656396800 +1662063983698397696 +1662063983737398528 +1662063983779399424 +1662063983824400384 +1662063983863401216 +1662063983905402112 +1662063983959403264 +1662063984001404160 +1662063984043405056 +1662063984085405952 +1662063984124406784 +1662063984166407680 +1662063984220408832 +1662063984262409728 +1662063984310410752 +1662063984355411712 +1662063984397412608 +1662063984436413440 +1662063984478414336 +1662063984520415232 +1662063984568416256 +1662063984613417216 +1662063984658418176 +1662063984703419136 +1662063984745420032 +1662063984790420992 +1662063984835421952 +1662063984880422912 +1662063984940424192 +1662063984979425024 +1662063985021425920 +1662063985063426816 +1662063985111427840 +1662063985153428736 +1662063985195429632 +1662063985249430784 +1662063985291431680 +1662063985330432512 +1662063985375433472 +1662063985420434432 +1662063985459435264 +1662063985504436224 +1662063985546437120 +1662063985591438080 +1662063985636439040 +1662063985678439936 +1662063985726440960 +1662063985765441792 +1662063985807442688 +1662063985855443712 +1662063985900444672 +1662063985939445504 +1662063985987446528 +1662063986029447424 +1662063986074448384 +1662063986116449280 +1662063986158450176 +1662063986200451072 +1662063986248452096 +1662063986290452992 +1662063986335453952 +1662063986377454848 +1662063986419455744 +1662063986461456640 +1662063986509457664 +1662063986551458560 +1662063986593459456 +1662063986647460608 +1662063986686461440 +1662063986728462336 +1662063986770463232 +1662063986809464064 +1662063986851464960 +1662063986896465920 +1662063986938466816 +1662063986980467712 +1662063987022468608 +1662063987070469632 +1662063987112470528 +1662063987157471488 +1662063987196472320 +1662063987238473216 +1662063987289474304 +1662063987334475264 +1662063987391476480 +1662063987430477312 +1662063987475478272 +1662063987517479168 +1662063987559480064 +1662063987601480960 +1662063987637481728 +1662063987679482624 +1662063987721483520 +1662063987763484416 +1662063987805485312 +1662063987847486208 +1662063987889487104 +1662063987937488128 +1662063987979489024 +1662063988021489920 +1662063988057490688 +1662063988102491648 +1662063988144492544 +1662063988186493440 +1662063988231494400 +1662063988273495296 +1662063988318496256 +1662063988360497152 +1662063988402498048 +1662063988441498880 +1662063988483499776 +1662063988525500672 +1662063988567501568 +1662063988609502464 +1662063988651503360 +1662063988696504320 +1662063988738505216 +1662063988783506176 +1662063988825507072 +1662063988879508224 +1662063988921509120 +1662063988963510016 +1662063989008510976 +1662063989050511872 +1662063989092512768 +1662063989140513792 +1662063989185514752 +1662063989227515648 +1662063989269516544 +1662063989317517568 +1662063989362518528 +1662063989404519424 +1662063989449520384 +1662063989491521280 +1662063989533522176 +1662063989578523136 +1662063989623524096 +1662063989665524992 +1662063989707525888 +1662063989755526912 +1662063989797527808 +1662063989839528704 +1662063989881529600 +1662063989926530560 +1662063989971531520 +1662063990016532480 +1662063990055533312 +1662063990097534208 +1662063990139535104 +1662063990181536000 +1662063990223536896 +1662063990265537792 +1662063990307538688 +1662063990349539584 +1662063990391540480 +1662063990439541504 +1662063990481542400 +1662063990526543360 +1662063990571544320 +1662063990610545152 +1662063990652546048 +1662063990694546944 +1662063990739547904 +1662063990784548864 +1662063990826549760 +1662063990874550784 +1662063990916551680 +1662063990958552576 +1662063991003553536 +1662063991045554432 +1662063991087555328 +1662063991135556352 +1662063991183557376 +1662063991231558400 +1662063991270559232 +1662063991318560256 +1662063991360561152 +1662063991405562112 +1662063991450563072 +1662063991492563968 +1662063991540564992 +1662063991579565824 +1662063991618566656 +1662063991666567680 +1662063991708568576 +1662063991753569536 +1662063991801570560 +1662063991843571456 +1662063991888572416 +1662063991930573312 +1662063991975574272 +1662063992020575232 +1662063992065576192 +1662063992113577216 +1662063992158578176 +1662063992197579008 +1662063992245580032 +1662063992284580864 +1662063992332581888 +1662063992374582784 +1662063992422583808 +1662063992470584832 +1662063992521585920 +1662063992563586816 +1662063992602587648 +1662063992647588608 +1662063992692589568 +1662063992740590592 +1662063992785591552 +1662063992836592640 +1662063992875593472 +1662063992917594368 +1662063992962595328 +1662063993004596224 +1662063993049597184 +1662063993094598144 +1662063993139599104 +1662063993178599936 +1662063993223600896 +1662063993262601728 +1662063993304602624 +1662063993349603584 +1662063993388604416 +1662063993430605312 +1662063993475606272 +1662063993517607168 +1662063993559608064 +1662063993601608960 +1662063993649609984 +1662063993691610880 +1662063993733611776 +1662063993775612672 +1662063993826613760 +1662063993865614592 +1662063993907615488 +1662063993949616384 +1662063994000617472 +1662063994045618432 +1662063994084619264 +1662063994126620160 +1662063994162620928 +1662063994207621888 +1662063994255622912 +1662063994303623936 +1662063994345624832 +1662063994399625984 +1662063994444626944 +1662063994486627840 +1662063994525628672 +1662063994573629696 +1662063994621630720 +1662063994669631744 +1662063994711632640 +1662063994756633600 +1662063994798634496 +1662063994846635520 +1662063994888636416 +1662063994939637504 +1662063994990638592 +1662063995032639488 +1662063995077640448 +1662063995119641344 +1662063995164642304 +1662063995209643264 +1662063995254644224 +1662063995299645184 +1662063995347646208 +1662063995389647104 +1662063995434648064 +1662063995479649024 +1662063995527650048 +1662063995569650944 +1662063995608651776 +1662063995650652672 +1662063995695653632 +1662063995737654528 +1662063995785655552 +1662063995830656512 +1662063995872657408 +1662063995914658304 +1662063995953659136 +1662063995998660096 +1662063996040660992 +1662063996085661952 +1662063996133662976 +1662063996181664000 +1662063996229665024 +1662063996283666176 +1662063996325667072 +1662063996373668096 +1662063996412668928 +1662063996463670016 +1662063996508670976 +1662063996550671872 +1662063996592672768 +1662063996637673728 +1662063996679674624 +1662063996730675712 +1662063996775676672 +1662063996817677568 +1662063996859678464 +1662063996904679424 +1662063996952680448 +1662063996997681408 +1662063997048682496 +1662063997087683328 +1662063997126684160 +1662063997177685248 +1662063997222686208 +1662063997264687104 +1662063997306688000 +1662063997345688832 +1662063997396689920 +1662063997444690944 +1662063997486691840 +1662063997531692800 +1662063997573693696 +1662063997621694720 +1662063997666695680 +1662063997708696576 +1662063997750697472 +1662063997795698432 +1662063997840699392 +1662063997888700416 +1662063997933701376 +1662063997975702272 +1662063998020703232 +1662063998062704128 +1662063998107705088 +1662063998149705984 +1662063998200707072 +1662063998242707968 +1662063998287708928 +1662063998335709952 +1662063998377710848 +1662063998428711936 +1662063998473712896 +1662063998527714048 +1662063998575715072 +1662063998626716160 +1662063998677717248 +1662063998725718272 +1662063998770719232 +1662063998812720128 +1662063998854721024 +1662063998896721920 +1662063998944722944 +1662063998986723840 +1662063999028724736 +1662063999079725824 +1662063999121726720 +1662063999163727616 +1662063999208728576 +1662063999250729472 +1662063999292730368 +1662063999334731264 +1662063999385732352 +1662063999433733376 +1662063999475734272 +1662063999517735168 +1662063999559736064 +1662063999604737024 +1662063999646737920 +1662063999688738816 +1662063999730739712 +1662063999769740544 +1662063999811741440 +1662063999856742400 +1662063999904743424 +1662063999946744320 +1662063999988745216 +1662064000027746048 +1662064000069746944 +1662064000114747904 +1662064000156748800 +1662064000201749760 +1662064000246750720 +1662064000291751680 +1662064000333752576 +1662064000378753536 +1662064000420754432 +1662064000465755392 +1662064000510756352 +1662064000555757312 +1662064000603758336 +1662064000648759296 +1662064000687760128 +1662064000729761024 +1662064000771761920 +1662064000816762880 +1662064000864763904 +1662064000906764800 +1662064000948765696 +1662064000993766656 +1662064001044767744 +1662064001086768640 +1662064001128769536 +1662064001173770496 +1662064001215771392 +1662064001260772352 +1662064001308773376 +1662064001350774272 +1662064001398775296 +1662064001440776192 +1662064001488777216 +1662064001533778176 +1662064001578779136 +1662064001629780224 +1662064001671781120 +1662064001713782016 +1662064001755782912 +1662064001797783808 +1662064001839784704 +1662064001881785600 +1662064001929786624 +1662064001971787520 +1662064002013788416 +1662064002055789312 +1662064002097790208 +1662064002142791168 +1662064002187792128 +1662064002229793024 +1662064002274793984 +1662064002319794944 +1662064002373796096 +1662064002415796992 +1662064002457797888 +1662064002499798784 +1662064002550799872 +1662064002592800768 +1662064002634801664 +1662064002673802496 +1662064002718803456 +1662064002760804352 +1662064002805805312 +1662064002847806208 +1662064002889807104 +1662064002931808000 +1662064002979809024 +1662064003030810112 +1662064003075811072 +1662064003120812032 +1662064003168813056 +1662064003207813888 +1662064003249814784 +1662064003294815744 +1662064003342816768 +1662064003390817792 +1662064003435818752 +1662064003477819648 +1662064003522820608 +1662064003564821504 +1662064003606822400 +1662064003654823424 +1662064003699824384 +1662064003747825408 +1662064003789826304 +1662064003828827136 +1662064003873828096 +1662064003915828992 +1662064003960829952 +1662064004008830976 +1662064004053831936 +1662064004092832768 +1662064004134833664 +1662064004176834560 +1662064004218835456 +1662064004266836480 +1662064004308837376 +1662064004350838272 +1662064004392839168 +1662064004434840064 +1662064004485841152 +1662064004527842048 +1662064004575843072 +1662064004617843968 +1662064004668845056 +1662064004713846016 +1662064004758846976 +1662064004800847872 +1662064004842848768 +1662064004887849728 +1662064004929850624 +1662064004971851520 +1662064005019852544 +1662064005064853504 +1662064005115854592 +1662064005160855552 +1662064005202856448 +1662064005247857408 +1662064005289858304 +1662064005331859200 +1662064005373860096 +1662064005424861184 +1662064005466862080 +1662064005511863040 +1662064005553863936 +1662064005598864896 +1662064005640865792 +1662064005682866688 +1662064005736867840 +1662064005781868800 +1662064005826869760 +1662064005871870720 +1662064005910871552 +1662064005955872512 +1662064006000873472 +1662064006045874432 +1662064006090875392 +1662064006132876288 +1662064006177877248 +1662064006222878208 +1662064006264879104 +1662064006309880064 +1662064006360881152 +1662064006402882048 +1662064006444882944 +1662064006489883904 +1662064006531884800 +1662064006576885760 +1662064006621886720 +1662064006669887744 +1662064006717888768 +1662064006762889728 +1662064006804890624 +1662064006855891712 +1662064006897892608 +1662064006942893568 +1662064006990894592 +1662064007032895488 +1662064007077896448 +1662064007119897344 +1662064007161898240 +1662064007206899200 +1662064007248900096 +1662064007290900992 +1662064007332901888 +1662064007374902784 +1662064007425903872 +1662064007464904704 +1662064007512905728 +1662064007557906688 +1662064007602907648 +1662064007647908608 +1662064007692909568 +1662064007746910720 +1662064007791911680 +1662064007833912576 +1662064007878913536 +1662064007920914432 +1662064007962915328 +1662064008004916224 +1662064008046917120 +1662064008091918080 +1662064008133918976 +1662064008175919872 +1662064008220920832 +1662064008262921728 +1662064008307922688 +1662064008352923648 +1662064008394924544 +1662064008436925440 +1662064008478926336 +1662064008520927232 +1662064008565928192 +1662064008610929152 +1662064008664930304 +1662064008709931264 +1662064008754932224 +1662064008796933120 +1662064008844934144 +1662064008889935104 +1662064008934936064 +1662064008985937152 +1662064009027938048 +1662064009075939072 +1662064009120940032 +1662064009162940928 +1662064009207941888 +1662064009249942784 +1662064009288943616 +1662064009339944704 +1662064009381945600 +1662064009423946496 +1662064009465947392 +1662064009510948352 +1662064009558949376 +1662064009597950208 +1662064009636951040 +1662064009678951936 +1662064009717952768 +1662064009762953728 +1662064009807954688 +1662064009849955584 +1662064009897956608 +1662064009948957696 +1662064009990958592 +1662064010035959552 +1662064010077960448 +1662064010122961408 +1662064010170962432 +1662064010215963392 +1662064010260964352 +1662064010317965568 +1662064010365966592 +1662064010410967552 +1662064010458968576 +1662064010500969472 +1662064010542970368 +1662064010587971328 +1662064010629972224 +1662064010674973184 +1662064010719974144 +1662064010767975168 +1662064010809976064 +1662064010857977088 +1662064010902978048 +1662064010947979008 +1662064010989979904 +1662064011031980800 +1662064011073981696 +1662064011121982720 +1662064011172983808 +1662064011214984704 +1662064011259985664 +1662064011307986688 +1662064011346987520 +1662064011391988480 +1662064011436989440 +1662064011478990336 +1662064011523991296 +1662064011568992256 +1662064011610993152 +1662064011655994112 +1662064011700995072 +1662064011748996096 +1662064011790996992 +1662064011835997952 +1662064011877998848 +1662064011919999744 +1662064011965000704 +1662064012010001664 +1662064012049002496 +1662064012091003392 +1662064012133004288 +1662064012175005184 +1662064012217006080 +1662064012262007040 +1662064012301007872 +1662064012346008832 +1662064012391009792 +1662064012433010688 +1662064012481011712 +1662064012526012672 +1662064012568013568 +1662064012610014464 +1662064012652015360 +1662064012694016256 +1662064012748017408 +1662064012790018304 +1662064012832019200 +1662064012874020096 +1662064012916020992 +1662064012961021952 +1662064013015023104 +1662064013060024064 +1662064013105025024 +1662064013150025984 +1662064013192026880 +1662064013237027840 +1662064013279028736 +1662064013321029632 +1662064013369030656 +1662064013411031552 +1662064013456032512 +1662064013501033472 +1662064013543034368 +1662064013585035264 +1662064013630036224 +1662064013678037248 +1662064013720038144 +1662064013768039168 +1662064013810040064 +1662064013855041024 +1662064013900041984 +1662064013948043008 +1662064013993043968 +1662064014038044928 +1662064014089046016 +1662064014134046976 +1662064014179047936 +1662064014224048896 +1662064014275049984 +1662064014314050816 +1662064014356051712 +1662064014401052672 +1662064014446053632 +1662064014488054528 +1662064014533055488 +1662064014578056448 +1662064014623057408 +1662064014662058240 +1662064014710059264 +1662064014758060288 +1662064014797061120 +1662064014839062016 +1662064014887063040 +1662064014935064064 +1662064014980065024 +1662064015031066112 +1662064015082067200 +1662064015124068096 +1662064015166068992 +1662064015211069952 +1662064015259070976 +1662064015304071936 +1662064015349072896 +1662064015391073792 +1662064015436074752 +1662064015478075648 +1662064015520076544 +1662064015574077696 +1662064015634078976 +1662064015685080064 +1662064015727080960 +1662064015769081856 +1662064015811082752 +1662064015850083584 +1662064015889084416 +1662064015931085312 +1662064015973086208 +1662064016018087168 +1662064016060088064 +1662064016111089152 +1662064016153090048 +1662064016198091008 +1662064016240091904 +1662064016294093056 +1662064016342094080 +1662064016387095040 +1662064016435096064 +1662064016477096960 +1662064016522097920 +1662064016564098816 +1662064016609099776 +1662064016660100864 +1662064016705101824 +1662064016750102784 +1662064016792103680 +1662064016837104640 +1662064016879105536 +1662064016924106496 +1662064016966107392 +1662064017011108352 +1662064017053109248 +1662064017095110144 +1662064017140111104 +1662064017182112000 +1662064017227112960 +1662064017269113856 +1662064017311114752 +1662064017353115648 +1662064017395116544 +1662064017437117440 +1662064017482118400 +1662064017524119296 +1662064017566120192 +1662064017608121088 +1662064017656122112 +1662064017704123136 +1662064017749124096 +1662064017791124992 +1662064017836125952 +1662064017878126848 +1662064017920127744 +1662064017965128704 +1662064018010129664 +1662064018055130624 +1662064018103131648 +1662064018145132544 +1662064018187133440 +1662064018232134400 +1662064018289135616 +1662064018334136576 +1662064018382137600 +1662064018421138432 +1662064018463139328 +1662064018505140224 +1662064018550141184 +1662064018595142144 +1662064018640143104 +1662064018682144000 +1662064018721144832 +1662064018766145792 +1662064018808146688 +1662064018850147584 +1662064018892148480 +1662064018934149376 +1662064018976150272 +1662064019024151296 +1662064019066152192 +1662064019111153152 +1662064019153154048 +1662064019198155008 +1662064019243155968 +1662064019288156928 +1662064019327157760 +1662064019378158848 +1662064019417159680 +1662064019462160640 +1662064019507161600 +1662064019552162560 +1662064019594163456 +1662064019636164352 +1662064019672165120 +1662064019717166080 +1662064019756166912 +1662064019798167808 +1662064019843168768 +1662064019888169728 +1662064019936170752 +1662064019978171648 +1662064020020172544 +1662064020065173504 +1662064020107174400 +1662064020152175360 +1662064020194176256 +1662064020239177216 +1662064020284178176 +1662064020329179136 +1662064020377180160 +1662064020428181248 +1662064020479182336 +1662064020521183232 +1662064020572184320 +1662064020614185216 +1662064020662186240 +1662064020707187200 +1662064020752188160 +1662064020794189056 +1662064020836189952 +1662064020878190848 +1662064020923191808 +1662064020968192768 +1662064021013193728 +1662064021058194688 +1662064021100195584 +1662064021154196736 +1662064021205197824 +1662064021247198720 +1662064021289199616 +1662064021331200512 +1662064021373201408 +1662064021421202432 +1662064021463203328 +1662064021508204288 +1662064021553205248 +1662064021595206144 +1662064021637207040 +1662064021682208000 +1662064021724208896 +1662064021766209792 +1662064021811210752 +1662064021853211648 +1662064021901212672 +1662064021949213696 +1662064021994214656 +1662064022036215552 +1662064022081216512 +1662064022120217344 +1662064022162218240 +1662064022210219264 +1662064022255220224 +1662064022297221120 +1662064022342222080 +1662064022384222976 +1662064022432224000 +1662064022474224896 +1662064022525225984 +1662064022567226880 +1662064022612227840 +1662064022660228864 +1662064022702229760 +1662064022747230720 +1662064022789231616 +1662064022831232512 +1662064022888233728 +1662064022930234624 +1662064022978235648 +1662064023017236480 +1662064023065237504 +1662064023116238592 +1662064023155239424 +1662064023197240320 +1662064023239241216 +1662064023281242112 +1662064023323243008 +1662064023365243904 +1662064023407244800 +1662064023449245696 +1662064023500246784 +1662064023542247680 +1662064023584248576 +1662064023632249600 +1662064023677250560 +1662064023725251584 +1662064023767252480 +1662064023809253376 +1662064023857254400 +1662064023902255360 +1662064023944256256 +1662064023989257216 +1662064024031258112 +1662064024076259072 +1662064024127260160 +1662064024175261184 +1662064024217262080 +1662064024262263040 +1662064024304263936 +1662064024352264960 +1662064024397265920 +1662064024448267008 +1662064024496268032 +1662064024538268928 +1662064024583269888 +1662064024634270976 +1662064024679271936 +1662064024727272960 +1662064024778274048 +1662064024820274944 +1662064024871276032 +1662064024913276928 +1662064024955277824 +1662064024997278720 +1662064025039279616 +1662064025090280704 +1662064025129281536 +1662064025177282560 +1662064025228283648 +1662064025270284544 +1662064025312285440 +1662064025354286336 +1662064025396287232 +1662064025456288512 +1662064025507289600 +1662064025549290496 +1662064025594291456 +1662064025636292352 +1662064025678293248 +1662064025720294144 +1662064025768295168 +1662064025807296000 +1662064025852296960 +1662064025891297792 +1662064025933298688 +1662064025972299520 +1662064026020300544 +1662064026059301376 +1662064026101302272 +1662064026152303360 +1662064026197304320 +1662064026242305280 +1662064026284306176 +1662064026326307072 +1662064026368307968 +1662064026413308928 +1662064026455309824 +1662064026500310784 +1662064026539311616 +1662064026578312448 +1662064026620313344 +1662064026659314176 +1662064026701315072 +1662064026740315904 +1662064026785316864 +1662064026833317888 +1662064026878318848 +1662064026917319680 +1662064026962320640 +1662064027007321600 +1662064027061322752 +1662064027103323648 +1662064027142324480 +1662064027184325376 +1662064027226326272 +1662064027271327232 +1662064027313328128 +1662064027355329024 +1662064027397329920 +1662064027442330880 +1662064027484331776 +1662064027532332800 +1662064027571333632 +1662064027613334528 +1662064027655335424 +1662064027700336384 +1662064027745337344 +1662064027787338240 +1662064027832339200 +1662064027877340160 +1662064027922341120 +1662064027964342016 +1662064028006342912 +1662064028051343872 +1662064028093344768 +1662064028144345856 +1662064028192346880 +1662064028234347776 +1662064028288348928 +1662064028333349888 +1662064028378350848 +1662064028423351808 +1662064028462352640 +1662064028510353664 +1662064028549354496 +1662064028591355392 +1662064028636356352 +1662064028678357248 +1662064028723358208 +1662064028768359168 +1662064028810360064 +1662064028849360896 +1662064028891361792 +1662064028933362688 +1662064028975363584 +1662064029029364736 +1662064029071365632 +1662064029113366528 +1662064029158367488 +1662064029203368448 +1662064029245369344 +1662064029284370176 +1662064029329371136 +1662064029374372096 +1662064029416372992 +1662064029458373888 +1662064029503374848 +1662064029545375744 +1662064029593376768 +1662064029635377664 +1662064029683378688 +1662064029725379584 +1662064029767380480 +1662064029818381568 +1662064029866382592 +1662064029908383488 +1662064029950384384 +1662064029998385408 +1662064030052386560 +1662064030097387520 +1662064030145388544 +1662064030196389632 +1662064030238390528 +1662064030286391552 +1662064030331392512 +1662064030385393664 +1662064030430394624 +1662064030469395456 +1662064030514396416 +1662064030574397696 +1662064030616398592 +1662064030658399488 +1662064030700400384 +1662064030748401408 +1662064030793402368 +1662064030841403392 +1662064030886404352 +1662064030928405248 +1662064030979406336 +1662064031024407296 +1662064031066408192 +1662064031114409216 +1662064031156410112 +1662064031204411136 +1662064031246412032 +1662064031291412992 +1662064031333413888 +1662064031378414848 +1662064031417415680 +1662064031459416576 +1662064031519417856 +1662064031564418816 +1662064031612419840 +1662064031654420736 +1662064031699421696 +1662064031747422720 +1662064031798423808 +1662064031846424832 +1662064031888425728 +1662064031930426624 +1662064031972427520 +1662064032014428416 +1662064032056429312 +1662064032098430208 +1662064032143431168 +1662064032188432128 +1662064032230433024 +1662064032272433920 +1662064032314434816 +1662064032356435712 +1662064032401436672 +1662064032443437568 +1662064032488438528 +1662064032530439424 +1662064032584440576 +1662064032623441408 +1662064032665442304 +1662064032716443392 +1662064032758444288 +1662064032800445184 +1662064032845446144 +1662064032899447296 +1662064032947448320 +1662064032989449216 +1662064033031450112 +1662064033070450944 +1662064033112451840 +1662064033154452736 +1662064033205453824 +1662064033247454720 +1662064033295455744 +1662064033337456640 +1662064033385457664 +1662064033427458560 +1662064033472459520 +1662064033514460416 +1662064033559461376 +1662064033607462400 +1662064033652463360 +1662064033694464256 +1662064033736465152 +1662064033781466112 +1662064033826467072 +1662064033868467968 +1662064033910468864 +1662064033955469824 +1662064033997470720 +1662064034042471680 +1662064034084472576 +1662064034129473536 +1662064034168474368 +1662064034210475264 +1662064034252476160 +1662064034294477056 +1662064034336477952 +1662064034378478848 +1662064034417479680 +1662064034459480576 +1662064034504481536 +1662064034549482496 +1662064034597483520 +1662064034636484352 +1662064034681485312 +1662064034723486208 +1662064034765487104 +1662064034810488064 +1662064034855489024 +1662064034897489920 +1662064034936490752 +1662064034984491776 +1662064035032492800 +1662064035074493696 +1662064035122494720 +1662064035164495616 +1662064035206496512 +1662064035248497408 +1662064035290498304 +1662064035332499200 +1662064035374500096 +1662064035419501056 +1662064035458501888 +1662064035500502784 +1662064035542503680 +1662064035584504576 +1662064035626505472 +1662064035671506432 +1662064035713507328 +1662064035758508288 +1662064035806509312 +1662064035854510336 +1662064035896511232 +1662064035947512320 +1662064035995513344 +1662064036037514240 +1662064036085515264 +1662064036130516224 +1662064036172517120 +1662064036214518016 +1662064036256518912 +1662064036310520064 +1662064036352520960 +1662064036400521984 +1662064036445522944 +1662064036487523840 +1662064036529524736 +1662064036571525632 +1662064036613526528 +1662064036658527488 +1662064036697528320 +1662064036739529216 +1662064036787530240 +1662064036835531264 +1662064036877532160 +1662064036922533120 +1662064036967534080 +1662064037015535104 +1662064037057536000 +1662064037099536896 +1662064037147537920 +1662064037189538816 +1662064037234539776 +1662064037282540800 +1662064037324541696 +1662064037369542656 +1662064037408543488 +1662064037450544384 +1662064037492545280 +1662064037534546176 +1662064037576547072 +1662064037621548032 +1662064037663548928 +1662064037705549824 +1662064037750550784 +1662064037795551744 +1662064037843552768 +1662064037885553664 +1662064037930554624 +1662064037972555520 +1662064038014556416 +1662064038056557312 +1662064038104558336 +1662064038149559296 +1662064038191560192 +1662064038239561216 +1662064038281562112 +1662064038323563008 +1662064038365563904 +1662064038413564928 +1662064038455565824 +1662064038497566720 +1662064038542567680 +1662064038590568704 +1662064038638569728 +1662064038680570624 +1662064038719571456 +1662064038761572352 +1662064038806573312 +1662064038851574272 +1662064038896575232 +1662064038938576128 +1662064038983577088 +1662064039028578048 +1662064039076579072 +1662064039118579968 +1662064039160580864 +1662064039205581824 +1662064039253582848 +1662064039295583744 +1662064039340584704 +1662064039382585600 +1662064039424586496 +1662064039469587456 +1662064039508588288 +1662064039550589184 +1662064039595590144 +1662064039637591040 +1662064039685592064 +1662064039727592960 +1662064039766593792 +1662064039811594752 +1662064039853595648 +1662064039898596608 +1662064039940597504 +1662064039982598400 +1662064040024599296 +1662064040072600320 +1662064040114601216 +1662064040162602240 +1662064040207603200 +1662064040252604160 +1662064040303605248 +1662064040348606208 +1662064040390607104 +1662064040435608064 +1662064040477608960 +1662064040519609856 +1662064040561610752 +1662064040603611648 +1662064040642612480 +1662064040699613696 +1662064040738614528 +1662064040777615360 +1662064040819616256 +1662064040864617216 +1662064040906618112 +1662064040945618944 +1662064040990619904 +1662064041032620800 +1662064041074621696 +1662064041122622720 +1662064041164623616 +1662064041209624576 +1662064041254625536 +1662064041296626432 +1662064041347627520 +1662064041395628544 +1662064041443629568 +1662064041488630528 +1662064041533631488 +1662064041584632576 +1662064041629633536 +1662064041671634432 +1662064041713635328 +1662064041755636224 +1662064041806637312 +1662064041845638144 +1662064041887639040 +1662064041932640000 +1662064041977640960 +1662064042025641984 +1662064042076643072 +1662064042121644032 +1662064042163644928 +1662064042205645824 +1662064042247646720 +1662064042292647680 +1662064042334648576 +1662064042379649536 +1662064042424650496 +1662064042466651392 +1662064042508652288 +1662064042553653248 +1662064042598654208 +1662064042646655232 +1662064042691656192 +1662064042733657088 +1662064042778658048 +1662064042829659136 +1662064042871660032 +1662064042916660992 +1662064042964662016 +1662064043015663104 +1662064043057664000 +1662064043108665088 +1662064043153666048 +1662064043198667008 +1662064043240667904 +1662064043288668928 +1662064043330669824 +1662064043378670848 +1662064043423671808 +1662064043471672832 +1662064043513673728 +1662064043558674688 +1662064043603675648 +1662064043657676800 +1662064043705677824 +1662064043750678784 +1662064043792679680 +1662064043843680768 +1662064043882681600 +1662064043927682560 +1662064043966683392 +1662064044011684352 +1662064044062685440 +1662064044107686400 +1662064044146687232 +1662064044197688320 +1662064044239689216 +1662064044290690304 +1662064044332691200 +1662064044383692288 +1662064044431693312 +1662064044473694208 +1662064044515695104 +1662064044563696128 +1662064044602696960 +1662064044647697920 +1662064044698699008 +1662064044743699968 +1662064044788700928 +1662064044830701824 +1662064044872702720 +1662064044923703808 +1662064044965704704 +1662064045016705792 +1662064045058706688 +1662064045100707584 +1662064045145708544 +1662064045187709440 +1662064045238710528 +1662064045280711424 +1662064045328712448 +1662064045370713344 +1662064045415714304 +1662064045454715136 +1662064045496716032 +1662064045544717056 +1662064045589718016 +1662064045634718976 +1662064045679719936 +1662064045721720832 +1662064045763721728 +1662064045805722624 +1662064045850723584 +1662064045895724544 +1662064045940725504 +1662064045982726400 +1662064046027727360 +1662064046075728384 +1662064046123729408 +1662064046165730304 +1662064046207731200 +1662064046258732288 +1662064046303733248 +1662064046351734272 +1662064046396735232 +1662064046441736192 +1662064046492737280 +1662064046534738176 +1662064046576739072 +1662064046621740032 +1662064046666740992 +1662064046711741952 +1662064046756742912 +1662064046804743936 +1662064046846744832 +1662064046885745664 +1662064046927746560 +1662064046969747456 +1662064047014748416 +1662064047056749312 +1662064047101750272 +1662064047149751296 +1662064047194752256 +1662064047239753216 +1662064047284754176 +1662064047326755072 +1662064047371756032 +1662064047419757056 +1662064047464758016 +1662064047509758976 +1662064047554759936 +1662064047605761024 +1662064047653762048 +1662064047707763200 +1662064047752764160 +1662064047794765056 +1662064047836765952 +1662064047878766848 +1662064047923767808 +1662064047965768704 +1662064048010769664 +1662064048052770560 +1662064048094771456 +1662064048142772480 +1662064048184773376 +1662064048226774272 +1662064048277775360 +1662064048319776256 +1662064048361777152 +1662064048406778112 +1662064048448779008 +1662064048493779968 +1662064048535780864 +1662064048577781760 +1662064048619782656 +1662064048664783616 +1662064048706784512 +1662064048754785536 +1662064048793786368 +1662064048832787200 +1662064048877788160 +1662064048922789120 +1662064048967790080 +1662064049009790976 +1662064049048791808 +1662064049096792832 +1662064049141793792 +1662064049186794752 +1662064049234795776 +1662064049276796672 +1662064049318797568 +1662064049366798592 +1662064049408799488 +1662064049450800384 +1662064049495801344 +1662064049537802240 +1662064049576803072 +1662064049618803968 +1662064049660804864 +1662064049702805760 +1662064049744806656 +1662064049789807616 +1662064049834808576 +1662064049876809472 +1662064049918810368 +1662064049960811264 +1662064050002812160 +1662064050053813248 +1662064050095814144 +1662064050137815040 +1662064050179815936 +1662064050221816832 +1662064050263817728 +1662064050305818624 +1662064050347819520 +1662064050389820416 +1662064050434821376 +1662064050482822400 +1662064050524823296 +1662064050584824576 +1662064050626825472 +1662064050668826368 +1662064050713827328 +1662064050755828224 +1662064050797829120 +1662064050845830144 +1662064050887831040 +1662064050932832000 +1662064050977832960 +1662064051016833792 +1662064051070834944 +1662064051115835904 +1662064051157836800 +1662064051199837696 +1662064051241838592 +1662064051283839488 +1662064051325840384 +1662064051367841280 +1662064051409842176 +1662064051454843136 +1662064051499844096 +1662064051544845056 +1662064051592846080 +1662064051631846912 +1662064051673847808 +1662064051715848704 +1662064051763849728 +1662064051808850688 +1662064051853851648 +1662064051901852672 +1662064051943853568 +1662064051985854464 +1662064052036855552 +1662064052081856512 +1662064052129857536 +1662064052171858432 +1662064052213859328 +1662064052261860352 +1662064052303861248 +1662064052345862144 +1662064052387863040 +1662064052438864128 +1662064052483865088 +1662064052525865984 +1662064052573867008 +1662064052624868096 +1662064052669869056 +1662064052714870016 +1662064052759870976 +1662064052795871744 +1662064052840872704 +1662064052885873664 +1662064052924874496 +1662064052969875456 +1662064053011876352 +1662064053056877312 +1662064053098878208 +1662064053143879168 +1662064053188880128 +1662064053233881088 +1662064053278882048 +1662064053323883008 +1662064053365883904 +1662064053407884800 +1662064053452885760 +1662064053491886592 +1662064053533887488 +1662064053575888384 +1662064053614889216 +1662064053659890176 +1662064053698891008 +1662064053746892032 +1662064053791892992 +1662064053842894080 +1662064053884894976 +1662064053929895936 +1662064053974896896 +1662064054019897856 +1662064054061898752 +1662064054103899648 +1662064054142900480 +1662064054184901376 +1662064054223902208 +1662064054265903104 +1662064054307904000 +1662064054355905024 +1662064054409906176 +1662064054457907200 +1662064054502908160 +1662064054541908992 +1662064054589910016 +1662064054631910912 +1662064054676911872 +1662064054727912960 +1662064054772913920 +1662064054814914816 +1662064054865915904 +1662064054910916864 +1662064054946917632 +1662064054997918720 +1662064055042919680 +1662064055090920704 +1662064055138921728 +1662064055180922624 +1662064055225923584 +1662064055270924544 +1662064055315925504 +1662064055360926464 diff --git a/Examples/Monocular-Inertial/MIMIR_TimeStamps/SandPipe_track0_light.txt b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SandPipe_track0_light.txt new file mode 100644 index 0000000000..b9447370b4 --- /dev/null +++ b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SandPipe_track0_light.txt @@ -0,0 +1,2605 @@ +1662121584099220736 +1662121584144221696 +1662121584186222592 +1662121584234223616 +1662121584279224576 +1662121584321225472 +1662121584369226496 +1662121584417227520 +1662121584459228416 +1662121584498229248 +1662121584540230144 +1662121584582231040 +1662121584624231936 +1662121584669232896 +1662121584717233920 +1662121584762234880 +1662121584807235840 +1662121584855236864 +1662121584900237824 +1662121584942238720 +1662121584987239680 +1662121585032240640 +1662121585074241536 +1662121585119242496 +1662121585161243392 +1662121585203244288 +1662121585251245312 +1662121585296246272 +1662121585338247168 +1662121585389248256 +1662121585434249216 +1662121585476250112 +1662121585524251136 +1662121585575252224 +1662121585617253120 +1662121585671254272 +1662121585716255232 +1662121585758256128 +1662121585803257088 +1662121585845257984 +1662121585887258880 +1662121585932259840 +1662121585977260800 +1662121586019261696 +1662121586061262592 +1662121586106263552 +1662121586151264512 +1662121586193265408 +1662121586235266304 +1662121586277267200 +1662121586319268096 +1662121586364269056 +1662121586409270016 +1662121586460271104 +1662121586502272000 +1662121586553273088 +1662121586595273984 +1662121586634274816 +1662121586679275776 +1662121586724276736 +1662121586766277632 +1662121586823278848 +1662121586868279808 +1662121586916280832 +1662121586961281792 +1662121587003282688 +1662121587048283648 +1662121587093284608 +1662121587135285504 +1662121587177286400 +1662121587216287232 +1662121587258288128 +1662121587303289088 +1662121587345289984 +1662121587387290880 +1662121587429291776 +1662121587474292736 +1662121587522293760 +1662121587567294720 +1662121587615295744 +1662121587657296640 +1662121587702297600 +1662121587747298560 +1662121587789299456 +1662121587834300416 +1662121587876301312 +1662121587921302272 +1662121587966303232 +1662121588008304128 +1662121588053305088 +1662121588101306112 +1662121588143307008 +1662121588197308160 +1662121588245309184 +1662121588290310144 +1662121588332311040 +1662121588383312128 +1662121588428313088 +1662121588470313984 +1662121588512314880 +1662121588557315840 +1662121588602316800 +1662121588644317696 +1662121588686318592 +1662121588737319680 +1662121588779320576 +1662121588821321472 +1662121588872322560 +1662121588914323456 +1662121588962324480 +1662121589004325376 +1662121589043326208 +1662121589088327168 +1662121589130328064 +1662121589172328960 +1662121589214329856 +1662121589265330944 +1662121589307331840 +1662121589349332736 +1662121589397333760 +1662121589439334656 +1662121589478335488 +1662121589520336384 +1662121589565337344 +1662121589604338176 +1662121589646339072 +1662121589691340032 +1662121589739341056 +1662121589784342016 +1662121589826342912 +1662121589871343872 +1662121589919344896 +1662121589961345792 +1662121590003346688 +1662121590051347712 +1662121590093348608 +1662121590135349504 +1662121590183350528 +1662121590228351488 +1662121590279352576 +1662121590321353472 +1662121590360354304 +1662121590405355264 +1662121590447356160 +1662121590492357120 +1662121590540358144 +1662121590579358976 +1662121590621359872 +1662121590663360768 +1662121590705361664 +1662121590747362560 +1662121590792363520 +1662121590837364480 +1662121590885365504 +1662121590927366400 +1662121590969367296 +1662121591014368256 +1662121591062369280 +1662121591107370240 +1662121591155371264 +1662121591194372096 +1662121591236372992 +1662121591284374016 +1662121591329374976 +1662121591374375936 +1662121591428377088 +1662121591473378048 +1662121591518379008 +1662121591560379904 +1662121591611380992 +1662121591650381824 +1662121591701382912 +1662121591743383808 +1662121591785384704 +1662121591830385664 +1662121591875386624 +1662121591917387520 +1662121591962388480 +1662121592007389440 +1662121592049390336 +1662121592091391232 +1662121592133392128 +1662121592175393024 +1662121592226394112 +1662121592268395008 +1662121592313395968 +1662121592352396800 +1662121592391397632 +1662121592439398656 +1662121592496399872 +1662121592538400768 +1662121592583401728 +1662121592625402624 +1662121592670403584 +1662121592712404480 +1662121592751405312 +1662121592799406336 +1662121592844407296 +1662121592883408128 +1662121592925409024 +1662121592970409984 +1662121593024411136 +1662121593069412096 +1662121593114413056 +1662121593156413952 +1662121593201414912 +1662121593246415872 +1662121593294416896 +1662121593342417920 +1662121593390418944 +1662121593444420096 +1662121593486420992 +1662121593531421952 +1662121593576422912 +1662121593627424000 +1662121593672424960 +1662121593726426112 +1662121593777427200 +1662121593816428032 +1662121593855428864 +1662121593900429824 +1662121593948430848 +1662121594005432064 +1662121594050433024 +1662121594092433920 +1662121594143435008 +1662121594185435904 +1662121594230436864 +1662121594278437888 +1662121594323438848 +1662121594371439872 +1662121594416440832 +1662121594461441792 +1662121594503442688 +1662121594551443712 +1662121594599444736 +1662121594641445632 +1662121594683446528 +1662121594725447424 +1662121594770448384 +1662121594812449280 +1662121594857450240 +1662121594899451136 +1662121594941452032 +1662121594983452928 +1662121595034454016 +1662121595076454912 +1662121595124455936 +1662121595184457216 +1662121595226458112 +1662121595274459136 +1662121595316460032 +1662121595361460992 +1662121595406461952 +1662121595454462976 +1662121595496463872 +1662121595541464832 +1662121595583465728 +1662121595631466752 +1662121595676467712 +1662121595724468736 +1662121595772469760 +1662121595826470912 +1662121595868471808 +1662121595919472896 +1662121595964473856 +1662121596006474752 +1662121596051475712 +1662121596099476736 +1662121596144477696 +1662121596186478592 +1662121596234479616 +1662121596276480512 +1662121596318481408 +1662121596357482240 +1662121596399483136 +1662121596447484160 +1662121596489485056 +1662121596534486016 +1662121596576486912 +1662121596630488064 +1662121596675489024 +1662121596720489984 +1662121596768491008 +1662121596819492096 +1662121596861492992 +1662121596912494080 +1662121596951494912 +1662121596993495808 +1662121597038496768 +1662121597083497728 +1662121597125498624 +1662121597173499648 +1662121597215500544 +1662121597260501504 +1662121597305502464 +1662121597344503296 +1662121597389504256 +1662121597443505408 +1662121597485506304 +1662121597524507136 +1662121597572508160 +1662121597617509120 +1662121597662510080 +1662121597710511104 +1662121597761512192 +1662121597812513280 +1662121597863514368 +1662121597908515328 +1662121597950516224 +1662121598001517312 +1662121598043518208 +1662121598097519360 +1662121598148520448 +1662121598190521344 +1662121598238522368 +1662121598283523328 +1662121598334524416 +1662121598379525376 +1662121598427526400 +1662121598472527360 +1662121598520528384 +1662121598565529344 +1662121598607530240 +1662121598652531200 +1662121598694532096 +1662121598742533120 +1662121598781533952 +1662121598823534848 +1662121598868535808 +1662121598913536768 +1662121598955537664 +1662121598997538560 +1662121599042539520 +1662121599090540544 +1662121599135541504 +1662121599183542528 +1662121599231543552 +1662121599279544576 +1662121599324545536 +1662121599369546496 +1662121599411547392 +1662121599456548352 +1662121599498549248 +1662121599543550208 +1662121599585551104 +1662121599633552128 +1662121599678553088 +1662121599717553920 +1662121599762554880 +1662121599807555840 +1662121599852556800 +1662121599894557696 +1662121599936558592 +1662121599984559616 +1662121600026560512 +1662121600071561472 +1662121600122562560 +1662121600179563776 +1662121600221564672 +1662121600263565568 +1662121600302566400 +1662121600350567424 +1662121600395568384 +1662121600437569280 +1662121600482570240 +1662121600536571392 +1662121600581572352 +1662121600623573248 +1662121600665574144 +1662121600710575104 +1662121600752576000 +1662121600806577152 +1662121600848578048 +1662121600890578944 +1662121600932579840 +1662121600974580736 +1662121601025581824 +1662121601070582784 +1662121601115583744 +1662121601157584640 +1662121601205585664 +1662121601247586560 +1662121601289587456 +1662121601337588480 +1662121601382589440 +1662121601433590528 +1662121601475591424 +1662121601517592320 +1662121601559593216 +1662121601604594176 +1662121601652595200 +1662121601697596160 +1662121601742597120 +1662121601784598016 +1662121601835599104 +1662121601880600064 +1662121601928601088 +1662121601970601984 +1662121602027603200 +1662121602075604224 +1662121602117605120 +1662121602162606080 +1662121602204606976 +1662121602255608064 +1662121602297608960 +1662121602336609792 +1662121602378610688 +1662121602426611712 +1662121602468612608 +1662121602519613696 +1662121602555614464 +1662121602600615424 +1662121602645616384 +1662121602699617536 +1662121602741618432 +1662121602783619328 +1662121602825620224 +1662121602867621120 +1662121602909622016 +1662121602951622912 +1662121602999623936 +1662121603047624960 +1662121603089625856 +1662121603140626944 +1662121603185627904 +1662121603227628800 +1662121603281629952 +1662121603326630912 +1662121603368631808 +1662121603422632960 +1662121603467633920 +1662121603509634816 +1662121603563635968 +1662121603608636928 +1662121603650637824 +1662121603692638720 +1662121603734639616 +1662121603776640512 +1662121603818641408 +1662121603860642304 +1662121603905643264 +1662121603953644288 +1662121604001645312 +1662121604043646208 +1662121604088647168 +1662121604133648128 +1662121604175649024 +1662121604217649920 +1662121604262650880 +1662121604307651840 +1662121604355652864 +1662121604394653696 +1662121604442654720 +1662121604484655616 +1662121604523656448 +1662121604574657536 +1662121604619658496 +1662121604664659456 +1662121604709660416 +1662121604754661376 +1662121604805662464 +1662121604850663424 +1662121604895664384 +1662121604940665344 +1662121604988666368 +1662121605042667520 +1662121605084668416 +1662121605129669376 +1662121605174670336 +1662121605216671232 +1662121605255672064 +1662121605300673024 +1662121605342673920 +1662121605396675072 +1662121605438675968 +1662121605480676864 +1662121605528677888 +1662121605573678848 +1662121605618679808 +1662121605663680768 +1662121605705681664 +1662121605747682560 +1662121605798683648 +1662121605840684544 +1662121605882685440 +1662121605930686464 +1662121605975687424 +1662121606017688320 +1662121606059689216 +1662121606104690176 +1662121606146691072 +1662121606188691968 +1662121606230692864 +1662121606275693824 +1662121606323694848 +1662121606368695808 +1662121606413696768 +1662121606455697664 +1662121606497698560 +1662121606542699520 +1662121606587700480 +1662121606626701312 +1662121606665702144 +1662121606710703104 +1662121606758704128 +1662121606803705088 +1662121606857706240 +1662121606902707200 +1662121606944708096 +1662121606986708992 +1662121607031709952 +1662121607076710912 +1662121607124711936 +1662121607169712896 +1662121607217713920 +1662121607262714880 +1662121607304715776 +1662121607346716672 +1662121607391717632 +1662121607436718592 +1662121607487719680 +1662121607532720640 +1662121607577721600 +1662121607628722688 +1662121607670723584 +1662121607715724544 +1662121607763725568 +1662121607805726464 +1662121607847727360 +1662121607889728256 +1662121607928729088 +1662121607970729984 +1662121608018731008 +1662121608060731904 +1662121608102732800 +1662121608147733760 +1662121608198734848 +1662121608246735872 +1662121608288736768 +1662121608333737728 +1662121608375738624 +1662121608426739712 +1662121608468740608 +1662121608510741504 +1662121608552742400 +1662121608597743360 +1662121608639744256 +1662121608681745152 +1662121608729746176 +1662121608777747200 +1662121608822748160 +1662121608867749120 +1662121608909750016 +1662121608951750912 +1662121609002752000 +1662121609044752896 +1662121609086753792 +1662121609134754816 +1662121609182755840 +1662121609230756864 +1662121609272757760 +1662121609317758720 +1662121609359759616 +1662121609398760448 +1662121609443761408 +1662121609491762432 +1662121609533763328 +1662121609575764224 +1662121609617765120 +1662121609662766080 +1662121609710767104 +1662121609755768064 +1662121609797768960 +1662121609839769856 +1662121609884770816 +1662121609935771904 +1662121609977772800 +1662121610022773760 +1662121610064774656 +1662121610106775552 +1662121610151776512 +1662121610196777472 +1662121610238778368 +1662121610292779520 +1662121610331780352 +1662121610382781440 +1662121610427782400 +1662121610469783296 +1662121610511784192 +1662121610559785216 +1662121610604786176 +1662121610646787072 +1662121610691788032 +1662121610733788928 +1662121610787790080 +1662121610832791040 +1662121610874791936 +1662121610922792960 +1662121610964793856 +1662121611006794752 +1662121611048795648 +1662121611096796672 +1662121611147797760 +1662121611198798848 +1662121611252800000 +1662121611294800896 +1662121611336801792 +1662121611381802752 +1662121611432803840 +1662121611474804736 +1662121611519805696 +1662121611561806592 +1662121611603807488 +1662121611651808512 +1662121611702809600 +1662121611747810560 +1662121611789811456 +1662121611834812416 +1662121611879813376 +1662121611927814400 +1662121611972815360 +1662121612017816320 +1662121612062817280 +1662121612107818240 +1662121612152819200 +1662121612194820096 +1662121612236820992 +1662121612278821888 +1662121612323822848 +1662121612368823808 +1662121612410824704 +1662121612449825536 +1662121612491826432 +1662121612548827648 +1662121612593828608 +1662121612635829504 +1662121612683830528 +1662121612731831552 +1662121612770832384 +1662121612818833408 +1662121612860834304 +1662121612902835200 +1662121612947836160 +1662121612989837056 +1662121613037838080 +1662121613082839040 +1662121613124839936 +1662121613166840832 +1662121613211841792 +1662121613259842816 +1662121613307843840 +1662121613349844736 +1662121613397845760 +1662121613442846720 +1662121613484847616 +1662121613526848512 +1662121613577849600 +1662121613625850624 +1662121613670851584 +1662121613724852736 +1662121613769853696 +1662121613817854720 +1662121613859855616 +1662121613907856640 +1662121613958857728 +1662121614009858816 +1662121614054859776 +1662121614096860672 +1662121614138861568 +1662121614177862400 +1662121614219863296 +1662121614267864320 +1662121614318865408 +1662121614360866304 +1662121614405867264 +1662121614450868224 +1662121614492869120 +1662121614540870144 +1662121614582871040 +1662121614630872064 +1662121614672872960 +1662121614720873984 +1662121614768875008 +1662121614816876032 +1662121614855876864 +1662121614897877760 +1662121614939878656 +1662121614987879680 +1662121615032880640 +1662121615077881600 +1662121615119882496 +1662121615164883456 +1662121615209884416 +1662121615254885376 +1662121615302886400 +1662121615350887424 +1662121615395888384 +1662121615443889408 +1662121615488890368 +1662121615530891264 +1662121615584892416 +1662121615626893312 +1662121615668894208 +1662121615707895040 +1662121615752896000 +1662121615800897024 +1662121615845897984 +1662121615896899072 +1662121615947900160 +1662121615992901120 +1662121616034902016 +1662121616079902976 +1662121616127904000 +1662121616178905088 +1662121616223906048 +1662121616268907008 +1662121616316908032 +1662121616358908928 +1662121616412910080 +1662121616463911168 +1662121616505912064 +1662121616547912960 +1662121616589913856 +1662121616634914816 +1662121616679915776 +1662121616727916800 +1662121616769917696 +1662121616823918848 +1662121616865919744 +1662121616913920768 +1662121616955921664 +1662121616997922560 +1662121617045923584 +1662121617087924480 +1662121617132925440 +1662121617177926400 +1662121617222927360 +1662121617264928256 +1662121617312929280 +1662121617360930304 +1662121617402931200 +1662121617444932096 +1662121617501933312 +1662121617543934208 +1662121617591935232 +1662121617639936256 +1662121617690937344 +1662121617741938432 +1662121617789939456 +1662121617831940352 +1662121617873941248 +1662121617918942208 +1662121617966943232 +1662121618014944256 +1662121618062945280 +1662121618104946176 +1662121618149947136 +1662121618200948224 +1662121618245949184 +1662121618287950080 +1662121618326950912 +1662121618368951808 +1662121618410952704 +1662121618452953600 +1662121618500954624 +1662121618545955584 +1662121618599956736 +1662121618641957632 +1662121618686958592 +1662121618728959488 +1662121618770960384 +1662121618815961344 +1662121618863962368 +1662121618905963264 +1662121618947964160 +1662121618992965120 +1662121619034966016 +1662121619079966976 +1662121619124967936 +1662121619166968832 +1662121619211969792 +1662121619253970688 +1662121619304971776 +1662121619346972672 +1662121619400973824 +1662121619442974720 +1662121619490975744 +1662121619535976704 +1662121619577977600 +1662121619619978496 +1662121619667979520 +1662121619706980352 +1662121619751981312 +1662121619802982400 +1662121619847983360 +1662121619892984320 +1662121619937985280 +1662121619979986176 +1662121620027987200 +1662121620075988224 +1662121620117989120 +1662121620162990080 +1662121620207991040 +1662121620252992000 +1662121620306993152 +1662121620351994112 +1662121620396995072 +1662121620438995968 +1662121620480996864 +1662121620525997824 +1662121620570998784 +1662121620615999744 +1662121620658000640 +1662121620703001600 +1662121620757002752 +1662121620799003648 +1662121620847004672 +1662121620892005632 +1662121620934006528 +1662121620976007424 +1662121621018008320 +1662121621060009216 +1662121621111010304 +1662121621159011328 +1662121621204012288 +1662121621246013184 +1662121621291014144 +1662121621330014976 +1662121621372015872 +1662121621414016768 +1662121621462017792 +1662121621507018752 +1662121621555019776 +1662121621594020608 +1662121621645021696 +1662121621687022592 +1662121621729023488 +1662121621774024448 +1662121621816025344 +1662121621861026304 +1662121621912027392 +1662121621957028352 +1662121622005029376 +1662121622050030336 +1662121622095031296 +1662121622137032192 +1662121622182033152 +1662121622227034112 +1662121622272035072 +1662121622323036160 +1662121622374037248 +1662121622413038080 +1662121622458039040 +1662121622503040000 +1662121622548040960 +1662121622593041920 +1662121622638042880 +1662121622686043904 +1662121622731044864 +1662121622773045760 +1662121622818046720 +1662121622863047680 +1662121622908048640 +1662121622953049600 +1662121623001050624 +1662121623049051648 +1662121623097052672 +1662121623148053760 +1662121623193054720 +1662121623238055680 +1662121623295056896 +1662121623340057856 +1662121623385058816 +1662121623427059712 +1662121623472060672 +1662121623514061568 +1662121623559062528 +1662121623604063488 +1662121623658064640 +1662121623700065536 +1662121623742066432 +1662121623784067328 +1662121623829068288 +1662121623877069312 +1662121623919070208 +1662121623961071104 +1662121624006072064 +1662121624051073024 +1662121624093073920 +1662121624135074816 +1662121624180075776 +1662121624225076736 +1662121624279077888 +1662121624324078848 +1662121624369079808 +1662121624411080704 +1662121624456081664 +1662121624498082560 +1662121624543083520 +1662121624594084608 +1662121624642085632 +1662121624687086592 +1662121624735087616 +1662121624780088576 +1662121624828089600 +1662121624879090688 +1662121624924091648 +1662121624966092544 +1662121625020093696 +1662121625065094656 +1662121625107095552 +1662121625152096512 +1662121625197097472 +1662121625239098368 +1662121625284099328 +1662121625335100416 +1662121625380101376 +1662121625425102336 +1662121625467103232 +1662121625512104192 +1662121625560105216 +1662121625608106240 +1662121625653107200 +1662121625698108160 +1662121625752109312 +1662121625797110272 +1662121625839111168 +1662121625887112192 +1662121625929113088 +1662121625977114112 +1662121626016114944 +1662121626058115840 +1662121626100116736 +1662121626148117760 +1662121626193118720 +1662121626241119744 +1662121626283120640 +1662121626325121536 +1662121626370122496 +1662121626412123392 +1662121626457124352 +1662121626502125312 +1662121626544126208 +1662121626589127168 +1662121626631128064 +1662121626673128960 +1662121626715129856 +1662121626760130816 +1662121626808131840 +1662121626859132928 +1662121626904133888 +1662121626952134912 +1662121626997135872 +1662121627042136832 +1662121627090137856 +1662121627135138816 +1662121627177139712 +1662121627228140800 +1662121627276141824 +1662121627318142720 +1662121627360143616 +1662121627405144576 +1662121627447145472 +1662121627498146560 +1662121627549147648 +1662121627597148672 +1662121627639149568 +1662121627690150656 +1662121627732151552 +1662121627774152448 +1662121627816153344 +1662121627858154240 +1662121627900155136 +1662121627942156032 +1662121627984156928 +1662121628029157888 +1662121628071158784 +1662121628119159808 +1662121628173160960 +1662121628212161792 +1662121628254162688 +1662121628299163648 +1662121628350164736 +1662121628398165760 +1662121628440166656 +1662121628488167680 +1662121628533168640 +1662121628581169664 +1662121628623170560 +1662121628671171584 +1662121628722172672 +1662121628770173696 +1662121628818174720 +1662121628860175616 +1662121628908176640 +1662121628953177600 +1662121629001178624 +1662121629049179648 +1662121629094180608 +1662121629145181696 +1662121629196182784 +1662121629244183808 +1662121629289184768 +1662121629331185664 +1662121629376186624 +1662121629424187648 +1662121629472188672 +1662121629517189632 +1662121629571190784 +1662121629616191744 +1662121629661192704 +1662121629703193600 +1662121629739194368 +1662121629787195392 +1662121629838196480 +1662121629883197440 +1662121629931198464 +1662121629973199360 +1662121630015200256 +1662121630057201152 +1662121630102202112 +1662121630153203200 +1662121630195204096 +1662121630237204992 +1662121630282205952 +1662121630324206848 +1662121630369207808 +1662121630423208960 +1662121630474210048 +1662121630525211136 +1662121630582212352 +1662121630621213184 +1662121630660214016 +1662121630702214912 +1662121630750215936 +1662121630792216832 +1662121630843217920 +1662121630885218816 +1662121630933219840 +1662121630975220736 +1662121631026221824 +1662121631068222720 +1662121631119223808 +1662121631167224832 +1662121631212225792 +1662121631254226688 +1662121631305227776 +1662121631347228672 +1662121631389229568 +1662121631431230464 +1662121631482231552 +1662121631530232576 +1662121631575233536 +1662121631620234496 +1662121631662235392 +1662121631707236352 +1662121631752237312 +1662121631800238336 +1662121631854239488 +1662121631896240384 +1662121631938241280 +1662121631983242240 +1662121632022243072 +1662121632064243968 +1662121632109244928 +1662121632154245888 +1662121632196246784 +1662121632244247808 +1662121632289248768 +1662121632334249728 +1662121632382250752 +1662121632424251648 +1662121632466252544 +1662121632508253440 +1662121632553254400 +1662121632598255360 +1662121632649256448 +1662121632697257472 +1662121632751258624 +1662121632793259520 +1662121632838260480 +1662121632883261440 +1662121632925262336 +1662121632976263424 +1662121633018264320 +1662121633066265344 +1662121633111266304 +1662121633159267328 +1662121633204268288 +1662121633246269184 +1662121633291270144 +1662121633339271168 +1662121633390272256 +1662121633435273216 +1662121633477274112 +1662121633519275008 +1662121633564275968 +1662121633609276928 +1662121633651277824 +1662121633696278784 +1662121633738279680 +1662121633786280704 +1662121633828281600 +1662121633876282624 +1662121633921283584 +1662121633963284480 +1662121634008285440 +1662121634050286336 +1662121634098287360 +1662121634143288320 +1662121634185289216 +1662121634233290240 +1662121634281291264 +1662121634320292096 +1662121634368293120 +1662121634422294272 +1662121634467295232 +1662121634515296256 +1662121634554297088 +1662121634602298112 +1662121634644299008 +1662121634692300032 +1662121634746301184 +1662121634797302272 +1662121634842303232 +1662121634884304128 +1662121634929305088 +1662121634980306176 +1662121635022307072 +1662121635073308160 +1662121635124309248 +1662121635169310208 +1662121635211311104 +1662121635262312192 +1662121635307313152 +1662121635349314048 +1662121635391314944 +1662121635436315904 +1662121635484316928 +1662121635526317824 +1662121635574318848 +1662121635622319872 +1662121635670320896 +1662121635724322048 +1662121635769323008 +1662121635811323904 +1662121635853324800 +1662121635901325824 +1662121635946326784 +1662121635991327744 +1662121636033328640 +1662121636078329600 +1662121636123330560 +1662121636174331648 +1662121636219332608 +1662121636267333632 +1662121636309334528 +1662121636351335424 +1662121636396336384 +1662121636438337280 +1662121636480338176 +1662121636525339136 +1662121636567340032 +1662121636609340928 +1662121636657341952 +1662121636702342912 +1662121636744343808 +1662121636789344768 +1662121636840345856 +1662121636894347008 +1662121636942348032 +1662121636987348992 +1662121637029349888 +1662121637074350848 +1662121637125351936 +1662121637170352896 +1662121637212353792 +1662121637254354688 +1662121637302355712 +1662121637350356736 +1662121637398357760 +1662121637443358720 +1662121637485359616 +1662121637533360640 +1662121637587361792 +1662121637632362752 +1662121637677363712 +1662121637719364608 +1662121637761365504 +1662121637803366400 +1662121637848367360 +1662121637887368192 +1662121637929369088 +1662121637974370048 +1662121638019371008 +1662121638061371904 +1662121638103372800 +1662121638145373696 +1662121638190374656 +1662121638232375552 +1662121638277376512 +1662121638319377408 +1662121638361378304 +1662121638406379264 +1662121638448380160 +1662121638490381056 +1662121638532381952 +1662121638574382848 +1662121638616383744 +1662121638655384576 +1662121638703385600 +1662121638748386560 +1662121638799387648 +1662121638841388544 +1662121638895389696 +1662121638937390592 +1662121638979391488 +1662121639024392448 +1662121639063393280 +1662121639105394176 +1662121639159395328 +1662121639204396288 +1662121639249397248 +1662121639300398336 +1662121639342399232 +1662121639387400192 +1662121639432401152 +1662121639477402112 +1662121639519403008 +1662121639564403968 +1662121639609404928 +1662121639651405824 +1662121639699406848 +1662121639750407936 +1662121639792408832 +1662121639834409728 +1662121639876410624 +1662121639924411648 +1662121639969412608 +1662121640011413504 +1662121640062414592 +1662121640113415680 +1662121640155416576 +1662121640197417472 +1662121640239418368 +1662121640284419328 +1662121640326420224 +1662121640371421184 +1662121640419422208 +1662121640464423168 +1662121640506424064 +1662121640554425088 +1662121640590425856 +1662121640644427008 +1662121640692428032 +1662121640737428992 +1662121640785430016 +1662121640824430848 +1662121640866431744 +1662121640911432704 +1662121640959433728 +1662121641004434688 +1662121641049435648 +1662121641091436544 +1662121641142437632 +1662121641193438720 +1662121641238439680 +1662121641283440640 +1662121641337441792 +1662121641379442688 +1662121641421443584 +1662121641463444480 +1662121641505445376 +1662121641550446336 +1662121641601447424 +1662121641643448320 +1662121641694449408 +1662121641739450368 +1662121641778451200 +1662121641823452160 +1662121641868453120 +1662121641907453952 +1662121641952454912 +1662121641997455872 +1662121642042456832 +1662121642090457856 +1662121642132458752 +1662121642174459648 +1662121642219460608 +1662121642264461568 +1662121642312462592 +1662121642354463488 +1662121642399464448 +1662121642441465344 +1662121642483466240 +1662121642528467200 +1662121642570468096 +1662121642612468992 +1662121642660470016 +1662121642705470976 +1662121642747471872 +1662121642801473024 +1662121642843473920 +1662121642891474944 +1662121642939475968 +1662121642981476864 +1662121643023477760 +1662121643065478656 +1662121643107479552 +1662121643149480448 +1662121643191481344 +1662121643233482240 +1662121643275483136 +1662121643317484032 +1662121643362484992 +1662121643410486016 +1662121643455486976 +1662121643503488000 +1662121643542488832 +1662121643587489792 +1662121643629490688 +1662121643674491648 +1662121643719492608 +1662121643764493568 +1662121643806494464 +1662121643845495296 +1662121643887496192 +1662121643932497152 +1662121643983498240 +1662121644034499328 +1662121644079500288 +1662121644121501184 +1662121644160502016 +1662121644208503040 +1662121644250503936 +1662121644295504896 +1662121644337505792 +1662121644385506816 +1662121644433507840 +1662121644478508800 +1662121644526509824 +1662121644568510720 +1662121644613511680 +1662121644658512640 +1662121644706513664 +1662121644748514560 +1662121644799515648 +1662121644853516800 +1662121644898517760 +1662121644940518656 +1662121644988519680 +1662121645033520640 +1662121645078521600 +1662121645120522496 +1662121645162523392 +1662121645210524416 +1662121645252525312 +1662121645300526336 +1662121645342527232 +1662121645384528128 +1662121645426529024 +1662121645468529920 +1662121645510530816 +1662121645561531904 +1662121645603532800 +1662121645645533696 +1662121645690534656 +1662121645735535616 +1662121645780536576 +1662121645825537536 +1662121645870538496 +1662121645912539392 +1662121645957540352 +1662121646005541376 +1662121646053542400 +1662121646107543552 +1662121646149544448 +1662121646197545472 +1662121646239546368 +1662121646281547264 +1662121646329548288 +1662121646371549184 +1662121646419550208 +1662121646470551296 +1662121646521552384 +1662121646566553344 +1662121646611554304 +1662121646653555200 +1662121646698556160 +1662121646737556992 +1662121646779557888 +1662121646824558848 +1662121646869559808 +1662121646911560704 +1662121646956561664 +1662121646998562560 +1662121647040563456 +1662121647085564416 +1662121647127565312 +1662121647172566272 +1662121647214567168 +1662121647262568192 +1662121647304569088 +1662121647352570112 +1662121647400571136 +1662121647451572224 +1662121647496573184 +1662121647547574272 +1662121647589575168 +1662121647634576128 +1662121647676577024 +1662121647727578112 +1662121647784579328 +1662121647832580352 +1662121647874581248 +1662121647931582464 +1662121647973583360 +1662121648015584256 +1662121648069585408 +1662121648114586368 +1662121648156587264 +1662121648198588160 +1662121648240589056 +1662121648288590080 +1662121648336591104 +1662121648393592320 +1662121648435593216 +1662121648477594112 +1662121648519595008 +1662121648573596160 +1662121648627597312 +1662121648678598400 +1662121648723599360 +1662121648768600320 +1662121648813601280 +1662121648852602112 +1662121648894603008 +1662121648939603968 +1662121648981604864 +1662121649023605760 +1662121649080606976 +1662121649125607936 +1662121649167608832 +1662121649209609728 +1662121649251610624 +1662121649302611712 +1662121649341612544 +1662121649392613632 +1662121649437614592 +1662121649479615488 +1662121649521616384 +1662121649569617408 +1662121649614618368 +1662121649653619200 +1662121649692620032 +1662121649740621056 +1662121649785622016 +1662121649830622976 +1662121649875623936 +1662121649920624896 +1662121649971625984 +1662121650013626880 +1662121650058627840 +1662121650106628864 +1662121650148629760 +1662121650193630720 +1662121650241631744 +1662121650286632704 +1662121650331633664 +1662121650376634624 +1662121650424635648 +1662121650466636544 +1662121650517637632 +1662121650559638528 +1662121650601639424 +1662121650646640384 +1662121650688641280 +1662121650730642176 +1662121650772643072 +1662121650823644160 +1662121650868645120 +1662121650910646016 +1662121650952646912 +1662121651000647936 +1662121651042648832 +1662121651087649792 +1662121651129650688 +1662121651171651584 +1662121651213652480 +1662121651255653376 +1662121651300654336 +1662121651345655296 +1662121651384656128 +1662121651429657088 +1662121651477658112 +1662121651525659136 +1662121651573660160 +1662121651618661120 +1662121651669662208 +1662121651714663168 +1662121651765664256 +1662121651816665344 +1662121651864666368 +1662121651909667328 +1662121651951668224 +1662121652002669312 +1662121652050670336 +1662121652101671424 +1662121652143672320 +1662121652188673280 +1662121652236674304 +1662121652284675328 +1662121652335676416 +1662121652377677312 +1662121652425678336 +1662121652479679488 +1662121652521680384 +1662121652560681216 +1662121652608682240 +1662121652665683456 +1662121652707684352 +1662121652749685248 +1662121652791686144 +1662121652839687168 +1662121652881688064 +1662121652923688960 +1662121652971689984 +1662121653013690880 +1662121653055691776 +1662121653100692736 +1662121653142693632 +1662121653184694528 +1662121653229695488 +1662121653271696384 +1662121653319697408 +1662121653358698240 +1662121653403699200 +1662121653445700096 +1662121653487700992 +1662121653532701952 +1662121653577702912 +1662121653625703936 +1662121653670704896 +1662121653712705792 +1662121653754706688 +1662121653799707648 +1662121653841708544 +1662121653883709440 +1662121653934710528 +1662121653979711488 +1662121654024712448 +1662121654066713344 +1662121654108714240 +1662121654162715392 +1662121654210716416 +1662121654252717312 +1662121654300718336 +1662121654342719232 +1662121654387720192 +1662121654432721152 +1662121654471721984 +1662121654519723008 +1662121654564723968 +1662121654606724864 +1662121654657725952 +1662121654696726784 +1662121654738727680 +1662121654789728768 +1662121654831729664 +1662121654876730624 +1662121654918731520 +1662121654963732480 +1662121655002733312 +1662121655044734208 +1662121655086735104 +1662121655131736064 +1662121655176737024 +1662121655221737984 +1662121655278739200 +1662121655323740160 +1662121655365741056 +1662121655410742016 +1662121655455742976 +1662121655500743936 +1662121655539744768 +1662121655596745984 +1662121655638746880 +1662121655680747776 +1662121655722748672 +1662121655764749568 +1662121655806750464 +1662121655848751360 +1662121655893752320 +1662121655935753216 +1662121655977754112 +1662121656028755200 +1662121656073756160 +1662121656124757248 +1662121656172758272 +1662121656214759168 +1662121656262760192 +1662121656307761152 +1662121656355762176 +1662121656403763200 +1662121656445764096 +1662121656493765120 +1662121656544766208 +1662121656589767168 +1662121656631768064 +1662121656670768896 +1662121656715769856 +1662121656757770752 +1662121656805771776 +1662121656859772928 +1662121656901773824 +1662121656949774848 +1662121656991775744 +1662121657033776640 +1662121657075777536 +1662121657123778560 +1662121657168779520 +1662121657210780416 +1662121657258781440 +1662121657312782592 +1662121657360783616 +1662121657405784576 +1662121657453785600 +1662121657501786624 +1662121657546787584 +1662121657591788544 +1662121657636789504 +1662121657681790464 +1662121657723791360 +1662121657768792320 +1662121657813793280 +1662121657852794112 +1662121657897795072 +1662121657939795968 +1662121657984796928 +1662121658026797824 +1662121658068798720 +1662121658113799680 +1662121658158800640 +1662121658200801536 +1662121658254802688 +1662121658302803712 +1662121658350804736 +1662121658404805888 +1662121658446806784 +1662121658491807744 +1662121658536808704 +1662121658575809536 +1662121658626810624 +1662121658668811520 +1662121658716812544 +1662121658758813440 +1662121658809814528 +1662121658851815424 +1662121658905816576 +1662121658947817472 +1662121658989818368 +1662121659031819264 +1662121659076820224 +1662121659121821184 +1662121659166822144 +1662121659208823040 +1662121659253824000 +1662121659307825152 +1662121659361826304 +1662121659406827264 +1662121659454828288 +1662121659502829312 +1662121659547830272 +1662121659589831168 +1662121659640832256 +1662121659685833216 +1662121659739834368 +1662121659787835392 +1662121659835836416 +1662121659880837376 +1662121659925838336 +1662121659970839296 +1662121660012840192 +1662121660063841280 +1662121660108842240 +1662121660150843136 +1662121660195844096 +1662121660240845056 +1662121660288846080 +1662121660339847168 +1662121660387848192 +1662121660429849088 +1662121660474850048 +1662121660528851200 +1662121660570852096 +1662121660615853056 +1662121660657853952 +1662121660702854912 +1662121660747855872 +1662121660798856960 +1662121660840857856 +1662121660882858752 +1662121660924859648 +1662121660972860672 +1662121661020861696 +1662121661062862592 +1662121661104863488 +1662121661152864512 +1662121661197865472 +1662121661239866368 +1662121661284867328 +1662121661329868288 +1662121661374869248 +1662121661422870272 +1662121661470871296 +1662121661512872192 +1662121661557873152 +1662121661605874176 +1662121661650875136 +1662121661698876160 +1662121661740877056 +1662121661782877952 +1662121661833879040 +1662121661887880192 +1662121661929881088 +1662121661974882048 +1662121662013882880 +1662121662055883776 +1662121662103884800 +1662121662148885760 +1662121662190886656 +1662121662232887552 +1662121662283888640 +1662121662328889600 +1662121662370890496 +1662121662418891520 +1662121662463892480 +1662121662511893504 +1662121662556894464 +1662121662604895488 +1662121662649896448 +1662121662688897280 +1662121662736898304 +1662121662778899200 +1662121662823900160 +1662121662868901120 +1662121662913902080 +1662121662958903040 +1662121663006904064 +1662121663051905024 +1662121663102906112 +1662121663147907072 +1662121663195908096 +1662121663243909120 +1662121663282909952 +1662121663324910848 +1662121663366911744 +1662121663414912768 +1662121663459913728 +1662121663504914688 +1662121663549915648 +1662121663597916672 +1662121663639917568 +1662121663681918464 +1662121663723919360 +1662121663765920256 +1662121663810921216 +1662121663855922176 +1662121663903923200 +1662121663948924160 +1662121663993925120 +1662121664035926016 +1662121664089927168 +1662121664134928128 +1662121664182929152 +1662121664224930048 +1662121664272931072 +1662121664320932096 +1662121664365933056 +1662121664413934080 +1662121664461935104 +1662121664512936192 +1662121664554937088 +1662121664596937984 +1662121664647939072 +1662121664701940224 +1662121664752941312 +1662121664809942528 +1662121664854943488 +1662121664899944448 +1662121664941945344 +1662121664983946240 +1662121665037947392 +1662121665079948288 +1662121665121949184 +1662121665163950080 +1662121665214951168 +1662121665262952192 +1662121665307953152 +1662121665355954176 +1662121665400955136 +1662121665445956096 +1662121665502957312 +1662121665547958272 +1662121665592959232 +1662121665640960256 +1662121665685961216 +1662121665730962176 +1662121665772963072 +1662121665817964032 +1662121665856964864 +1662121665904965888 +1662121665946966784 +1662121665988967680 +1662121666030968576 +1662121666078969600 +1662121666120970496 +1662121666162971392 +1662121666210972416 +1662121666255973376 +1662121666297974272 +1662121666345975296 +1662121666390976256 +1662121666432977152 +1662121666474978048 +1662121666519979008 +1662121666567980032 +1662121666612980992 +1662121666666982144 +1662121666705982976 +1662121666756984064 +1662121666801985024 +1662121666858986240 +1662121666900987136 +1662121666942988032 +1662121666987988992 +1662121667041990144 +1662121667089991168 +1662121667137992192 +1662121667185993216 +1662121667230994176 +1662121667275995136 +1662121667320996096 +1662121667362996992 +1662121667410998016 +1662121667455998976 +1662121667500999936 +1662121667546000896 +1662121667594001920 +1662121667642002944 +1662121667687003904 +1662121667729004800 +1662121667771005696 +1662121667816006656 +1662121667861007616 +1662121667903008512 +1662121667957009664 +1662121667999010560 +1662121668041011456 +1662121668089012480 +1662121668134013440 +1662121668179014400 +1662121668224015360 +1662121668278016512 +1662121668323017472 +1662121668374018560 +1662121668413019392 +1662121668458020352 +1662121668500021248 +1662121668539022080 +1662121668581022976 +1662121668626023936 +1662121668668024832 +1662121668710025728 +1662121668752026624 +1662121668797027584 +1662121668842028544 +1662121668884029440 +1662121668926030336 +1662121668974031360 +1662121669019032320 +1662121669061033216 +1662121669103034112 +1662121669154035200 +1662121669199036160 +1662121669241037056 +1662121669283037952 +1662121669325038848 +1662121669367039744 +1662121669409040640 +1662121669454041600 +1662121669511042816 +1662121669556043776 +1662121669595044608 +1662121669634045440 +1662121669673046272 +1662121669715047168 +1662121669760048128 +1662121669802049024 +1662121669856050176 +1662121669901051136 +1662121669943052032 +1662121669988052992 +1662121670036054016 +1662121670081054976 +1662121670123055872 +1662121670165056768 +1662121670219057920 +1662121670267058944 +1662121670315059968 +1662121670360060928 +1662121670411062016 +1662121670456062976 +1662121670507064064 +1662121670561065216 +1662121670606066176 +1662121670654067200 +1662121670699068160 +1662121670753069312 +1662121670789070080 +1662121670831070976 +1662121670873071872 +1662121670921072896 +1662121670963073792 +1662121671005074688 +1662121671047075584 +1662121671089076480 +1662121671137077504 +1662121671179078400 +1662121671221079296 +1662121671263080192 +1662121671317081344 +1662121671359082240 +1662121671401083136 +1662121671443084032 +1662121671485084928 +1662121671536086016 +1662121671578086912 +1662121671620087808 +1662121671671088896 +1662121671713089792 +1662121671758090752 +1662121671800091648 +1662121671842092544 +1662121671893093632 +1662121671935094528 +1662121671977095424 +1662121672025096448 +1662121672073097472 +1662121672115098368 +1662121672157099264 +1662121672208100352 +1662121672259101440 +1662121672304102400 +1662121672349103360 +1662121672394104320 +1662121672436105216 +1662121672484106240 +1662121672526107136 +1662121672574108160 +1662121672616109056 +1662121672664110080 +1662121672709111040 +1662121672754112000 +1662121672799112960 +1662121672841113856 +1662121672886114816 +1662121672934115840 +1662121672985116928 +1662121673027117824 +1662121673066118656 +1662121673111119616 +1662121673159120640 +1662121673204121600 +1662121673243122432 +1662121673288123392 +1662121673339124480 +1662121673387125504 +1662121673435126528 +1662121673489127680 +1662121673537128704 +1662121673582129664 +1662121673639130880 +1662121673681131776 +1662121673726132736 +1662121673768133632 +1662121673819134720 +1662121673861135616 +1662121673906136576 +1662121673963137792 +1662121674002138624 +1662121674050139648 +1662121674092140544 +1662121674137141504 +1662121674182142464 +1662121674230143488 +1662121674275144448 +1662121674323145472 +1662121674365146368 +1662121674413147392 +1662121674458148352 +1662121674500149248 +1662121674542150144 +1662121674587151104 +1662121674629152000 +1662121674674152960 +1662121674719153920 +1662121674767154944 +1662121674818156032 +1662121674863156992 +1662121674917158144 +1662121674959159040 +1662121675007160064 +1662121675046160896 +1662121675094161920 +1662121675136162816 +1662121675178163712 +1662121675226164736 +1662121675268165632 +1662121675313166592 +1662121675355167488 +1662121675400168448 +1662121675445169408 +1662121675493170432 +1662121675535171328 +1662121675580172288 +1662121675625173248 +1662121675667174144 +1662121675709175040 +1662121675751175936 +1662121675799176960 +1662121675847177984 +1662121675892178944 +1662121675937179904 +1662121675979180800 +1662121676021181696 +1662121676066182656 +1662121676108183552 +1662121676153184512 +1662121676207185664 +1662121676249186560 +1662121676294187520 +1662121676339188480 +1662121676387189504 +1662121676432190464 +1662121676474191360 +1662121676519192320 +1662121676567193344 +1662121676621194496 +1662121676666195456 +1662121676708196352 +1662121676756197376 +1662121676798198272 +1662121676852199424 +1662121676903200512 +1662121676948201472 +1662121676993202432 +1662121677035203328 +1662121677083204352 +1662121677134205440 +1662121677188206592 +1662121677236207616 +1662121677278208512 +1662121677317209344 +1662121677365210368 +1662121677407211264 +1662121677449212160 +1662121677491213056 +1662121677533213952 +1662121677575214848 +1662121677617215744 +1662121677659216640 +1662121677701217536 +1662121677743218432 +1662121677785219328 +1662121677827220224 +1662121677869221120 +1662121677914222080 +1662121677956222976 +1662121678004224000 +1662121678055225088 +1662121678094225920 +1662121678136226816 +1662121678187227904 +1662121678229228800 +1662121678274229760 +1662121678319230720 +1662121678367231744 +1662121678412232704 +1662121678469233920 +1662121678520235008 +1662121678565235968 +1662121678607236864 +1662121678649237760 +1662121678691238656 +1662121678733239552 +1662121678775240448 +1662121678817241344 +1662121678862242304 +1662121678907243264 +1662121678952244224 +1662121679009245440 +1662121679051246336 +1662121679093247232 +1662121679138248192 +1662121679186249216 +1662121679228250112 +1662121679273251072 +1662121679321252096 +1662121679372253184 +1662121679420254208 +1662121679462255104 +1662121679504256000 +1662121679549256960 +1662121679594257920 +1662121679639258880 +1662121679684259840 +1662121679729260800 +1662121679768261632 +1662121679810262528 +1662121679861263616 +1662121679903264512 +1662121679948265472 +1662121679996266496 +1662121680035267328 +1662121680080268288 +1662121680125269248 +1662121680167270144 +1662121680218271232 +1662121680263272192 +1662121680305273088 +1662121680347273984 +1662121680392274944 +1662121680437275904 +1662121680479276800 +1662121680530277888 +1662121680578278912 +1662121680629280000 +1662121680671280896 +1662121680713281792 +1662121680761282816 +1662121680803283712 +1662121680851284736 +1662121680896285696 +1662121680935286528 +1662121680974287360 +1662121681016288256 +1662121681064289280 +1662121681109290240 +1662121681157291264 +1662121681208292352 +1662121681250293248 +1662121681295294208 +1662121681340295168 +1662121681391296256 +1662121681436297216 +1662121681484298240 +1662121681535299328 +1662121681577300224 +1662121681622301184 +1662121681673302272 +1662121681724303360 +1662121681772304384 +1662121681817305344 +1662121681862306304 +1662121681910307328 +1662121681958308352 +1662121682000309248 +1662121682048310272 +1662121682090311168 +1662121682132312064 +1662121682180313088 +1662121682225314048 +1662121682270315008 +1662121682321316096 +1662121682369317120 +1662121682417318144 +1662121682459319040 +1662121682504320000 +1662121682546320896 +1662121682597321984 +1662121682639322880 +1662121682684323840 +1662121682735324928 +1662121682789326080 +1662121682831326976 +1662121682873327872 +1662121682921328896 +1662121682966329856 +1662121683014330880 +1662121683062331904 +1662121683107332864 +1662121683161334016 +1662121683203334912 +1662121683248335872 +1662121683296336896 +1662121683341337856 +1662121683386338816 +1662121683434339840 +1662121683482340864 +1662121683527341824 +1662121683575342848 +1662121683623343872 +1662121683668344832 +1662121683713345792 +1662121683761346816 +1662121683806347776 +1662121683848348672 +1662121683899349760 +1662121683941350656 +1662121683983351552 +1662121684025352448 +1662121684067353344 +1662121684109354240 +1662121684157355264 +1662121684202356224 +1662121684250357248 +1662121684298358272 +1662121684346359296 +1662121684391360256 +1662121684433361152 +1662121684475362048 +1662121684517362944 +1662121684562363904 +1662121684616365056 +1662121684661366016 +1662121684703366912 +1662121684754368000 +1662121684799368960 +1662121684850370048 +1662121684898371072 +1662121684940371968 +1662121684997373184 +1662121685036374016 +1662121685081374976 +1662121685123375872 +1662121685171376896 +1662121685228378112 +1662121685282379264 +1662121685330380288 +1662121685375381248 +1662121685420382208 +1662121685468383232 +1662121685510384128 +1662121685561385216 +1662121685609386240 +1662121685651387136 +1662121685693388032 +1662121685738388992 +1662121685783389952 +1662121685834391040 +1662121685897392384 +1662121685948393472 +1662121685993394432 +1662121686044395520 +1662121686086396416 +1662121686131397376 +1662121686176398336 +1662121686215399168 +1662121686260400128 +1662121686305401088 +1662121686353402112 +1662121686404403200 +1662121686449404160 +1662121686491405056 +1662121686533405952 +1662121686575406848 +1662121686626407936 +1662121686668408832 +1662121686716409856 +1662121686767410944 +1662121686812411904 +1662121686854412800 +1662121686899413760 +1662121686941414656 +1662121686992415744 +1662121687040416768 +1662121687085417728 +1662121687133418752 +1662121687175419648 +1662121687217420544 +1662121687265421568 +1662121687307422464 +1662121687352423424 +1662121687397424384 +1662121687445425408 +1662121687490426368 +1662121687532427264 +1662121687574428160 +1662121687619429120 +1662121687664430080 +1662121687709431040 +1662121687751431936 +1662121687793432832 +1662121687832433664 +1662121687880434688 +1662121687928435712 +1662121687970436608 +1662121688018437632 +1662121688069438720 +1662121688126439936 +1662121688171440896 +1662121688216441856 +1662121688258442752 +1662121688303443712 +1662121688345444608 +1662121688387445504 +1662121688429446400 +1662121688474447360 +1662121688522448384 +1662121688570449408 +1662121688609450240 +1662121688651451136 +1662121688705452288 +1662121688747453184 +1662121688795454208 +1662121688840455168 +1662121688885456128 +1662121688924456960 +1662121688975458048 +1662121689017458944 +1662121689059459840 +1662121689101460736 +1662121689149461760 +1662121689194462720 +1662121689239463680 +1662121689287464704 +1662121689329465600 +1662121689380466688 +1662121689422467584 +1662121689467468544 +1662121689509469440 +1662121689554470400 +1662121689602471424 +1662121689644472320 +1662121689686473216 +1662121689734474240 +1662121689773475072 +1662121689812475904 +1662121689857476864 +1662121689908477952 +1662121689950478848 +1662121689995479808 +1662121690046480896 +1662121690094481920 +1662121690139482880 +1662121690178483712 +1662121690220484608 +1662121690268485632 +1662121690313486592 +1662121690361487616 +1662121690403488512 +1662121690454489600 +1662121690496490496 +1662121690538491392 +1662121690583492352 +1662121690625493248 +1662121690673494272 +1662121690721495296 +1662121690766496256 +1662121690805497088 +1662121690850498048 +1662121690892498944 +1662121690934499840 +1662121690976500736 +1662121691027501824 +1662121691072502784 +1662121691114503680 +1662121691156504576 +1662121691201505536 +1662121691246506496 +1662121691297507584 +1662121691342508544 +1662121691384509440 +1662121691429510400 +1662121691471511296 +1662121691522512384 +1662121691564513280 +1662121691612514304 +1662121691660515328 +1662121691705516288 +1662121691747517184 +1662121691792518144 +1662121691834519040 +1662121691885520128 +1662121691927521024 +1662121691969521920 +1662121692023523072 +1662121692068524032 +1662121692125525248 +1662121692182526464 +1662121692224527360 +1662121692266528256 +1662121692311529216 +1662121692359530240 +1662121692407531264 +1662121692449532160 +1662121692491533056 +1662121692545534208 +1662121692593535232 +1662121692644536320 +1662121692686537216 +1662121692731538176 +1662121692779539200 +1662121692818540032 +1662121692866541056 +1662121692911542016 +1662121692956542976 +1662121692998543872 +1662121693046544896 +1662121693097545984 +1662121693139546880 +1662121693184547840 +1662121693229548800 +1662121693277549824 +1662121693322550784 +1662121693364551680 +1662121693409552640 +1662121693457553664 +1662121693502554624 +1662121693547555584 +1662121693589556480 +1662121693634557440 +1662121693673558272 +1662121693718559232 +1662121693763560192 +1662121693805561088 +1662121693847561984 +1662121693895563008 +1662121693937563904 +1662121693982564864 +1662121694033565952 +1662121694081566976 +1662121694132568064 +1662121694177569024 +1662121694219569920 +1662121694267570944 +1662121694312571904 +1662121694360572928 +1662121694408573952 +1662121694462575104 +1662121694507576064 +1662121694549576960 +1662121694594577920 +1662121694636578816 +1662121694678579712 +1662121694729580800 +1662121694771581696 +1662121694822582784 +1662121694864583680 +1662121694909584640 +1662121694951585536 +1662121695002586624 +1662121695047587584 +1662121695089588480 +1662121695137589504 +1662121695185590528 +1662121695227591424 +1662121695269592320 +1662121695311593216 +1662121695353594112 +1662121695398595072 +1662121695449596160 +1662121695491597056 +1662121695548598272 +1662121695593599232 +1662121695638600192 +1662121695683601152 +1662121695725602048 +1662121695767602944 +1662121695809603840 +1662121695854604800 +1662121695896605696 +1662121695947606784 +1662121695998607872 +1662121696046608896 +1662121696091609856 +1662121696151611136 +1662121696202612224 +1662121696250613248 +1662121696298614272 +1662121696340615168 +1662121696385616128 +1662121696433617152 +1662121696478618112 +1662121696526619136 +1662121696571620096 +1662121696616621056 +1662121696661622016 +1662121696709623040 +1662121696757624064 +1662121696802625024 +1662121696847625984 +1662121696889626880 +1662121696943628032 +1662121696985628928 +1662121697036630016 +1662121697084631040 +1662121697123631872 +1662121697171632896 +1662121697219633920 +1662121697267634944 +1662121697312635904 +1662121697354636800 +1662121697399637760 +1662121697441638656 +1662121697489639680 +1662121697534640640 +1662121697582641664 +1662121697633642752 +1662121697678643712 +1662121697732644864 +1662121697780645888 +1662121697831646976 +1662121697873647872 +1662121697915648768 +1662121697960649728 +1662121698005650688 +1662121698047651584 +1662121698098652672 +1662121698143653632 +1662121698191654656 +1662121698242655744 +1662121698287656704 +1662121698329657600 +1662121698371658496 +1662121698413659392 +1662121698458660352 +1662121698506661376 +1662121698554662400 +1662121698602663424 +1662121698647664384 +1662121698689665280 +1662121698737666304 +1662121698782667264 +1662121698827668224 +1662121698866669056 +1662121698914670080 +1662121698959671040 +1662121699004672000 +1662121699049672960 +1662121699094673920 +1662121699136674816 +1662121699181675776 +1662121699226676736 +1662121699268677632 +1662121699310678528 +1662121699358679552 +1662121699400680448 +1662121699445681408 +1662121699487682304 +1662121699532683264 +1662121699577684224 +1662121699622685184 +1662121699667686144 +1662121699709687040 +1662121699763688192 +1662121699814689280 +1662121699856690176 +1662121699898691072 +1662121699946692096 +1662121700003693312 +1662121700048694272 +1662121700096695296 +1662121700138696192 +1662121700177697024 +1662121700219697920 +1662121700267698944 +1662121700312699904 +1662121700357700864 +1662121700408701952 +1662121700453702912 +1662121700495703808 +1662121700546704896 +1662121700597705984 +1662121700642706944 +1662121700684707840 +1662121700729708800 +1662121700774709760 +1662121700816710656 +1662121700864711680 +1662121700906712576 +1662121700960713728 +1662121701011714816 +1662121701053715712 +1662121701095716608 +1662121701140717568 +1662121701191718656 +1662121701233719552 +1662121701278720512 +1662121701326721536 +1662121701371722496 +1662121701413723392 +1662121701461724416 +1662121701503725312 +1662121701545726208 +1662121701584727040 +1662121701629728000 +1662121701677729024 +1662121701722729984 +1662121701770731008 +1662121701812731904 +1662121701857732864 +1662121701902733824 diff --git a/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt new file mode 100644 index 0000000000..23ef73aa69 --- /dev/null +++ b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt @@ -0,0 +1,2934 @@ +1662064490014331136 +1662064490059332096 +1662064490101332992 +1662064490140333824 +1662064490188334848 +1662064490233335808 +1662064490275336704 +1662064490323337728 +1662064490371338752 +1662064490419339776 +1662064490461340672 +1662064490506341632 +1662064490548342528 +1662064490590343424 +1662064490632344320 +1662064490671345152 +1662064490710345984 +1662064490749346816 +1662064490794347776 +1662064490836348672 +1662064490878349568 +1662064490920350464 +1662064490962351360 +1662064491007352320 +1662064491049353216 +1662064491088354048 +1662064491130354944 +1662064491175355904 +1662064491223356928 +1662064491265357824 +1662064491307358720 +1662064491352359680 +1662064491397360640 +1662064491439361536 +1662064491481362432 +1662064491523363328 +1662064491562364160 +1662064491601364992 +1662064491643365888 +1662064491685366784 +1662064491727367680 +1662064491778368768 +1662064491820369664 +1662064491862370560 +1662064491904371456 +1662064491946372352 +1662064491985373184 +1662064492030374144 +1662064492072375040 +1662064492117376000 +1662064492159376896 +1662064492201377792 +1662064492246378752 +1662064492288379648 +1662064492330380544 +1662064492372381440 +1662064492411382272 +1662064492456383232 +1662064492501384192 +1662064492543385088 +1662064492588386048 +1662064492630386944 +1662064492669387776 +1662064492714388736 +1662064492756389632 +1662064492801390592 +1662064492846391552 +1662064492885392384 +1662064492927393280 +1662064492975394304 +1662064493017395200 +1662064493065396224 +1662064493107397120 +1662064493149398016 +1662064493188398848 +1662064493236399872 +1662064493284400896 +1662064493329401856 +1662064493374402816 +1662064493419403776 +1662064493464404736 +1662064493506405632 +1662064493554406656 +1662064493596407552 +1662064493638408448 +1662064493680409344 +1662064493722410240 +1662064493767411200 +1662064493815412224 +1662064493857413120 +1662064493899414016 +1662064493938414848 +1662064493983415808 +1662064494028416768 +1662064494073417728 +1662064494115418624 +1662064494160419584 +1662064494205420544 +1662064494244421376 +1662064494289422336 +1662064494331423232 +1662064494379424256 +1662064494418425088 +1662064494463426048 +1662064494505426944 +1662064494547427840 +1662064494589428736 +1662064494631429632 +1662064494670430464 +1662064494721431552 +1662064494766432512 +1662064494811433472 +1662064494853434368 +1662064494895435264 +1662064494937436160 +1662064494976436992 +1662064495018437888 +1662064495063438848 +1662064495108439808 +1662064495147440640 +1662064495189441536 +1662064495231442432 +1662064495273443328 +1662064495321444352 +1662064495366445312 +1662064495408446208 +1662064495450447104 +1662064495486447872 +1662064495528448768 +1662064495570449664 +1662064495615450624 +1662064495654451456 +1662064495699452416 +1662064495738453248 +1662064495783454208 +1662064495819454976 +1662064495861455872 +1662064495903456768 +1662064495945457664 +1662064495987458560 +1662064496026459392 +1662064496071460352 +1662064496116461312 +1662064496161462272 +1662064496200463104 +1662064496242464000 +1662064496284464896 +1662064496326465792 +1662064496365466624 +1662064496407467520 +1662064496452468480 +1662064496494469376 +1662064496536470272 +1662064496578471168 +1662064496623472128 +1662064496668473088 +1662064496707473920 +1662064496752474880 +1662064496794475776 +1662064496833476608 +1662064496875477504 +1662064496917478400 +1662064496959479296 +1662064497004480256 +1662064497046481152 +1662064497091482112 +1662064497133483008 +1662064497175483904 +1662064497217484800 +1662064497256485632 +1662064497295486464 +1662064497334487296 +1662064497379488256 +1662064497424489216 +1662064497463490048 +1662064497505490944 +1662064497550491904 +1662064497589492736 +1662064497631493632 +1662064497676494592 +1662064497727495680 +1662064497769496576 +1662064497811497472 +1662064497853498368 +1662064497892499200 +1662064497934500096 +1662064497973500928 +1662064498012501760 +1662064498057502720 +1662064498102503680 +1662064498147504640 +1662064498189505536 +1662064498234506496 +1662064498276507392 +1662064498318508288 +1662064498363509248 +1662064498408510208 +1662064498450511104 +1662064498492512000 +1662064498534512896 +1662064498579513856 +1662064498615514624 +1662064498654515456 +1662064498696516352 +1662064498741517312 +1662064498777518080 +1662064498813518848 +1662064498855519744 +1662064498903520768 +1662064498948521728 +1662064498993522688 +1662064499035523584 +1662064499080524544 +1662064499122525440 +1662064499161526272 +1662064499206527232 +1662064499242528000 +1662064499284528896 +1662064499323529728 +1662064499365530624 +1662064499404531456 +1662064499446532352 +1662064499494533376 +1662064499542534400 +1662064499590535424 +1662064499629536256 +1662064499671537152 +1662064499716538112 +1662064499761539072 +1662064499800539904 +1662064499839540736 +1662064499884541696 +1662064499923542528 +1662064499968543488 +1662064500016544512 +1662064500064545536 +1662064500109546496 +1662064500148547328 +1662064500190548224 +1662064500235549184 +1662064500277550080 +1662064500322551040 +1662064500367552000 +1662064500409552896 +1662064500451553792 +1662064500496554752 +1662064500541555712 +1662064500583556608 +1662064500625557504 +1662064500670558464 +1662064500712559360 +1662064500757560320 +1662064500799561216 +1662064500841562112 +1662064500883563008 +1662064500925563904 +1662064500970564864 +1662064501015565824 +1662064501060566784 +1662064501102567680 +1662064501144568576 +1662064501192569600 +1662064501234570496 +1662064501276571392 +1662064501315572224 +1662064501354573056 +1662064501405574144 +1662064501447575040 +1662064501489575936 +1662064501534576896 +1662064501579577856 +1662064501621578752 +1662064501666579712 +1662064501714580736 +1662064501756581632 +1662064501798582528 +1662064501843583488 +1662064501885584384 +1662064501924585216 +1662064501969586176 +1662064502011587072 +1662064502053587968 +1662064502098588928 +1662064502143589888 +1662064502191590912 +1662064502236591872 +1662064502281592832 +1662064502320593664 +1662064502362594560 +1662064502398595328 +1662064502440596224 +1662064502485597184 +1662064502524598016 +1662064502566598912 +1662064502608599808 +1662064502653600768 +1662064502695601664 +1662064502737602560 +1662064502782603520 +1662064502827604480 +1662064502872605440 +1662064502917606400 +1662064502962607360 +1662064503007608320 +1662064503052609280 +1662064503100610304 +1662064503139611136 +1662064503178611968 +1662064503223612928 +1662064503268613888 +1662064503313614848 +1662064503355615744 +1662064503397616640 +1662064503442617600 +1662064503484618496 +1662064503526619392 +1662064503568620288 +1662064503610621184 +1662064503658622208 +1662064503703623168 +1662064503745624064 +1662064503790625024 +1662064503832625920 +1662064503874626816 +1662064503916627712 +1662064503958628608 +1662064504000629504 +1662064504042630400 +1662064504084631296 +1662064504126632192 +1662064504162632960 +1662064504204633856 +1662064504249634816 +1662064504294635776 +1662064504339636736 +1662064504381637632 +1662064504429638656 +1662064504468639488 +1662064504510640384 +1662064504558641408 +1662064504597642240 +1662064504645643264 +1662064504687644160 +1662064504729645056 +1662064504771645952 +1662064504813646848 +1662064504852647680 +1662064504897648640 +1662064504936649472 +1662064504975650304 +1662064505017651200 +1662064505059652096 +1662064505101652992 +1662064505143653888 +1662064505191654912 +1662064505236655872 +1662064505278656768 +1662064505320657664 +1662064505362658560 +1662064505407659520 +1662064505449660416 +1662064505497661440 +1662064505539662336 +1662064505578663168 +1662064505623664128 +1662064505668665088 +1662064505716666112 +1662064505758667008 +1662064505809668096 +1662064505848668928 +1662064505890669824 +1662064505938670848 +1662064505980671744 +1662064506022672640 +1662064506064673536 +1662064506106674432 +1662064506151675392 +1662064506196676352 +1662064506244677376 +1662064506289678336 +1662064506334679296 +1662064506376680192 +1662064506418681088 +1662064506454681856 +1662064506499682816 +1662064506544683776 +1662064506586684672 +1662064506631685632 +1662064506673686528 +1662064506715687424 +1662064506757688320 +1662064506796689152 +1662064506838690048 +1662064506880690944 +1662064506922691840 +1662064506970692864 +1662064507012693760 +1662064507057694720 +1662064507099695616 +1662064507141696512 +1662064507180697344 +1662064507219698176 +1662064507270699264 +1662064507315700224 +1662064507357701120 +1662064507405702144 +1662064507447703040 +1662064507486703872 +1662064507528704768 +1662064507570705664 +1662064507612706560 +1662064507654707456 +1662064507702708480 +1662064507747709440 +1662064507789710336 +1662064507834711296 +1662064507879712256 +1662064507930713344 +1662064507975714304 +1662064508014715136 +1662064508062716160 +1662064508107717120 +1662064508152718080 +1662064508194718976 +1662064508236719872 +1662064508281720832 +1662064508329721856 +1662064508362722560 +1662064508407723520 +1662064508455724544 +1662064508497725440 +1662064508539726336 +1662064508584727296 +1662064508623728128 +1662064508665729024 +1662064508710729984 +1662064508761731072 +1662064508806732032 +1662064508854733056 +1662064508899734016 +1662064508941734912 +1662064508983735808 +1662064509025736704 +1662064509070737664 +1662064509115738624 +1662064509151739392 +1662064509193740288 +1662064509235741184 +1662064509280742144 +1662064509325743104 +1662064509364743936 +1662064509406744832 +1662064509448745728 +1662064509490746624 +1662064509532747520 +1662064509574748416 +1662064509616749312 +1662064509661750272 +1662064509706751232 +1662064509751752192 +1662064509793753088 +1662064509835753984 +1662064509877754880 +1662064509922755840 +1662064509967756800 +1662064510009757696 +1662064510051758592 +1662064510099759616 +1662064510141760512 +1662064510183761408 +1662064510228762368 +1662064510273763328 +1662064510321764352 +1662064510363765248 +1662064510405766144 +1662064510453767168 +1662064510495768064 +1662064510540769024 +1662064510582769920 +1662064510621770752 +1662064510660771584 +1662064510702772480 +1662064510747773440 +1662064510789774336 +1662064510831775232 +1662064510870776064 +1662064510915777024 +1662064510957777920 +1662064510999778816 +1662064511041779712 +1662064511083780608 +1662064511122781440 +1662064511164782336 +1662064511206783232 +1662064511254784256 +1662064511296785152 +1662064511338786048 +1662064511383787008 +1662064511425787904 +1662064511473788928 +1662064511515789824 +1662064511557790720 +1662064511602791680 +1662064511644792576 +1662064511686793472 +1662064511725794304 +1662064511770795264 +1662064511809796096 +1662064511851796992 +1662064511896797952 +1662064511938798848 +1662064511980799744 +1662064512028800768 +1662064512070801664 +1662064512109802496 +1662064512151803392 +1662064512193804288 +1662064512235805184 +1662064512271805952 +1662064512322807040 +1662064512364807936 +1662064512406808832 +1662064512445809664 +1662064512484810496 +1662064512523811328 +1662064512568812288 +1662064512607813120 +1662064512646813952 +1662064512691814912 +1662064512733815808 +1662064512778816768 +1662064512820817664 +1662064512859818496 +1662064512904819456 +1662064512952820480 +1662064512997821440 +1662064513039822336 +1662064513081823232 +1662064513123824128 +1662064513165825024 +1662064513207825920 +1662064513252826880 +1662064513294827776 +1662064513339828736 +1662064513381829632 +1662064513423830528 +1662064513465831424 +1662064513507832320 +1662064513546833152 +1662064513588834048 +1662064513627834880 +1662064513672835840 +1662064513714836736 +1662064513756837632 +1662064513795838464 +1662064513834839296 +1662064513873840128 +1662064513915841024 +1662064513960841984 +1662064514008843008 +1662064514050843904 +1662064514095844864 +1662064514137845760 +1662064514179846656 +1662064514221847552 +1662064514266848512 +1662064514311849472 +1662064514350850304 +1662064514383851008 +1662064514425851904 +1662064514467852800 +1662064514512853760 +1662064514554854656 +1662064514596855552 +1662064514641856512 +1662064514683857408 +1662064514725858304 +1662064514767859200 +1662064514812860160 +1662064514854861056 +1662064514899862016 +1662064514944862976 +1662064514986863872 +1662064515028864768 +1662064515070865664 +1662064515112866560 +1662064515154867456 +1662064515205868544 +1662064515250869504 +1662064515295870464 +1662064515343871488 +1662064515388872448 +1662064515427873280 +1662064515472874240 +1662064515517875200 +1662064515556876032 +1662064515598876928 +1662064515637877760 +1662064515685878784 +1662064515727879680 +1662064515769880576 +1662064515817881600 +1662064515859882496 +1662064515898883328 +1662064515937884160 +1662064515985885184 +1662064516024886016 +1662064516063886848 +1662064516105887744 +1662064516144888576 +1662064516189889536 +1662064516228890368 +1662064516270891264 +1662064516315892224 +1662064516360893184 +1662064516402894080 +1662064516441894912 +1662064516483895808 +1662064516522896640 +1662064516558897408 +1662064516600898304 +1662064516639899136 +1662064516687900160 +1662064516729901056 +1662064516774902016 +1662064516819902976 +1662064516858903808 +1662064516900904704 +1662064516942905600 +1662064516984906496 +1662064517029907456 +1662064517071908352 +1662064517116909312 +1662064517158910208 +1662064517200911104 +1662064517254912256 +1662064517296913152 +1662064517338914048 +1662064517380914944 +1662064517419915776 +1662064517467916800 +1662064517512917760 +1662064517554918656 +1662064517605919744 +1662064517650920704 +1662064517692921600 +1662064517737922560 +1662064517779923456 +1662064517824924416 +1662064517863925248 +1662064517902926080 +1662064517947927040 +1662064517989927936 +1662064518028928768 +1662064518073929728 +1662064518118930688 +1662064518160931584 +1662064518199932416 +1662064518241933312 +1662064518280934144 +1662064518322935040 +1662064518361935872 +1662064518406936832 +1662064518448937728 +1662064518490938624 +1662064518532939520 +1662064518577940480 +1662064518622941440 +1662064518667942400 +1662064518709943296 +1662064518751944192 +1662064518793945088 +1662064518832945920 +1662064518874946816 +1662064518916947712 +1662064518964948736 +1662064519009949696 +1662064519048950528 +1662064519084951296 +1662064519126952192 +1662064519168953088 +1662064519210953984 +1662064519252954880 +1662064519288955648 +1662064519333956608 +1662064519378957568 +1662064519420958464 +1662064519462959360 +1662064519507960320 +1662064519546961152 +1662064519591962112 +1662064519639963136 +1662064519678963968 +1662064519717964800 +1662064519759965696 +1662064519804966656 +1662064519849967616 +1662064519888968448 +1662064519930969344 +1662064519975970304 +1662064520017971200 +1662064520062972160 +1662064520104973056 +1662064520149974016 +1662064520194974976 +1662064520239975936 +1662064520281976832 +1662064520323977728 +1662064520368978688 +1662064520416979712 +1662064520464980736 +1662064520506981632 +1662064520548982528 +1662064520593983488 +1662064520641984512 +1662064520683985408 +1662064520725986304 +1662064520767987200 +1662064520812988160 +1662064520854989056 +1662064520896989952 +1662064520938990848 +1662064520977991680 +1662064521022992640 +1662064521064993536 +1662064521106994432 +1662064521148995328 +1662064521187996160 +1662064521226996992 +1662064521268997888 +1662064521316998912 +1662064521361999872 +1662064521407000832 +1662064521449001728 +1662064521491002624 +1662064521536003584 +1662064521578004480 +1662064521620005376 +1662064521662006272 +1662064521707007232 +1662064521746008064 +1662064521788008960 +1662064521827009792 +1662064521869010688 +1662064521911011584 +1662064521950012416 +1662064521992013312 +1662064522034014208 +1662064522076015104 +1662064522118016000 +1662064522163016960 +1662064522205017856 +1662064522247018752 +1662064522286019584 +1662064522328020480 +1662064522370021376 +1662064522412022272 +1662064522457023232 +1662064522499024128 +1662064522538024960 +1662064522580025856 +1662064522625026816 +1662064522667027712 +1662064522709028608 +1662064522754029568 +1662064522793030400 +1662064522835031296 +1662064522877032192 +1662064522919033088 +1662064522961033984 +1662064523003034880 +1662064523045035776 +1662064523093036800 +1662064523138037760 +1662064523180038656 +1662064523225039616 +1662064523267040512 +1662064523312041472 +1662064523354042368 +1662064523396043264 +1662064523438044160 +1662064523480045056 +1662064523522045952 +1662064523561046784 +1662064523600047616 +1662064523645048576 +1662064523687049472 +1662064523735050496 +1662064523777051392 +1662064523819052288 +1662064523861053184 +1662064523903054080 +1662064523954055168 +1662064523996056064 +1662064524035056896 +1662064524083057920 +1662064524128058880 +1662064524170059776 +1662064524212060672 +1662064524254061568 +1662064524302062592 +1662064524344063488 +1662064524389064448 +1662064524431065344 +1662064524470066176 +1662064524512067072 +1662064524557068032 +1662064524596068864 +1662064524638069760 +1662064524677070592 +1662064524722071552 +1662064524761072384 +1662064524806073344 +1662064524851074304 +1662064524896075264 +1662064524932076032 +1662064524971076864 +1662064525013077760 +1662064525058078720 +1662064525106079744 +1662064525151080704 +1662064525196081664 +1662064525238082560 +1662064525280083456 +1662064525328084480 +1662064525367085312 +1662064525412086272 +1662064525454087168 +1662064525499088128 +1662064525544089088 +1662064525586089984 +1662064525628090880 +1662064525664091648 +1662064525712092672 +1662064525754093568 +1662064525802094592 +1662064525847095552 +1662064525889096448 +1662064525931097344 +1662064525982098432 +1662064526024099328 +1662064526066100224 +1662064526105101056 +1662064526147101952 +1662064526189102848 +1662064526231103744 +1662064526276104704 +1662064526324105728 +1662064526366106624 +1662064526405107456 +1662064526450108416 +1662064526492109312 +1662064526534110208 +1662064526579111168 +1662064526624112128 +1662064526666113024 +1662064526708113920 +1662064526753114880 +1662064526798115840 +1662064526840116736 +1662064526885117696 +1662064526927118592 +1662064526969119488 +1662064527020120576 +1662064527062121472 +1662064527104122368 +1662064527149123328 +1662064527185124096 +1662064527227124992 +1662064527269125888 +1662064527311126784 +1662064527353127680 +1662064527389128448 +1662064527431129344 +1662064527470130176 +1662064527512131072 +1662064527557132032 +1662064527602132992 +1662064527644133888 +1662064527692134912 +1662064527731135744 +1662064527776136704 +1662064527815137536 +1662064527863138560 +1662064527905139456 +1662064527950140416 +1662064527992141312 +1662064528037142272 +1662064528079143168 +1662064528124144128 +1662064528172145152 +1662064528214146048 +1662064528262147072 +1662064528304147968 +1662064528349148928 +1662064528391149824 +1662064528430150656 +1662064528472151552 +1662064528514152448 +1662064528556153344 +1662064528592154112 +1662064528628154880 +1662064528667155712 +1662064528712156672 +1662064528754157568 +1662064528796158464 +1662064528838159360 +1662064528883160320 +1662064528922161152 +1662064528964162048 +1662064529009163008 +1662064529048163840 +1662064529093164800 +1662064529138165760 +1662064529183166720 +1662064529225167616 +1662064529267168512 +1662064529309169408 +1662064529354170368 +1662064529396171264 +1662064529438172160 +1662064529480173056 +1662064529525174016 +1662064529564174848 +1662064529609175808 +1662064529654176768 +1662064529693177600 +1662064529738178560 +1662064529780179456 +1662064529822180352 +1662064529867181312 +1662064529915182336 +1662064529957183232 +1662064530002184192 +1662064530047185152 +1662064530092186112 +1662064530134187008 +1662064530182188032 +1662064530227188992 +1662064530269189888 +1662064530308190720 +1662064530350191616 +1662064530395192576 +1662064530437193472 +1662064530482194432 +1662064530521195264 +1662064530566196224 +1662064530611197184 +1662064530653198080 +1662064530695198976 +1662064530740199936 +1662064530788200960 +1662064530833201920 +1662064530872202752 +1662064530920203776 +1662064530962204672 +1662064531007205632 +1662064531049206528 +1662064531097207552 +1662064531142208512 +1662064531184209408 +1662064531223210240 +1662064531265211136 +1662064531310212096 +1662064531352212992 +1662064531394213888 +1662064531436214784 +1662064531478215680 +1662064531517216512 +1662064531556217344 +1662064531601218304 +1662064531646219264 +1662064531685220096 +1662064531727220992 +1662064531769221888 +1662064531808222720 +1662064531847223552 +1662064531892224512 +1662064531934225408 +1662064531982226432 +1662064532027227392 +1662064532069228288 +1662064532111229184 +1662064532159230208 +1662064532201231104 +1662064532246232064 +1662064532291233024 +1662064532330233856 +1662064532372234752 +1662064532417235712 +1662064532462236672 +1662064532504237568 +1662064532543238400 +1662064532585239296 +1662064532627240192 +1662064532672241152 +1662064532714242048 +1662064532756242944 +1662064532795243776 +1662064532837244672 +1662064532882245632 +1662064532927246592 +1662064532966247424 +1662064533008248320 +1662064533047249152 +1662064533089250048 +1662064533131250944 +1662064533173251840 +1662064533215252736 +1662064533257253632 +1662064533302254592 +1662064533344255488 +1662064533386256384 +1662064533428257280 +1662064533470258176 +1662064533512259072 +1662064533551259904 +1662064533593260800 +1662064533638261760 +1662064533680262656 +1662064533722263552 +1662064533767264512 +1662064533809265408 +1662064533851266304 +1662064533893267200 +1662064533935268096 +1662064533977268992 +1662064534022269952 +1662064534067270912 +1662064534109271808 +1662064534154272768 +1662064534193273600 +1662064534238274560 +1662064534280275456 +1662064534322276352 +1662064534367277312 +1662064534409278208 +1662064534451279104 +1662064534499280128 +1662064534544281088 +1662064534589282048 +1662064534634283008 +1662064534673283840 +1662064534712284672 +1662064534754285568 +1662064534799286528 +1662064534844287488 +1662064534892288512 +1662064534937289472 +1662064534979290368 +1662064535021291264 +1662064535060292096 +1662064535105293056 +1662064535156294144 +1662064535201295104 +1662064535249296128 +1662064535291297024 +1662064535336297984 +1662064535375298816 +1662064535417299712 +1662064535459300608 +1662064535501301504 +1662064535543302400 +1662064535585303296 +1662064535627304192 +1662064535669305088 +1662064535714306048 +1662064535753306880 +1662064535795307776 +1662064535837308672 +1662064535879309568 +1662064535921310464 +1662064535969311488 +1662064536014312448 +1662064536056313344 +1662064536104314368 +1662064536143315200 +1662064536185316096 +1662064536230317056 +1662064536275318016 +1662064536323319040 +1662064536365319936 +1662064536410320896 +1662064536452321792 +1662064536497322752 +1662064536545323776 +1662064536593324800 +1662064536635325696 +1662064536677326592 +1662064536719327488 +1662064536761328384 +1662064536806329344 +1662064536854330368 +1662064536905331456 +1662064536950332416 +1662064536992333312 +1662064537034334208 +1662064537079335168 +1662064537124336128 +1662064537163336960 +1662064537202337792 +1662064537244338688 +1662064537289339648 +1662064537331340544 +1662064537376341504 +1662064537421342464 +1662064537463343360 +1662064537505344256 +1662064537553345280 +1662064537595346176 +1662064537640347136 +1662064537688348160 +1662064537733349120 +1662064537775350016 +1662064537817350912 +1662064537856351744 +1662064537898352640 +1662064537940353536 +1662064537988354560 +1662064538033355520 +1662064538078356480 +1662064538123357440 +1662064538171358464 +1662064538213359360 +1662064538258360320 +1662064538297361152 +1662064538339362048 +1662064538384363008 +1662064538429363968 +1662064538471364864 +1662064538513365760 +1662064538555366656 +1662064538597367552 +1662064538639368448 +1662064538684369408 +1662064538726370304 +1662064538771371264 +1662064538810372096 +1662064538852372992 +1662064538891373824 +1662064538939374848 +1662064538984375808 +1662064539026376704 +1662064539071377664 +1662064539113378560 +1662064539158379520 +1662064539200380416 +1662064539242381312 +1662064539281382144 +1662064539326383104 +1662064539368384000 +1662064539410384896 +1662064539455385856 +1662064539497386752 +1662064539539387648 +1662064539581388544 +1662064539629389568 +1662064539671390464 +1662064539719391488 +1662064539764392448 +1662064539803393280 +1662064539845394176 +1662064539896395264 +1662064539938396160 +1662064539977396992 +1662064540022397952 +1662064540061398784 +1662064540103399680 +1662064540151400704 +1662064540187401472 +1662064540226402304 +1662064540271403264 +1662064540319404288 +1662064540361405184 +1662064540403406080 +1662064540445406976 +1662064540481407744 +1662064540523408640 +1662064540562409472 +1662064540607410432 +1662064540649411328 +1662064540694412288 +1662064540736413184 +1662064540781414144 +1662064540826415104 +1662064540868416000 +1662064540910416896 +1662064540949417728 +1662064540994418688 +1662064541039419648 +1662064541078420480 +1662064541117421312 +1662064541159422208 +1662064541198423040 +1662064541240423936 +1662064541282424832 +1662064541324425728 +1662064541366426624 +1662064541405427456 +1662064541444428288 +1662064541489429248 +1662064541534430208 +1662064541576431104 +1662064541621432064 +1662064541666433024 +1662064541705433856 +1662064541744434688 +1662064541789435648 +1662064541828436480 +1662064541870437376 +1662064541915438336 +1662064541957439232 +1662064541999440128 +1662064542044441088 +1662064542086441984 +1662064542131442944 +1662064542173443840 +1662064542215444736 +1662064542263445760 +1662064542308446720 +1662064542350447616 +1662064542395448576 +1662064542440449536 +1662064542482450432 +1662064542524451328 +1662064542569452288 +1662064542614453248 +1662064542659454208 +1662064542701455104 +1662064542743456000 +1662064542782456832 +1662064542827457792 +1662064542875458816 +1662064542920459776 +1662064542959460608 +1662064543004461568 +1662064543049462528 +1662064543091463424 +1662064543139464448 +1662064543184465408 +1662064543235466496 +1662064543280467456 +1662064543325468416 +1662064543367469312 +1662064543412470272 +1662064543454471168 +1662064543496472064 +1662064543541473024 +1662064543580473856 +1662064543625474816 +1662064543667475712 +1662064543706476544 +1662064543742477312 +1662064543784478208 +1662064543823479040 +1662064543877480192 +1662064543928481280 +1662064543973482240 +1662064544018483200 +1662064544057484032 +1662064544099484928 +1662064544144485888 +1662064544186486784 +1662064544228487680 +1662064544267488512 +1662064544309489408 +1662064544354490368 +1662064544396491264 +1662064544438492160 +1662064544477492992 +1662064544519493888 +1662064544564494848 +1662064544609495808 +1662064544651496704 +1662064544693497600 +1662064544735498496 +1662064544777499392 +1662064544819500288 +1662064544864501248 +1662064544909502208 +1662064544954503168 +1662064544993504000 +1662064545035504896 +1662064545080505856 +1662064545122506752 +1662064545164507648 +1662064545209508608 +1662064545257509632 +1662064545299510528 +1662064545344511488 +1662064545389512448 +1662064545431513344 +1662064545476514304 +1662064545518515200 +1662064545563516160 +1662064545617517312 +1662064545659518208 +1662064545707519232 +1662064545749520128 +1662064545794521088 +1662064545836521984 +1662064545881522944 +1662064545926523904 +1662064545971524864 +1662064546016525824 +1662064546061526784 +1662064546106527744 +1662064546148528640 +1662064546193529600 +1662064546232530432 +1662064546274531328 +1662064546316532224 +1662064546361533184 +1662064546406534144 +1662064546445534976 +1662064546484535808 +1662064546529536768 +1662064546574537728 +1662064546619538688 +1662064546658539520 +1662064546700540416 +1662064546739541248 +1662064546784542208 +1662064546826543104 +1662064546871544064 +1662064546913544960 +1662064546955545856 +1662064546997546752 +1662064547042547712 +1662064547087548672 +1662064547132549632 +1662064547177550592 +1662064547219551488 +1662064547264552448 +1662064547306553344 +1662064547348554240 +1662064547390555136 +1662064547432556032 +1662064547474556928 +1662064547522557952 +1662064547564558848 +1662064547606559744 +1662064547651560704 +1662064547699561728 +1662064547738562560 +1662064547780563456 +1662064547816564224 +1662064547855565056 +1662064547900566016 +1662064547942566912 +1662064547987567872 +1662064548029568768 +1662064548074569728 +1662064548116570624 +1662064548158571520 +1662064548197572352 +1662064548242573312 +1662064548284574208 +1662064548329575168 +1662064548368576000 +1662064548407576832 +1662064548452577792 +1662064548500578816 +1662064548545579776 +1662064548590580736 +1662064548629581568 +1662064548671582464 +1662064548713583360 +1662064548758584320 +1662064548803585280 +1662064548845586176 +1662064548884587008 +1662064548929587968 +1662064548974588928 +1662064549016589824 +1662064549061590784 +1662064549100591616 +1662064549148592640 +1662064549199593728 +1662064549241594624 +1662064549286595584 +1662064549328596480 +1662064549373597440 +1662064549418598400 +1662064549463599360 +1662064549505600256 +1662064549550601216 +1662064549592602112 +1662064549634603008 +1662064549676603904 +1662064549724604928 +1662064549766605824 +1662064549805606656 +1662064549847607552 +1662064549886608384 +1662064549931609344 +1662064549976610304 +1662064550021611264 +1662064550063612160 +1662064550108613120 +1662064550147613952 +1662064550189614848 +1662064550231615744 +1662064550276616704 +1662064550318617600 +1662064550357618432 +1662064550399619328 +1662064550444620288 +1662064550486621184 +1662064550528622080 +1662064550567622912 +1662064550609623808 +1662064550657624832 +1662064550702625792 +1662064550744626688 +1662064550786627584 +1662064550822628352 +1662064550861629184 +1662064550906630144 +1662064550951631104 +1662064550987631872 +1662064551029632768 +1662064551071633664 +1662064551116634624 +1662064551158635520 +1662064551200636416 +1662064551239637248 +1662064551281638144 +1662064551323639040 +1662064551365639936 +1662064551404640768 +1662064551449641728 +1662064551494642688 +1662064551539643648 +1662064551581644544 +1662064551623645440 +1662064551662646272 +1662064551707647232 +1662064551749648128 +1662064551794649088 +1662064551839650048 +1662064551881650944 +1662064551926651904 +1662064551971652864 +1662064552010653696 +1662064552049654528 +1662064552088655360 +1662064552133656320 +1662064552178657280 +1662064552220658176 +1662064552262659072 +1662064552310660096 +1662064552352660992 +1662064552394661888 +1662064552436662784 +1662064552478663680 +1662064552532664832 +1662064552577665792 +1662064552619666688 +1662064552661667584 +1662064552709668608 +1662064552757669632 +1662064552802670592 +1662064552844671488 +1662064552886672384 +1662064552928673280 +1662064552970674176 +1662064553018675200 +1662064553060676096 +1662064553093676800 +1662064553141677824 +1662064553180678656 +1662064553228679680 +1662064553273680640 +1662064553315681536 +1662064553354682368 +1662064553396683264 +1662064553438684160 +1662064553480685056 +1662064553525686016 +1662064553567686912 +1662064553612687872 +1662064553654688768 +1662064553699689728 +1662064553741690624 +1662064553780691456 +1662064553822692352 +1662064553864693248 +1662064553906694144 +1662064553948695040 +1662064553990695936 +1662064554035696896 +1662064554074697728 +1662064554116698624 +1662064554155699456 +1662064554200700416 +1662064554245701376 +1662064554287702272 +1662064554332703232 +1662064554371704064 +1662064554413704960 +1662064554452705792 +1662064554494706688 +1662064554536707584 +1662064554578708480 +1662064554620709376 +1662064554665710336 +1662064554707711232 +1662064554752712192 +1662064554797713152 +1662064554836713984 +1662064554878714880 +1662064554920715776 +1662064554962716672 +1662064555007717632 +1662064555049718528 +1662064555088719360 +1662064555130720256 +1662064555172721152 +1662064555214722048 +1662064555256722944 +1662064555301723904 +1662064555346724864 +1662064555391725824 +1662064555433726720 +1662064555475727616 +1662064555514728448 +1662064555571729664 +1662064555613730560 +1662064555655731456 +1662064555703732480 +1662064555748733440 +1662064555790734336 +1662064555832735232 +1662064555874736128 +1662064555919737088 +1662064555961737984 +1662064556006738944 +1662064556048739840 +1662064556093740800 +1662064556132741632 +1662064556174742528 +1662064556219743488 +1662064556264744448 +1662064556309745408 +1662064556357746432 +1662064556405747456 +1662064556450748416 +1662064556489749248 +1662064556534750208 +1662064556582751232 +1662064556627752192 +1662064556669753088 +1662064556711753984 +1662064556756754944 +1662064556798755840 +1662064556843756800 +1662064556885757696 +1662064556933758720 +1662064556969759488 +1662064557008760320 +1662064557047761152 +1662064557089762048 +1662064557131762944 +1662064557173763840 +1662064557212764672 +1662064557260765696 +1662064557305766656 +1662064557347767552 +1662064557383768320 +1662064557422769152 +1662064557467770112 +1662064557515771136 +1662064557557772032 +1662064557599772928 +1662064557638773760 +1662064557683774720 +1662064557728775680 +1662064557773776640 +1662064557818777600 +1662064557860778496 +1662064557902779392 +1662064557941780224 +1662064557983781120 +1662064558028782080 +1662064558067782912 +1662064558109783808 +1662064558148784640 +1662064558190785536 +1662064558232786432 +1662064558277787392 +1662064558322788352 +1662064558364789248 +1662064558409790208 +1662064558457791232 +1662064558499792128 +1662064558538792960 +1662064558583793920 +1662064558631794944 +1662064558673795840 +1662064558715796736 +1662064558757797632 +1662064558799798528 +1662064558847799552 +1662064558886800384 +1662064558928801280 +1662064558973802240 +1662064559018803200 +1662064559063804160 +1662064559108805120 +1662064559147805952 +1662064559189806848 +1662064559234807808 +1662064559276808704 +1662064559312809472 +1662064559354810368 +1662064559399811328 +1662064559441812224 +1662064559489813248 +1662064559534814208 +1662064559576815104 +1662064559618816000 +1662064559663816960 +1662064559705817856 +1662064559744818688 +1662064559786819584 +1662064559828820480 +1662064559867821312 +1662064559915822336 +1662064559957823232 +1662064559999824128 +1662064560044825088 +1662064560089826048 +1662064560134827008 +1662064560176827904 +1662064560218828800 +1662064560260829696 +1662064560299830528 +1662064560338831360 +1662064560377832192 +1662064560416833024 +1662064560458833920 +1662064560503834880 +1662064560545835776 +1662064560587836672 +1662064560632837632 +1662064560671838464 +1662064560716839424 +1662064560761840384 +1662064560803841280 +1662064560848842240 +1662064560893843200 +1662064560932844032 +1662064560968844800 +1662064561010845696 +1662064561055846656 +1662064561094847488 +1662064561136848384 +1662064561184849408 +1662064561220850176 +1662064561265851136 +1662064561310852096 +1662064561352852992 +1662064561397853952 +1662064561436854784 +1662064561478855680 +1662064561523856640 +1662064561568857600 +1662064561607858432 +1662064561652859392 +1662064561691860224 +1662064561733861120 +1662064561775862016 +1662064561817862912 +1662064561859863808 +1662064561901864704 +1662064561943865600 +1662064561988866560 +1662064562033867520 +1662064562075868416 +1662064562120869376 +1662064562162870272 +1662064562201871104 +1662064562243872000 +1662064562285872896 +1662064562327873792 +1662064562372874752 +1662064562417875712 +1662064562462876672 +1662064562510877696 +1662064562552878592 +1662064562594879488 +1662064562636880384 +1662064562681881344 +1662064562726882304 +1662064562768883200 +1662064562816884224 +1662064562861885184 +1662064562903886080 +1662064562948887040 +1662064562996888064 +1662064563038888960 +1662064563080889856 +1662064563122890752 +1662064563164891648 +1662064563209892608 +1662064563248893440 +1662064563290894336 +1662064563332895232 +1662064563374896128 +1662064563416897024 +1662064563461897984 +1662064563503898880 +1662064563545899776 +1662064563590900736 +1662064563632901632 +1662064563674902528 +1662064563719903488 +1662064563767904512 +1662064563806905344 +1662064563848906240 +1662064563887907072 +1662064563929907968 +1662064563971908864 +1662064564010909696 +1662064564052910592 +1662064564097911552 +1662064564139912448 +1662064564184913408 +1662064564226914304 +1662064564271915264 +1662064564313916160 +1662064564352916992 +1662064564397917952 +1662064564439918848 +1662064564484919808 +1662064564529920768 +1662064564571921664 +1662064564616922624 +1662064564658923520 +1662064564703924480 +1662064564745925376 +1662064564790926336 +1662064564832927232 +1662064564871928064 +1662064564913928960 +1662064564958929920 +1662064565000930816 +1662064565039931648 +1662064565081932544 +1662064565126933504 +1662064565171934464 +1662064565210935296 +1662064565255936256 +1662064565297937152 +1662064565339938048 +1662064565381938944 +1662064565426939904 +1662064565468940800 +1662064565510941696 +1662064565552942592 +1662064565594943488 +1662064565639944448 +1662064565681945344 +1662064565723946240 +1662064565768947200 +1662064565807948032 +1662064565849948928 +1662064565891949824 +1662064565933950720 +1662064565978951680 +1662064566020952576 +1662064566062953472 +1662064566104954368 +1662064566143955200 +1662064566188956160 +1662064566230957056 +1662064566263957760 +1662064566308958720 +1662064566353959680 +1662064566398960640 +1662064566440961536 +1662064566482962432 +1662064566527963392 +1662064566569964288 +1662064566617965312 +1662064566659966208 +1662064566701967104 +1662064566743968000 +1662064566785968896 +1662064566827969792 +1662064566872970752 +1662064566914971648 +1662064566959972608 +1662064567004973568 +1662064567046974464 +1662064567088975360 +1662064567133976320 +1662064567172977152 +1662064567214978048 +1662064567259979008 +1662064567298979840 +1662064567343980800 +1662064567388981760 +1662064567430982656 +1662064567472983552 +1662064567511984384 +1662064567556985344 +1662064567592986112 +1662064567634987008 +1662064567682988032 +1662064567721988864 +1662064567757989632 +1662064567799990528 +1662064567838991360 +1662064567880992256 +1662064567925993216 +1662064567964994048 +1662064568006994944 +1662064568051995904 +1662064568090996736 +1662064568132997632 +1662064568177998592 +1662064568222999552 +1662064568256000256 +1662064568301001216 +1662064568343002112 +1662064568385003008 +1662064568424003840 +1662064568466004736 +1662064568511005696 +1662064568553006592 +1662064568598007552 +1662064568640008448 +1662064568685009408 +1662064568724010240 +1662064568766011136 +1662064568811012096 +1662064568853012992 +1662064568898013952 +1662064568943014912 +1662064568988015872 +1662064569027016704 +1662064569069017600 +1662064569108018432 +1662064569150019328 +1662064569195020288 +1662064569234021120 +1662064569279022080 +1662064569324023040 +1662064569366023936 +1662064569411024896 +1662064569453025792 +1662064569498026752 +1662064569543027712 +1662064569582028544 +1662064569630029568 +1662064569672030464 +1662064569717031424 +1662064569759032320 +1662064569801033216 +1662064569837033984 +1662064569879034880 +1662064569927035904 +1662064569969036800 +1662064570011037696 +1662064570056038656 +1662064570101039616 +1662064570146040576 +1662064570188041472 +1662064570230042368 +1662064570275043328 +1662064570317044224 +1662064570359045120 +1662064570398045952 +1662064570443046912 +1662064570485047808 +1662064570527048704 +1662064570569049600 +1662064570614050560 +1662064570659051520 +1662064570701052416 +1662064570740053248 +1662064570782054144 +1662064570827055104 +1662064570869056000 +1662064570914056960 +1662064570959057920 +1662064571001058816 +1662064571043059712 +1662064571079060480 +1662064571124061440 +1662064571169062400 +1662064571211063296 +1662064571253064192 +1662064571298065152 +1662064571343066112 +1662064571394067200 +1662064571433068032 +1662064571478068992 +1662064571520069888 +1662064571565070848 +1662064571610071808 +1662064571652072704 +1662064571694073600 +1662064571736074496 +1662064571784075520 +1662064571829076480 +1662064571877077504 +1662064571919078400 +1662064571970079488 +1662064572012080384 +1662064572060081408 +1662064572102082304 +1662064572144083200 +1662064572186084096 +1662064572225084928 +1662064572267085824 +1662064572309086720 +1662064572357087744 +1662064572399088640 +1662064572444089600 +1662064572492090624 +1662064572540091648 +1662064572588092672 +1662064572630093568 +1662064572669094400 +1662064572714095360 +1662064572759096320 +1662064572801097216 +1662064572840098048 +1662064572882098944 +1662064572921099776 +1662064572966100736 +1662064573008101632 +1662064573050102528 +1662064573092103424 +1662064573134104320 +1662064573176105216 +1662064573215106048 +1662064573257106944 +1662064573299107840 +1662064573341108736 +1662064573383109632 +1662064573422110464 +1662064573464111360 +1662064573509112320 +1662064573545113088 +1662064573587113984 +1662064573629114880 +1662064573671115776 +1662064573710116608 +1662064573752117504 +1662064573794118400 +1662064573836119296 +1662064573878120192 +1662064573917121024 +1662064573959121920 +1662064574004122880 +1662064574049123840 +1662064574088124672 +1662064574133125632 +1662064574175126528 +1662064574220127488 +1662064574265128448 +1662064574304129280 +1662064574343130112 +1662064574388131072 +1662064574430131968 +1662064574475132928 +1662064574520133888 +1662064574556134656 +1662064574595135488 +1662064574637136384 +1662064574679137280 +1662064574721138176 +1662064574769139200 +1662064574811140096 +1662064574856141056 +1662064574898141952 +1662064574934142720 +1662064574970143488 +1662064575015144448 +1662064575057145344 +1662064575099146240 +1662064575144147200 +1662064575189148160 +1662064575231149056 +1662064575273149952 +1662064575318150912 +1662064575363151872 +1662064575408152832 +1662064575450153728 +1662064575489154560 +1662064575531155456 +1662064575579156480 +1662064575624157440 +1662064575663158272 +1662064575711159296 +1662064575756160256 +1662064575801161216 +1662064575840162048 +1662064575882162944 +1662064575924163840 +1662064575963164672 +1662064576008165632 +1662064576050166528 +1662064576095167488 +1662064576137168384 +1662064576182169344 +1662064576224170240 +1662064576263171072 +1662064576302171904 +1662064576347172864 +1662064576392173824 +1662064576434174720 +1662064576476175616 +1662064576518176512 +1662064576560177408 +1662064576608178432 +1662064576650179328 +1662064576701180416 +1662064576743181312 +1662064576782182144 +1662064576824183040 +1662064576866183936 +1662064576908184832 +1662064576950185728 +1662064576995186688 +1662064577034187520 +1662064577079188480 +1662064577118189312 +1662064577163190272 +1662064577205191168 +1662064577247192064 +1662064577289192960 +1662064577331193856 +1662064577373194752 +1662064577415195648 +1662064577460196608 +1662064577505197568 +1662064577547198464 +1662064577592199424 +1662064577634200320 +1662064577676201216 +1662064577718202112 +1662064577757202944 +1662064577799203840 +1662064577841204736 +1662064577886205696 +1662064577928206592 +1662064577973207552 +1662064578012208384 +1662064578051209216 +1662064578090210048 +1662064578132210944 +1662064578174211840 +1662064578219212800 +1662064578258213632 +1662064578306214656 +1662064578348215552 +1662064578393216512 +1662064578441217536 +1662064578489218560 +1662064578534219520 +1662064578576220416 +1662064578615221248 +1662064578657222144 +1662064578699223040 +1662064578741223936 +1662064578786224896 +1662064578828225792 +1662064578867226624 +1662064578912227584 +1662064578954228480 +1662064578996229376 +1662064579041230336 +1662064579080231168 +1662064579122232064 +1662064579161232896 +1662064579203233792 +1662064579248234752 +1662064579287235584 +1662064579329236480 +1662064579374237440 +1662064579422238464 +1662064579470239488 +1662064579515240448 +1662064579557241344 +1662064579599242240 +1662064579638243072 +1662064579680243968 +1662064579728244992 +1662064579773245952 +1662064579815246848 +1662064579860247808 +1662064579902248704 +1662064579944249600 +1662064579986250496 +1662064580028251392 +1662064580067252224 +1662064580112253184 +1662064580151254016 +1662064580190254848 +1662064580229255680 +1662064580271256576 +1662064580310257408 +1662064580352258304 +1662064580394259200 +1662064580442260224 +1662064580484261120 +1662064580526262016 +1662064580568262912 +1662064580610263808 +1662064580655264768 +1662064580697265664 +1662064580739266560 +1662064580781267456 +1662064580823268352 +1662064580868269312 +1662064580916270336 +1662064580955271168 +1662064581000272128 +1662064581045273088 +1662064581087273984 +1662064581135275008 +1662064581177275904 +1662064581222276864 +1662064581267277824 +1662064581312278784 +1662064581357279744 +1662064581399280640 +1662064581441281536 +1662064581489282560 +1662064581531283456 +1662064581564284160 +1662064581606285056 +1662064581651286016 +1662064581690286848 +1662064581732287744 +1662064581777288704 +1662064581816289536 +1662064581861290496 +1662064581903291392 +1662064581945292288 +1662064581987293184 +1662064582032294144 +1662064582068294912 +1662064582113295872 +1662064582152296704 +1662064582194297600 +1662064582239298560 +1662064582278299392 +1662064582320300288 +1662064582365301248 +1662064582404302080 +1662064582446302976 +1662064582485303808 +1662064582536304896 +1662064582578305792 +1662064582620306688 +1662064582665307648 +1662064582707308544 +1662064582752309504 +1662064582794310400 +1662064582839311360 +1662064582881312256 +1662064582923313152 +1662064582965314048 +1662064583007314944 +1662064583058316032 +1662064583100316928 +1662064583145317888 +1662064583187318784 +1662064583229319680 +1662064583274320640 +1662064583319321600 +1662064583364322560 +1662064583409323520 +1662064583454324480 +1662064583499325440 +1662064583544326400 +1662064583589327360 +1662064583631328256 +1662064583676329216 +1662064583715330048 +1662064583760331008 +1662064583802331904 +1662064583847332864 +1662064583886333696 +1662064583928334592 +1662064583973335552 +1662064584018336512 +1662064584063337472 +1662064584102338304 +1662064584141339136 +1662064584183340032 +1662064584222340864 +1662064584264341760 +1662064584309342720 +1662064584351343616 +1662064584393344512 +1662064584435345408 +1662064584477346304 +1662064584519347200 +1662064584561348096 +1662064584600348928 +1662064584645349888 +1662064584690350848 +1662064584729351680 +1662064584774352640 +1662064584816353536 +1662064584861354496 +1662064584903355392 +1662064584945356288 +1662064584990357248 +1662064585032358144 +1662064585074359040 +1662064585116359936 +1662064585164360960 +1662064585206361856 +1662064585248362752 +1662064585293363712 +1662064585332364544 +1662064585377365504 +1662064585419366400 +1662064585464367360 +1662064585509368320 +1662064585557369344 +1662064585599370240 +1662064585641371136 +1662064585686372096 +1662064585731373056 +1662064585779374080 +1662064585824375040 +1662064585866375936 +1662064585914376960 +1662064585953377792 +1662064586001378816 +1662064586043379712 +1662064586088380672 +1662064586133381632 +1662064586175382528 +1662064586217383424 +1662064586262384384 +1662064586307385344 +1662064586352386304 +1662064586394387200 +1662064586442388224 +1662064586484389120 +1662064586526390016 +1662064586574391040 +1662064586619392000 +1662064586664392960 +1662064586706393856 +1662064586748394752 +1662064586790395648 +1662064586835396608 +1662064586874397440 +1662064586919398400 +1662064586964399360 +1662064587006400256 +1662064587048401152 +1662064587093402112 +1662064587135403008 +1662064587180403968 +1662064587225404928 +1662064587267405824 +1662064587312406784 +1662064587357407744 +1662064587396408576 +1662064587441409536 +1662064587483410432 +1662064587531411456 +1662064587576412416 +1662064587621413376 +1662064587666414336 +1662064587708415232 +1662064587750416128 +1662064587798417152 +1662064587840418048 +1662064587882418944 +1662064587921419776 +1662064587963420672 +1662064588005421568 +1662064588041422336 +1662064588083423232 +1662064588122424064 +1662064588173425152 +1662064588212425984 +1662064588257426944 +1662064588299427840 +1662064588341428736 +1662064588386429696 +1662064588431430656 +1662064588476431616 +1662064588521432576 +1662064588563433472 +1662064588608434432 +1662064588647435264 +1662064588689436160 +1662064588734437120 +1662064588776438016 +1662064588815438848 +1662064588860439808 +1662064588902440704 +1662064588938441472 +1662064588983442432 +1662064589025443328 +1662064589067444224 +1662064589112445184 +1662064589154446080 +1662064589196446976 +1662064589244448000 +1662064589280448768 +1662064589322449664 +1662064589364450560 +1662064589406451456 +1662064589445452288 +1662064589487453184 +1662064589532454144 +1662064589571454976 +1662064589613455872 +1662064589658456832 +1662064589697457664 +1662064589742458624 +1662064589781459456 +1662064589823460352 +1662064589865461248 +1662064589907462144 +1662064589949463040 +1662064589994464000 +1662064590036464896 +1662064590081465856 +1662064590123466752 +1662064590168467712 +1662064590210468608 +1662064590255469568 +1662064590300470528 +1662064590348471552 +1662064590390472448 +1662064590435473408 +1662064590477474304 +1662064590516475136 +1662064590552475904 +1662064590594476800 +1662064590639477760 +1662064590687478784 +1662064590723479552 +1662064590762480384 +1662064590810481408 +1662064590849482240 +1662064590894483200 +1662064590939484160 +1662064590981485056 +1662064591023485952 +1662064591065486848 +1662064591107487744 +1662064591158488832 +1662064591206489856 +1662064591254490880 +1662064591296491776 +1662064591344492800 +1662064591389493760 +1662064591431494656 +1662064591479495680 +1662064591524496640 +1662064591569497600 +1662064591611498496 +1662064591650499328 +1662064591689500160 +1662064591734501120 +1662064591776502016 +1662064591821502976 +1662064591863503872 +1662064591905504768 +1662064591950505728 +1662064591992506624 +1662064592037507584 +1662064592079508480 +1662064592124509440 +1662064592163510272 +1662064592202511104 +1662064592247512064 +1662064592289512960 +1662064592328513792 +1662064592370514688 +1662064592412515584 +1662064592451516416 +1662064592490517248 +1662064592532518144 +1662064592577519104 +1662064592622520064 +1662064592661520896 +1662064592706521856 +1662064592748522752 +1662064592790523648 +1662064592829524480 +1662064592871525376 +1662064592913526272 +1662064592955527168 +1662064593000528128 +1662064593045529088 +1662064593087529984 +1662064593129530880 +1662064593168531712 +1662064593210532608 +1662064593252533504 +1662064593297534464 +1662064593342535424 +1662064593384536320 +1662064593429537280 +1662064593468538112 +1662064593510539008 +1662064593555539968 +1662064593600540928 +1662064593648541952 +1662064593687542784 +1662064593732543744 +1662064593771544576 +1662064593816545536 +1662064593861546496 +1662064593903547392 +1662064593942548224 +1662064593984549120 +1662064594026550016 +1662064594071550976 +1662064594113551872 +1662064594161552896 +1662064594206553856 +1662064594248554752 +1662064594287555584 +1662064594326556416 +1662064594371557376 +1662064594416558336 +1662064594452559104 +1662064594494560000 +1662064594533560832 +1662064594578561792 +1662064594623562752 +1662064594665563648 +1662064594704564480 +1662064594746565376 +1662064594788566272 +1662064594830567168 +1662064594869568000 +1662064594908568832 +1662064594950569728 +1662064594995570688 +1662064595037571584 +1662064595076572416 +1662064595115573248 +1662064595157574144 +1662064595199575040 +1662064595244576000 +1662064595286576896 +1662064595331577856 +1662064595373578752 +1662064595415579648 +1662064595460580608 +1662064595502581504 +1662064595550582528 +1662064595592583424 +1662064595637584384 +1662064595676585216 +1662064595718586112 +1662064595757586944 +1662064595802587904 +1662064595847588864 +1662064595886589696 +1662064595925590528 +1662064595967591424 +1662064596012592384 +1662064596057593344 +1662064596099594240 +1662064596141595136 +1662064596183596032 +1662064596228596992 +1662064596273597952 +1662064596312598784 +1662064596357599744 +1662064596402600704 +1662064596441601536 +1662064596483602432 +1662064596525603328 +1662064596567604224 +1662064596606605056 +1662064596648605952 +1662064596687606784 +1662064596729607680 +1662064596771608576 +1662064596816609536 +1662064596858610432 +1662064596900611328 +1662064596939612160 +1662064596975612928 +1662064597020613888 +1662064597068614912 +1662064597110615808 +1662064597155616768 +1662064597197617664 +1662064597239618560 +1662064597284619520 +1662064597326620416 +1662064597368621312 +1662064597410622208 +1662064597452623104 +1662064597497624064 +1662064597542625024 +1662064597584625920 +1662064597626626816 +1662064597668627712 +1662064597707628544 +1662064597749629440 +1662064597788630272 +1662064597836631296 +1662064597878632192 +1662064597920633088 +1662064597962633984 +1662064598010635008 +1662064598052635904 +1662064598097636864 +1662064598139637760 +1662064598175638528 +1662064598220639488 +1662064598259640320 +1662064598301641216 +1662064598346642176 +1662064598391643136 +1662064598433644032 +1662064598481645056 +1662064598520645888 +1662064598559646720 +1662064598601647616 +1662064598643648512 +1662064598685649408 +1662064598727650304 +1662064598772651264 +1662064598814652160 +1662064598859653120 +1662064598901654016 +1662064598943654912 +1662064598985655808 +1662064599027656704 +1662064599069657600 +1662064599114658560 +1662064599156659456 +1662064599201660416 +1662064599243661312 +1662064599288662272 +1662064599330663168 +1662064599372664064 +1662064599420665088 +1662064599465666048 +1662064599510667008 +1662064599552667904 +1662064599591668736 +1662064599639669760 +1662064599681670656 +1662064599723671552 +1662064599771672576 +1662064599810673408 +1662064599852674304 +1662064599900675328 +1662064599939676160 +1662064599981677056 +1662064600026678016 +1662064600071678976 +1662064600113679872 +1662064600158680832 +1662064600200681728 +1662064600245682688 +1662064600287683584 +1662064600329684480 +1662064600371685376 +1662064600416686336 +1662064600458687232 +1662064600497688064 +1662064600539688960 +1662064600581689856 +1662064600623690752 +1662064600668691712 +1662064600713692672 +1662064600761693696 +1662064600806694656 +1662064600851695616 +1662064600899696640 +1662064600947697664 +1662064600989698560 +1662064601031699456 +1662064601079700480 +1662064601124701440 +1662064601172702464 +1662064601217703424 +1662064601262704384 +1662064601307705344 +1662064601349706240 +1662064601388707072 +1662064601424707840 +1662064601466708736 +1662064601511709696 +1662064601550710528 +1662064601595711488 +1662064601640712448 +1662064601685713408 +1662064601727714304 +1662064601769715200 +1662064601811716096 +1662064601853716992 +1662064601901718016 +1662064601943718912 +1662064601988719872 +1662064602036720896 +1662064602078721792 +1662064602120722688 +1662064602168723712 +1662064602210724608 +1662064602249725440 +1662064602294726400 +1662064602333727232 +1662064602375728128 +1662064602414728960 +1662064602456729856 +1662064602495730688 +1662064602546731776 +1662064602591732736 +1662064602633733632 +1662064602675734528 +1662064602714735360 +1662064602762736384 +1662064602807737344 +1662064602846738176 +1662064602888739072 +1662064602930739968 +1662064602972740864 +1662064603017741824 +1662064603056742656 +1662064603095743488 +1662064603140744448 +1662064603182745344 +1662064603218746112 +1662064603269747200 +1662064603308748032 +1662064603347748864 +1662064603389749760 +1662064603434750720 +1662064603479751680 +1662064603521752576 +1662064603563753472 +1662064603605754368 +1662064603650755328 +1662064603689756160 +1662064603740757248 +1662064603782758144 +1662064603827759104 +1662064603869760000 +1662064603914760960 +1662064603950761728 +1662064603992762624 +1662064604034763520 +1662064604076764416 +1662064604118765312 +1662064604160766208 +1662064604208767232 +1662064604247768064 +1662064604289768960 +1662064604337769984 +1662064604379770880 +1662064604421771776 +1662064604463772672 +1662064604508773632 +1662064604550774528 +1662064604595775488 +1662064604640776448 +1662064604682777344 +1662064604724778240 +1662064604769779200 +1662064604814780160 +1662064604853780992 +1662064604901782016 +1662064604943782912 +1662064604985783808 +1662064605027784704 +1662064605072785664 +1662064605114786560 +1662064605156787456 +1662064605198788352 +1662064605240789248 +1662064605282790144 +1662064605324791040 +1662064605366791936 +1662064605411792896 +1662064605462793984 +1662064605510795008 +1662064605552795904 +1662064605591796736 +1662064605630797568 +1662064605672798464 +1662064605714799360 +1662064605765800448 +1662064605810801408 +1662064605852802304 +1662064605897803264 +1662064605936804096 +1662064605978804992 +1662064606020805888 +1662064606065806848 +1662064606110807808 +1662064606155808768 +1662064606197809664 +1662064606242810624 +1662064606287811584 +1662064606329812480 +1662064606368813312 +1662064606413814272 +1662064606452815104 +1662064606491815936 +1662064606533816832 +1662064606578817792 +1662064606620818688 +1662064606668819712 +1662064606710820608 +1662064606752821504 +1662064606794822400 +1662064606836823296 +1662064606881824256 +1662064606923825152 +1662064606968826112 +1662064607010827008 +1662064607055827968 +1662064607100828928 +1662064607142829824 +1662064607187830784 +1662064607229831680 +1662064607271832576 +1662064607316833536 +1662064607358834432 +1662064607406835456 +1662064607448836352 +1662064607493837312 +1662064607535838208 +1662064607577839104 +1662064607619840000 +1662064607664840960 +1662064607709841920 +1662064607751842816 +1662064607790843648 +1662064607829844480 +1662064607871845376 +1662064607910846208 +1662064607958847232 +1662064608003848192 +1662064608048849152 +1662064608090850048 +1662064608135851008 +1662064608177851904 +1662064608219852800 +1662064608267853824 +1662064608312854784 +1662064608354855680 +1662064608396856576 +1662064608441857536 +1662064608486858496 +1662064608528859392 +1662064608570860288 +1662064608615861248 +1662064608657862144 +1662064608699863040 +1662064608744864000 +1662064608786864896 +1662064608828865792 +1662064608870866688 +1662064608915867648 +1662064608957868544 +1662064608999869440 +1662064609038870272 +1662064609083871232 +1662064609128872192 +1662064609170873088 +1662064609212873984 +1662064609254874880 +1662064609299875840 +1662064609341876736 +1662064609386877696 +1662064609428878592 +1662064609470879488 +1662064609515880448 +1662064609560881408 +1662064609605882368 +1662064609653883392 +1662064609698884352 +1662064609740885248 +1662064609785886208 +1662064609827887104 +1662064609869888000 +1662064609917889024 +1662064609956889856 +1662064610001890816 +1662064610043891712 +1662064610082892544 +1662064610124893440 +1662064610166894336 +1662064610208895232 +1662064610250896128 +1662064610292897024 +1662064610334897920 +1662064610376898816 +1662064610418899712 +1662064610463900672 +1662064610505901568 +1662064610547902464 +1662064610589903360 +1662064610634904320 +1662064610676905216 +1662064610715906048 +1662064610760907008 +1662064610805907968 +1662064610850908928 +1662064610889909760 +1662064610931910656 +1662064610976911616 +1662064611021912576 +1662064611066913536 +1662064611111914496 +1662064611153915392 +1662064611198916352 +1662064611240917248 +1662064611282918144 +1662064611321918976 +1662064611363919872 +1662064611402920704 +1662064611447921664 +1662064611495922688 +1662064611537923584 +1662064611579924480 +1662064611627925504 +1662064611666926336 +1662064611708927232 +1662064611753928192 +1662064611795929088 +1662064611843930112 +1662064611885931008 +1662064611924931840 +1662064611969932800 +1662064612017933824 +1662064612059934720 +1662064612104935680 +1662064612149936640 +1662064612194937600 +1662064612233938432 +1662064612278939392 +1662064612326940416 +1662064612371941376 +1662064612410942208 +1662064612452943104 +1662064612491943936 +1662064612530944768 +1662064612569945600 +1662064612614946560 +1662064612659947520 +1662064612704948480 +1662064612749949440 +1662064612788950272 +1662064612833951232 +1662064612875952128 +1662064612917953024 +1662064612956953856 +1662064613001954816 +1662064613040955648 +1662064613085956608 +1662064613130957568 +1662064613178958592 +1662064613220959488 +1662064613262960384 +1662064613304961280 +1662064613346962176 +1662064613385963008 +1662064613430963968 +1662064613469964800 +1662064613511965696 +1662064613553966592 +1662064613595967488 +1662064613634968320 +1662064613673969152 +1662064613715970048 +1662064613757970944 +1662064613805971968 +1662064613847972864 +1662064613886973696 +1662064613925974528 +1662064613976975616 +1662064614015976448 +1662064614057977344 +1662064614102978304 +1662064614144979200 +1662064614186980096 +1662064614228980992 +1662064614267981824 +1662064614318982912 +1662064614360983808 +1662064614405984768 +1662064614447985664 +1662064614489986560 +1662064614531987456 +1662064614570988288 +1662064614609989120 +1662064614654990080 +1662064614696990976 +1662064614741991936 +1662064614783992832 +1662064614828993792 +1662064614870994688 +1662064614915995648 +1662064614960996608 +1662064615002997504 +1662064615044998400 +1662064615086999296 +1662064615132000256 +1662064615177001216 +1662064615219002112 +1662064615261003008 +1662064615303003904 +1662064615345004800 +1662064615384005632 +1662064615423006464 +1662064615462007296 +1662064615498008064 +1662064615546009088 +1662064615588009984 +1662064615630010880 +1662064615675011840 +1662064615714012672 +1662064615756013568 +1662064615798014464 diff --git a/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt new file mode 100644 index 0000000000..51983432b0 --- /dev/null +++ b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt @@ -0,0 +1,2076 @@ +1662125073430662912 +1662125073472663808 +1662125073511664640 +1662125073553665536 +1662125073598666496 +1662125073643667456 +1662125073688668416 +1662125073733669376 +1662125073781670400 +1662125073823671296 +1662125073865672192 +1662125073907673088 +1662125073952674048 +1662125073997675008 +1662125074042675968 +1662125074087676928 +1662125074132677888 +1662125074174678784 +1662125074216679680 +1662125074258680576 +1662125074303681536 +1662125074345682432 +1662125074387683328 +1662125074429684224 +1662125074474685184 +1662125074519686144 +1662125074564687104 +1662125074606688000 +1662125074651688960 +1662125074696689920 +1662125074741690880 +1662125074789691904 +1662125074831692800 +1662125074879693824 +1662125074918694656 +1662125074960695552 +1662125074999696384 +1662125075044697344 +1662125075086698240 +1662125075131699200 +1662125075176700160 +1662125075224701184 +1662125075269702144 +1662125075308702976 +1662125075347703808 +1662125075389704704 +1662125075440705792 +1662125075482706688 +1662125075524707584 +1662125075569708544 +1662125075617709568 +1662125075659710464 +1662125075701711360 +1662125075746712320 +1662125075788713216 +1662125075830714112 +1662125075872715008 +1662125075917715968 +1662125075956716800 +1662125076001717760 +1662125076046718720 +1662125076091719680 +1662125076139720704 +1662125076181721600 +1662125076223722496 +1662125076265723392 +1662125076307724288 +1662125076358725376 +1662125076400726272 +1662125076445727232 +1662125076490728192 +1662125076538729216 +1662125076580730112 +1662125076625731072 +1662125076670732032 +1662125076712732928 +1662125076754733824 +1662125076796734720 +1662125076847735808 +1662125076889736704 +1662125076934737664 +1662125076976738560 +1662125077024739584 +1662125077072740608 +1662125077114741504 +1662125077156742400 +1662125077195743232 +1662125077237744128 +1662125077279745024 +1662125077327746048 +1662125077366746880 +1662125077411747840 +1662125077453748736 +1662125077498749696 +1662125077540750592 +1662125077582751488 +1662125077627752448 +1662125077669753344 +1662125077711754240 +1662125077753755136 +1662125077795756032 +1662125077837756928 +1662125077879757824 +1662125077924758784 +1662125077969759744 +1662125078011760640 +1662125078056761600 +1662125078098762496 +1662125078143763456 +1662125078188764416 +1662125078227765248 +1662125078272766208 +1662125078314767104 +1662125078359768064 +1662125078401768960 +1662125078446769920 +1662125078494770944 +1662125078539771904 +1662125078587772928 +1662125078635773952 +1662125078677774848 +1662125078725775872 +1662125078767776768 +1662125078809777664 +1662125078848778496 +1662125078896779520 +1662125078938780416 +1662125078986781440 +1662125079025782272 +1662125079070783232 +1662125079112784128 +1662125079157785088 +1662125079199785984 +1662125079244786944 +1662125079289787904 +1662125079331788800 +1662125079373789696 +1662125079412790528 +1662125079457791488 +1662125079502792448 +1662125079541793280 +1662125079589794304 +1662125079625795072 +1662125079676796160 +1662125079715796992 +1662125079760797952 +1662125079802798848 +1662125079847799808 +1662125079892800768 +1662125079934801664 +1662125079976802560 +1662125080024803584 +1662125080066804480 +1662125080114805504 +1662125080162806528 +1662125080204807424 +1662125080246808320 +1662125080291809280 +1662125080336810240 +1662125080381811200 +1662125080423812096 +1662125080468813056 +1662125080510813952 +1662125080552814848 +1662125080597815808 +1662125080639816704 +1662125080684817664 +1662125080729818624 +1662125080771819520 +1662125080819820544 +1662125080861821440 +1662125080900822272 +1662125080948823296 +1662125080990824192 +1662125081032825088 +1662125081080826112 +1662125081122827008 +1662125081164827904 +1662125081206828800 +1662125081248829696 +1662125081296830720 +1662125081338831616 +1662125081380832512 +1662125081425833472 +1662125081467834368 +1662125081515835392 +1662125081557836288 +1662125081605837312 +1662125081653838336 +1662125081698839296 +1662125081743840256 +1662125081788841216 +1662125081833842176 +1662125081872843008 +1662125081923844096 +1662125081965844992 +1662125082010845952 +1662125082055846912 +1662125082097847808 +1662125082136848640 +1662125082178849536 +1662125082217850368 +1662125082256851200 +1662125082298852096 +1662125082346853120 +1662125082388854016 +1662125082433854976 +1662125082475855872 +1662125082520856832 +1662125082565857792 +1662125082610858752 +1662125082652859648 +1662125082697860608 +1662125082742861568 +1662125082781862400 +1662125082820863232 +1662125082859864064 +1662125082901864960 +1662125082943865856 +1662125082982866688 +1662125083024867584 +1662125083066868480 +1662125083111869440 +1662125083159870464 +1662125083207871488 +1662125083249872384 +1662125083294873344 +1662125083336874240 +1662125083378875136 +1662125083420876032 +1662125083462876928 +1662125083510877952 +1662125083555878912 +1662125083597879808 +1662125083639880704 +1662125083684881664 +1662125083726882560 +1662125083774883584 +1662125083813884416 +1662125083855885312 +1662125083900886272 +1662125083942887168 +1662125083984888064 +1662125084026888960 +1662125084068889856 +1662125084113890816 +1662125084155891712 +1662125084200892672 +1662125084242893568 +1662125084284894464 +1662125084326895360 +1662125084371896320 +1662125084416897280 +1662125084464898304 +1662125084509899264 +1662125084557900288 +1662125084605901312 +1662125084653902336 +1662125084695903232 +1662125084737904128 +1662125084776904960 +1662125084818905856 +1662125084857906688 +1662125084899907584 +1662125084944908544 +1662125084989909504 +1662125085031910400 +1662125085076911360 +1662125085127912448 +1662125085169913344 +1662125085214914304 +1662125085259915264 +1662125085301916160 +1662125085346917120 +1662125085388918016 +1662125085439919104 +1662125085481920000 +1662125085523920896 +1662125085565921792 +1662125085604922624 +1662125085649923584 +1662125085694924544 +1662125085739925504 +1662125085781926400 +1662125085826927360 +1662125085868928256 +1662125085913929216 +1662125085955930112 +1662125086000931072 +1662125086045932032 +1662125086087932928 +1662125086126933760 +1662125086168934656 +1662125086210935552 +1662125086249936384 +1662125086291937280 +1662125086333938176 +1662125086378939136 +1662125086423940096 +1662125086468941056 +1662125086519942144 +1662125086558942976 +1662125086603943936 +1662125086648944896 +1662125086693945856 +1662125086744946944 +1662125086783947776 +1662125086825948672 +1662125086870949632 +1662125086909950464 +1662125086951951360 +1662125086993952256 +1662125087038953216 +1662125087083954176 +1662125087125955072 +1662125087170956032 +1662125087215956992 +1662125087257957888 +1662125087299958784 +1662125087341959680 +1662125087386960640 +1662125087428961536 +1662125087473962496 +1662125087515963392 +1662125087557964288 +1662125087599965184 +1662125087644966144 +1662125087686967040 +1662125087731968000 +1662125087773968896 +1662125087812969728 +1662125087857970688 +1662125087896971520 +1662125087938972416 +1662125087977973248 +1662125088016974080 +1662125088061975040 +1662125088100975872 +1662125088151976960 +1662125088196977920 +1662125088241978880 +1662125088283979776 +1662125088334980864 +1662125088376981760 +1662125088418982656 +1662125088466983680 +1662125088511984640 +1662125088553985536 +1662125088601986560 +1662125088643987456 +1662125088685988352 +1662125088727989248 +1662125088766990080 +1662125088811991040 +1662125088856992000 +1662125088898992896 +1662125088943993856 +1662125088982994688 +1662125089018995456 +1662125089063996416 +1662125089108997376 +1662125089150998272 +1662125089189999104 +1662125089232000000 +1662125089277000960 +1662125089322001920 +1662125089373003008 +1662125089415003904 +1662125089457004800 +1662125089499005696 +1662125089550006784 +1662125089598007808 +1662125089640008704 +1662125089682009600 +1662125089727010560 +1662125089772011520 +1662125089814012416 +1662125089856013312 +1662125089898014208 +1662125089946015232 +1662125089991016192 +1662125090033017088 +1662125090075017984 +1662125090123019008 +1662125090165019904 +1662125090204020736 +1662125090243021568 +1662125090282022400 +1662125090327023360 +1662125090366024192 +1662125090402024960 +1662125090447025920 +1662125090489026816 +1662125090528027648 +1662125090573028608 +1662125090618029568 +1662125090660030464 +1662125090705031424 +1662125090747032320 +1662125090789033216 +1662125090834034176 +1662125090879035136 +1662125090930036224 +1662125090975037184 +1662125091020038144 +1662125091065039104 +1662125091110040064 +1662125091155041024 +1662125091197041920 +1662125091239042816 +1662125091284043776 +1662125091326044672 +1662125091368045568 +1662125091419046656 +1662125091461047552 +1662125091506048512 +1662125091548049408 +1662125091593050368 +1662125091635051264 +1662125091677052160 +1662125091719053056 +1662125091761053952 +1662125091806054912 +1662125091845055744 +1662125091887056640 +1662125091929057536 +1662125091977058560 +1662125092022059520 +1662125092067060480 +1662125092106061312 +1662125092148062208 +1662125092193063168 +1662125092235064064 +1662125092277064960 +1662125092319065856 +1662125092361066752 +1662125092406067712 +1662125092451068672 +1662125092496069632 +1662125092535070464 +1662125092580071424 +1662125092622072320 +1662125092667073280 +1662125092709074176 +1662125092751075072 +1662125092796076032 +1662125092838076928 +1662125092883077888 +1662125092925078784 +1662125092967079680 +1662125093012080640 +1662125093054081536 +1662125093102082560 +1662125093141083392 +1662125093183084288 +1662125093219085056 +1662125093261085952 +1662125093303086848 +1662125093348087808 +1662125093393088768 +1662125093435089664 +1662125093477090560 +1662125093522091520 +1662125093564092416 +1662125093606093312 +1662125093648094208 +1662125093690095104 +1662125093732096000 +1662125093771096832 +1662125093816097792 +1662125093858098688 +1662125093900099584 +1662125093942100480 +1662125093981101312 +1662125094023102208 +1662125094065103104 +1662125094110104064 +1662125094152104960 +1662125094194105856 +1662125094239106816 +1662125094284107776 +1662125094329108736 +1662125094377109760 +1662125094422110720 +1662125094467111680 +1662125094506112512 +1662125094548113408 +1662125094590114304 +1662125094638115328 +1662125094680116224 +1662125094722117120 +1662125094770118144 +1662125094815119104 +1662125094860120064 +1662125094908121088 +1662125094950121984 +1662125094995122944 +1662125095040123904 +1662125095085124864 +1662125095127125760 +1662125095169126656 +1662125095214127616 +1662125095253128448 +1662125095298129408 +1662125095340130304 +1662125095382131200 +1662125095424132096 +1662125095475133184 +1662125095517134080 +1662125095568135168 +1662125095613136128 +1662125095649136896 +1662125095685137664 +1662125095727138560 +1662125095772139520 +1662125095817140480 +1662125095856141312 +1662125095901142272 +1662125095940143104 +1662125095985144064 +1662125096024144896 +1662125096069145856 +1662125096114146816 +1662125096159147776 +1662125096201148672 +1662125096246149632 +1662125096291150592 +1662125096336151552 +1662125096381152512 +1662125096423153408 +1662125096465154304 +1662125096510155264 +1662125096555156224 +1662125096600157184 +1662125096648158208 +1662125096693159168 +1662125096732160000 +1662125096780161024 +1662125096819161856 +1662125096870162944 +1662125096909163776 +1662125096951164672 +1662125096993165568 +1662125097035166464 +1662125097080167424 +1662125097125168384 +1662125097170169344 +1662125097212170240 +1662125097251171072 +1662125097296172032 +1662125097338172928 +1662125097383173888 +1662125097428174848 +1662125097467175680 +1662125097512176640 +1662125097554177536 +1662125097596178432 +1662125097638179328 +1662125097680180224 +1662125097722181120 +1662125097764182016 +1662125097806182912 +1662125097848183808 +1662125097899184896 +1662125097944185856 +1662125097992186880 +1662125098034187776 +1662125098076188672 +1662125098118189568 +1662125098160190464 +1662125098205191424 +1662125098247192320 +1662125098289193216 +1662125098328194048 +1662125098373195008 +1662125098415195904 +1662125098457196800 +1662125098502197760 +1662125098544198656 +1662125098586199552 +1662125098637200640 +1662125098682201600 +1662125098724202496 +1662125098772203520 +1662125098814204416 +1662125098850205184 +1662125098892206080 +1662125098937207040 +1662125098985208064 +1662125099027208960 +1662125099072209920 +1662125099114210816 +1662125099153211648 +1662125099195212544 +1662125099240213504 +1662125099282214400 +1662125099330215424 +1662125099378216448 +1662125099423217408 +1662125099468218368 +1662125099510219264 +1662125099555220224 +1662125099600221184 +1662125099645222144 +1662125099687223040 +1662125099732224000 +1662125099774224896 +1662125099816225792 +1662125099861226752 +1662125099906227712 +1662125099951228672 +1662125099996229632 +1662125100041230592 +1662125100083231488 +1662125100122232320 +1662125100161233152 +1662125100209234176 +1662125100251235072 +1662125100296236032 +1662125100338236928 +1662125100383237888 +1662125100428238848 +1662125100470239744 +1662125100515240704 +1662125100551241472 +1662125100596242432 +1662125100635243264 +1662125100680244224 +1662125100722245120 +1662125100764246016 +1662125100806246912 +1662125100845247744 +1662125100890248704 +1662125100932249600 +1662125100977250560 +1662125101016251392 +1662125101061252352 +1662125101103253248 +1662125101145254144 +1662125101187255040 +1662125101229255936 +1662125101271256832 +1662125101316257792 +1662125101364258816 +1662125101412259840 +1662125101457260800 +1662125101499261696 +1662125101541262592 +1662125101580263424 +1662125101625264384 +1662125101673265408 +1662125101715266304 +1662125101760267264 +1662125101802268160 +1662125101844269056 +1662125101892270080 +1662125101934270976 +1662125101979271936 +1662125102027272960 +1662125102072273920 +1662125102114274816 +1662125102162275840 +1662125102204276736 +1662125102240277504 +1662125102279278336 +1662125102318279168 +1662125102363280128 +1662125102405281024 +1662125102441281792 +1662125102480282624 +1662125102522283520 +1662125102567284480 +1662125102612285440 +1662125102654286336 +1662125102696287232 +1662125102735288064 +1662125102777288960 +1662125102828290048 +1662125102870290944 +1662125102918291968 +1662125102963292928 +1662125103008293888 +1662125103050294784 +1662125103092295680 +1662125103137296640 +1662125103179297536 +1662125103221298432 +1662125103269299456 +1662125103308300288 +1662125103356301312 +1662125103401302272 +1662125103446303232 +1662125103485304064 +1662125103524304896 +1662125103563305728 +1662125103602306560 +1662125103644307456 +1662125103686308352 +1662125103728309248 +1662125103770310144 +1662125103812311040 +1662125103854311936 +1662125103896312832 +1662125103938313728 +1662125103980314624 +1662125104022315520 +1662125104064316416 +1662125104109317376 +1662125104151318272 +1662125104196319232 +1662125104241320192 +1662125104286321152 +1662125104328322048 +1662125104370322944 +1662125104412323840 +1662125104457324800 +1662125104496325632 +1662125104541326592 +1662125104592327680 +1662125104637328640 +1662125104682329600 +1662125104724330496 +1662125104769331456 +1662125104814332416 +1662125104859333376 +1662125104901334272 +1662125104952335360 +1662125104994336256 +1662125105036337152 +1662125105078338048 +1662125105126339072 +1662125105168339968 +1662125105210340864 +1662125105252341760 +1662125105294342656 +1662125105336343552 +1662125105381344512 +1662125105423345408 +1662125105468346368 +1662125105510347264 +1662125105552348160 +1662125105603349248 +1662125105648350208 +1662125105690351104 +1662125105729351936 +1662125105774352896 +1662125105819353856 +1662125105861354752 +1662125105906355712 +1662125105957356800 +1662125106002357760 +1662125106044358656 +1662125106089359616 +1662125106137360640 +1662125106176361472 +1662125106218362368 +1662125106260363264 +1662125106305364224 +1662125106350365184 +1662125106395366144 +1662125106440367104 +1662125106485368064 +1662125106527368960 +1662125106566369792 +1662125106611370752 +1662125106656371712 +1662125106701372672 +1662125106743373568 +1662125106791374592 +1662125106833375488 +1662125106878376448 +1662125106917377280 +1662125106959378176 +1662125107004379136 +1662125107046380032 +1662125107085380864 +1662125107133381888 +1662125107172382720 +1662125107208383488 +1662125107253384448 +1662125107298385408 +1662125107346386432 +1662125107388387328 +1662125107430388224 +1662125107472389120 +1662125107514390016 +1662125107553390848 +1662125107595391744 +1662125107637392640 +1662125107679393536 +1662125107718394368 +1662125107760395264 +1662125107802396160 +1662125107850397184 +1662125107895398144 +1662125107937399040 +1662125107982400000 +1662125108027400960 +1662125108069401856 +1662125108111402752 +1662125108156403712 +1662125108198404608 +1662125108240405504 +1662125108285406464 +1662125108333407488 +1662125108378408448 +1662125108423409408 +1662125108468410368 +1662125108507411200 +1662125108549412096 +1662125108588412928 +1662125108633413888 +1662125108672414720 +1662125108723415808 +1662125108765416704 +1662125108804417536 +1662125108849418496 +1662125108888419328 +1662125108933420288 +1662125108978421248 +1662125109017422080 +1662125109059422976 +1662125109101423872 +1662125109140424704 +1662125109185425664 +1662125109227426560 +1662125109269427456 +1662125109314428416 +1662125109359429376 +1662125109395430144 +1662125109437431040 +1662125109479431936 +1662125109521432832 +1662125109560433664 +1662125109602434560 +1662125109641435392 +1662125109689436416 +1662125109731437312 +1662125109776438272 +1662125109821439232 +1662125109860440064 +1662125109902440960 +1662125109944441856 +1662125109989442816 +1662125110028443648 +1662125110073444608 +1662125110121445632 +1662125110160446464 +1662125110202447360 +1662125110244448256 +1662125110286449152 +1662125110331450112 +1662125110370450944 +1662125110412451840 +1662125110457452800 +1662125110499453696 +1662125110544454656 +1662125110589455616 +1662125110631456512 +1662125110673457408 +1662125110715458304 +1662125110760459264 +1662125110808460288 +1662125110850461184 +1662125110889462016 +1662125110937463040 +1662125110988464128 +1662125111030465024 +1662125111078466048 +1662125111120466944 +1662125111162467840 +1662125111201468672 +1662125111243469568 +1662125111288470528 +1662125111330471424 +1662125111375472384 +1662125111414473216 +1662125111459474176 +1662125111501475072 +1662125111543475968 +1662125111585476864 +1662125111627477760 +1662125111672478720 +1662125111714479616 +1662125111759480576 +1662125111801481472 +1662125111843482368 +1662125111888483328 +1662125111930484224 +1662125111972485120 +1662125112017486080 +1662125112062487040 +1662125112107488000 +1662125112155489024 +1662125112197489920 +1662125112236490752 +1662125112278491648 +1662125112323492608 +1662125112368493568 +1662125112410494464 +1662125112452495360 +1662125112500496384 +1662125112539497216 +1662125112581498112 +1662125112623499008 +1662125112665499904 +1662125112704500736 +1662125112755501824 +1662125112794502656 +1662125112836503552 +1662125112881504512 +1662125112929505536 +1662125112977506560 +1662125113019507456 +1662125113064508416 +1662125113106509312 +1662125113151510272 +1662125113196511232 +1662125113238512128 +1662125113283513088 +1662125113322513920 +1662125113367514880 +1662125113415515904 +1662125113454516736 +1662125113496517632 +1662125113538518528 +1662125113583519488 +1662125113628520448 +1662125113670521344 +1662125113718522368 +1662125113763523328 +1662125113811524352 +1662125113853525248 +1662125113895526144 +1662125113940527104 +1662125113982528000 +1662125114021528832 +1662125114060529664 +1662125114099530496 +1662125114141531392 +1662125114183532288 +1662125114222533120 +1662125114267534080 +1662125114312535040 +1662125114357536000 +1662125114399536896 +1662125114441537792 +1662125114483538688 +1662125114531539712 +1662125114582540800 +1662125114624541696 +1662125114666542592 +1662125114708543488 +1662125114750544384 +1662125114792545280 +1662125114834546176 +1662125114876547072 +1662125114924548096 +1662125114969549056 +1662125115020550144 +1662125115065551104 +1662125115104551936 +1662125115146552832 +1662125115188553728 +1662125115233554688 +1662125115278555648 +1662125115323556608 +1662125115368557568 +1662125115410558464 +1662125115455559424 +1662125115497560320 +1662125115542561280 +1662125115581562112 +1662125115620562944 +1662125115662563840 +1662125115701564672 +1662125115746565632 +1662125115788566528 +1662125115833567488 +1662125115878568448 +1662125115923569408 +1662125115965570304 +1662125116007571200 +1662125116049572096 +1662125116094573056 +1662125116130573824 +1662125116175574784 +1662125116220575744 +1662125116268576768 +1662125116310577664 +1662125116349578496 +1662125116391579392 +1662125116436580352 +1662125116481581312 +1662125116526582272 +1662125116571583232 +1662125116607584000 +1662125116649584896 +1662125116691585792 +1662125116736586752 +1662125116781587712 +1662125116823588608 +1662125116862589440 +1662125116904590336 +1662125116943591168 +1662125116982592000 +1662125117027592960 +1662125117072593920 +1662125117117594880 +1662125117156595712 +1662125117201596672 +1662125117237597440 +1662125117276598272 +1662125117321599232 +1662125117363600128 +1662125117405601024 +1662125117447601920 +1662125117492602880 +1662125117537603840 +1662125117579604736 +1662125117618605568 +1662125117663606528 +1662125117705607424 +1662125117744608256 +1662125117789609216 +1662125117828610048 +1662125117870610944 +1662125117918611968 +1662125117963612928 +1662125118005613824 +1662125118047614720 +1662125118089615616 +1662125118131616512 +1662125118173617408 +1662125118215618304 +1662125118260619264 +1662125118299620096 +1662125118341620992 +1662125118386621952 +1662125118425622784 +1662125118470623744 +1662125118509624576 +1662125118554625536 +1662125118599626496 +1662125118641627392 +1662125118683628288 +1662125118725629184 +1662125118767630080 +1662125118809630976 +1662125118854631936 +1662125118896632832 +1662125118941633792 +1662125118980634624 +1662125119022635520 +1662125119070636544 +1662125119115637504 +1662125119154638336 +1662125119196639232 +1662125119238640128 +1662125119277640960 +1662125119322641920 +1662125119370642944 +1662125119415643904 +1662125119460644864 +1662125119505645824 +1662125119547646720 +1662125119580647424 +1662125119625648384 +1662125119670649344 +1662125119712650240 +1662125119754651136 +1662125119802652160 +1662125119844653056 +1662125119886653952 +1662125119928654848 +1662125119970655744 +1662125120012656640 +1662125120057657600 +1662125120102658560 +1662125120150659584 +1662125120195660544 +1662125120240661504 +1662125120282662400 +1662125120324663296 +1662125120369664256 +1662125120417665280 +1662125120459666176 +1662125120507667200 +1662125120555668224 +1662125120597669120 +1662125120639670016 +1662125120681670912 +1662125120723671808 +1662125120765672704 +1662125120804673536 +1662125120846674432 +1662125120885675264 +1662125120927676160 +1662125120969677056 +1662125121011677952 +1662125121053678848 +1662125121095679744 +1662125121137680640 +1662125121185681664 +1662125121230682624 +1662125121269683456 +1662125121311684352 +1662125121353685248 +1662125121398686208 +1662125121437687040 +1662125121488688128 +1662125121530689024 +1662125121575689984 +1662125121617690880 +1662125121662691840 +1662125121704692736 +1662125121749693696 +1662125121791694592 +1662125121833695488 +1662125121875696384 +1662125121920697344 +1662125121962698240 +1662125122007699200 +1662125122049700096 +1662125122091700992 +1662125122133701888 +1662125122175702784 +1662125122217703680 +1662125122259704576 +1662125122301705472 +1662125122340706304 +1662125122385707264 +1662125122430708224 +1662125122469709056 +1662125122511709952 +1662125122556710912 +1662125122601711872 +1662125122643712768 +1662125122685713664 +1662125122736714752 +1662125122778715648 +1662125122820716544 +1662125122868717568 +1662125122910718464 +1662125122952719360 +1662125122991720192 +1662125123033721088 +1662125123075721984 +1662125123120722944 +1662125123162723840 +1662125123201724672 +1662125123243725568 +1662125123285726464 +1662125123324727296 +1662125123366728192 +1662125123408729088 +1662125123453730048 +1662125123501731072 +1662125123543731968 +1662125123585732864 +1662125123627733760 +1662125123669734656 +1662125123717735680 +1662125123762736640 +1662125123804737536 +1662125123852738560 +1662125123891739392 +1662125123936740352 +1662125123975741184 +1662125124020742144 +1662125124059742976 +1662125124104743936 +1662125124146744832 +1662125124194745856 +1662125124239746816 +1662125124281747712 +1662125124329748736 +1662125124368749568 +1662125124410750464 +1662125124452751360 +1662125124494752256 +1662125124536753152 +1662125124578754048 +1662125124620754944 +1662125124665755904 +1662125124707756800 +1662125124746757632 +1662125124791758592 +1662125124833759488 +1662125124869760256 +1662125124911761152 +1662125124956762112 +1662125124998763008 +1662125125040763904 +1662125125085764864 +1662125125127765760 +1662125125172766720 +1662125125214767616 +1662125125262768640 +1662125125304769536 +1662125125346770432 +1662125125385771264 +1662125125427772160 +1662125125472773120 +1662125125514774016 +1662125125559774976 +1662125125601775872 +1662125125652776960 +1662125125700777984 +1662125125742778880 +1662125125790779904 +1662125125841780992 +1662125125883781888 +1662125125925782784 +1662125125976783872 +1662125126021784832 +1662125126066785792 +1662125126111786752 +1662125126153787648 +1662125126192788480 +1662125126231789312 +1662125126279790336 +1662125126321791232 +1662125126366792192 +1662125126408793088 +1662125126447793920 +1662125126495794944 +1662125126537795840 +1662125126582796800 +1662125126627797760 +1662125126669798656 +1662125126714799616 +1662125126753800448 +1662125126798801408 +1662125126831802112 +1662125126873803008 +1662125126915803904 +1662125126957804800 +1662125127002805760 +1662125127041806592 +1662125127089807616 +1662125127131808512 +1662125127170809344 +1662125127212810240 +1662125127254811136 +1662125127293811968 +1662125127335812864 +1662125127377813760 +1662125127419814656 +1662125127464815616 +1662125127503816448 +1662125127545817344 +1662125127584818176 +1662125127629819136 +1662125127677820160 +1662125127719821056 +1662125127761821952 +1662125127800822784 +1662125127842823680 +1662125127881824512 +1662125127926825472 +1662125127968826368 +1662125128007827200 +1662125128046828032 +1662125128088828928 +1662125128130829824 +1662125128175830784 +1662125128217831680 +1662125128259832576 +1662125128304833536 +1662125128340834304 +1662125128382835200 +1662125128424836096 +1662125128463836928 +1662125128508837888 +1662125128562839040 +1662125128610840064 +1662125128652840960 +1662125128697841920 +1662125128739842816 +1662125128781843712 +1662125128829844736 +1662125128871845632 +1662125128919846656 +1662125128958847488 +1662125129003848448 +1662125129045849344 +1662125129087850240 +1662125129126851072 +1662125129174852096 +1662125129219853056 +1662125129264854016 +1662125129306854912 +1662125129345855744 +1662125129390856704 +1662125129435857664 +1662125129480858624 +1662125129522859520 +1662125129567860480 +1662125129609861376 +1662125129651862272 +1662125129696863232 +1662125129738864128 +1662125129783865088 +1662125129825865984 +1662125129867866880 +1662125129912867840 +1662125129951868672 +1662125129993869568 +1662125130038870528 +1662125130083871488 +1662125130128872448 +1662125130167873280 +1662125130206874112 +1662125130248875008 +1662125130296876032 +1662125130338876928 +1662125130380877824 +1662125130422878720 +1662125130464879616 +1662125130506880512 +1662125130548881408 +1662125130593882368 +1662125130638883328 +1662125130680884224 +1662125130728885248 +1662125130767886080 +1662125130809886976 +1662125130854887936 +1662125130899888896 +1662125130941889792 +1662125130983890688 +1662125131025891584 +1662125131064892416 +1662125131109893376 +1662125131154894336 +1662125131196895232 +1662125131238896128 +1662125131283897088 +1662125131325897984 +1662125131367898880 +1662125131415899904 +1662125131457900800 +1662125131496901632 +1662125131541902592 +1662125131583903488 +1662125131625904384 +1662125131670905344 +1662125131712906240 +1662125131760907264 +1662125131805908224 +1662125131847909120 +1662125131892910080 +1662125131943911168 +1662125131988912128 +1662125132027912960 +1662125132066913792 +1662125132108914688 +1662125132153915648 +1662125132198916608 +1662125132243917568 +1662125132288918528 +1662125132330919424 +1662125132372920320 +1662125132417921280 +1662125132459922176 +1662125132504923136 +1662125132549924096 +1662125132594925056 +1662125132636925952 +1662125132675926784 +1662125132720927744 +1662125132759928576 +1662125132804929536 +1662125132849930496 +1662125132891931392 +1662125132933932288 +1662125132975933184 +1662125133020934144 +1662125133065935104 +1662125133107936000 +1662125133149936896 +1662125133191937792 +1662125133236938752 +1662125133278939648 +1662125133323940608 +1662125133365941504 +1662125133410942464 +1662125133452943360 +1662125133494944256 +1662125133536945152 +1662125133578946048 +1662125133626947072 +1662125133668947968 +1662125133710948864 +1662125133752949760 +1662125133791950592 +1662125133833951488 +1662125133878952448 +1662125133920953344 +1662125133962954240 +1662125134010955264 +1662125134055956224 +1662125134100957184 +1662125134148958208 +1662125134187959040 +1662125134229959936 +1662125134271960832 +1662125134313961728 +1662125134358962688 +1662125134403963648 +1662125134445964544 +1662125134490965504 +1662125134532966400 +1662125134577967360 +1662125134625968384 +1662125134670969344 +1662125134715970304 +1662125134757971200 +1662125134799972096 +1662125134847973120 +1662125134892974080 +1662125134937975040 +1662125134973975808 +1662125135018976768 +1662125135057977600 +1662125135102978560 +1662125135144979456 +1662125135192980480 +1662125135237981440 +1662125135279982336 +1662125135330983424 +1662125135378984448 +1662125135420985344 +1662125135465986304 +1662125135510987264 +1662125135549988096 +1662125135594989056 +1662125135639990016 +1662125135681990912 +1662125135726991872 +1662125135768992768 +1662125135807993600 +1662125135855994624 +1662125135903995648 +1662125135945996544 +1662125135987997440 +1662125136029998336 +1662125136071999232 +1662125136120000256 +1662125136165001216 +1662125136204002048 +1662125136243002880 +1662125136285003776 +1662125136330004736 +1662125136372005632 +1662125136414006528 +1662125136456007424 +1662125136501008384 +1662125136540009216 +1662125136585010176 +1662125136627011072 +1662125136663011840 +1662125136705012736 +1662125136750013696 +1662125136792014592 +1662125136834015488 +1662125136876016384 +1662125136921017344 +1662125136960018176 +1662125136999019008 +1662125137041019904 +1662125137083020800 +1662125137122021632 +1662125137164022528 +1662125137209023488 +1662125137251024384 +1662125137290025216 +1662125137329026048 +1662125137371026944 +1662125137416027904 +1662125137464028928 +1662125137509029888 +1662125137551030784 +1662125137593031680 +1662125137635032576 +1662125137677033472 +1662125137719034368 +1662125137770035456 +1662125137809036288 +1662125137851037184 +1662125137890038016 +1662125137932038912 +1662125137977039872 +1662125138016040704 +1662125138058041600 +1662125138100042496 +1662125138142043392 +1662125138181044224 +1662125138223045120 +1662125138268046080 +1662125138313047040 +1662125138358048000 +1662125138406049024 +1662125138457050112 +1662125138499051008 +1662125138547052032 +1662125138589052928 +1662125138634053888 +1662125138676054784 +1662125138721055744 +1662125138763056640 +1662125138811057664 +1662125138853058560 +1662125138895059456 +1662125138937060352 +1662125138979061248 +1662125139021062144 +1662125139063063040 +1662125139102063872 +1662125139144064768 +1662125139192065792 +1662125139237066752 +1662125139279067648 +1662125139318068480 +1662125139366069504 +1662125139408070400 +1662125139450071296 +1662125139492072192 +1662125139534073088 +1662125139585074176 +1662125139630075136 +1662125139675076096 +1662125139720077056 +1662125139762077952 +1662125139801078784 +1662125139843079680 +1662125139882080512 +1662125139924081408 +1662125139963082240 +1662125140005083136 +1662125140047084032 +1662125140089084928 +1662125140128085760 +1662125140173086720 +1662125140218087680 +1662125140263088640 +1662125140305089536 +1662125140347090432 +1662125140386091264 +1662125140428092160 +1662125140470093056 +1662125140518094080 +1662125140560094976 +1662125140602095872 +1662125140644096768 +1662125140689097728 +1662125140731098624 +1662125140779099648 +1662125140830100736 +1662125140872101632 +1662125140914102528 +1662125140959103488 +1662125141001104384 +1662125141040105216 +1662125141082106112 +1662125141124107008 +1662125141166107904 +1662125141211108864 +1662125141253109760 +1662125141298110720 +1662125141343111680 +1662125141382112512 +1662125141424113408 +1662125141466114304 +1662125141511115264 +1662125141553116160 +1662125141595117056 +1662125141640118016 +1662125141682118912 +1662125141724119808 +1662125141769120768 +1662125141817121792 +1662125141859122688 +1662125141904123648 +1662125141949124608 +1662125141994125568 +1662125142036126464 +1662125142075127296 +1662125142117128192 +1662125142159129088 +1662125142207130112 +1662125142252131072 +1662125142294131968 +1662125142336132864 +1662125142375133696 +1662125142420134656 +1662125142465135616 +1662125142507136512 +1662125142555137536 +1662125142600138496 +1662125142642139392 +1662125142681140224 +1662125142723141120 +1662125142765142016 +1662125142807142912 +1662125142849143808 +1662125142891144704 +1662125142936145664 +1662125142978146560 +1662125143026147584 +1662125143071148544 +1662125143113149440 +1662125143158150400 +1662125143197151232 +1662125143242152192 +1662125143290153216 +1662125143332154112 +1662125143377155072 +1662125143419155968 +1662125143473157120 +1662125143515158016 +1662125143560158976 +1662125143602159872 +1662125143641160704 +1662125143686161664 +1662125143725162496 +1662125143773163520 +1662125143818164480 +1662125143860165376 +1662125143911166464 +1662125143953167360 +1662125143992168192 +1662125144037169152 +1662125144085170176 +1662125144127171072 +1662125144172172032 +1662125144220173056 +1662125144268174080 +1662125144316175104 +1662125144355175936 +1662125144397176832 +1662125144442177792 +1662125144484178688 +1662125144526179584 +1662125144568180480 +1662125144610181376 +1662125144655182336 +1662125144703183360 +1662125144748184320 +1662125144793185280 +1662125144835186176 +1662125144883187200 +1662125144925188096 +1662125144970189056 +1662125145021190144 +1662125145072191232 +1662125145114192128 +1662125145156193024 +1662125145198193920 +1662125145240194816 +1662125145285195776 +1662125145333196800 +1662125145381197824 +1662125145426198784 +1662125145471199744 +1662125145513200640 +1662125145564201728 +1662125145600202496 +1662125145639203328 +1662125145684204288 +1662125145726205184 +1662125145762205952 +1662125145807206912 +1662125145849207808 +1662125145897208832 +1662125145939209728 +1662125145981210624 +1662125146029211648 +1662125146074212608 +1662125146119213568 +1662125146161214464 +1662125146203215360 +1662125146245216256 +1662125146290217216 +1662125146335218176 +1662125146380219136 +1662125146422220032 +1662125146464220928 +1662125146506221824 +1662125146545222656 +1662125146596223744 +1662125146638224640 +1662125146680225536 +1662125146722226432 +1662125146764227328 +1662125146809228288 +1662125146851229184 +1662125146893230080 +1662125146938231040 +1662125146977231872 +1662125147019232768 +1662125147061233664 +1662125147106234624 +1662125147151235584 +1662125147193236480 +1662125147235237376 +1662125147280238336 +1662125147325239296 +1662125147370240256 +1662125147415241216 +1662125147457242112 +1662125147499243008 +1662125147541243904 +1662125147583244800 +1662125147628245760 +1662125147673246720 +1662125147715247616 +1662125147757248512 +1662125147796249344 +1662125147841250304 +1662125147883251200 +1662125147931252224 +1662125147973253120 +1662125148012253952 +1662125148057254912 +1662125148099255808 +1662125148138256640 +1662125148186257664 +1662125148228258560 +1662125148270259456 +1662125148312260352 +1662125148354261248 +1662125148399262208 +1662125148441263104 +1662125148483264000 +1662125148528264960 +1662125148567265792 +1662125148618266880 +1662125148657267712 +1662125148702268672 +1662125148744269568 +1662125148786270464 +1662125148834271488 +1662125148879272448 +1662125148927273472 +1662125148975274496 +1662125149020275456 +1662125149062276352 +1662125149104277248 +1662125149146278144 +1662125149197279232 +1662125149242280192 +1662125149284281088 +1662125149329282048 +1662125149377283072 +1662125149419283968 +1662125149458284800 +1662125149494285568 +1662125149530286336 +1662125149572287232 +1662125149617288192 +1662125149659289088 +1662125149698289920 +1662125149743290880 +1662125149788291840 +1662125149830292736 +1662125149875293696 +1662125149920294656 +1662125149962295552 +1662125150007296512 +1662125150049297408 +1662125150091298304 +1662125150133299200 +1662125150184300288 +1662125150229301248 +1662125150271302144 +1662125150313303040 +1662125150358304000 +1662125150400304896 +1662125150445305856 +1662125150484306688 +1662125150526307584 +1662125150577308672 +1662125150622309632 +1662125150667310592 +1662125150709311488 +1662125150754312448 +1662125150796313344 +1662125150841314304 +1662125150883315200 +1662125150928316160 +1662125150973317120 +1662125151015318016 +1662125151054318848 +1662125151093319680 +1662125151135320576 +1662125151174321408 +1662125151213322240 +1662125151258323200 +1662125151300324096 +1662125151345325056 +1662125151393326080 +1662125151435326976 +1662125151477327872 +1662125151522328832 +1662125151561329664 +1662125151606330624 +1662125151651331584 +1662125151696332544 +1662125151738333440 +1662125151780334336 +1662125151825335296 +1662125151870336256 +1662125151912337152 +1662125151960338176 +1662125152002339072 +1662125152044339968 +1662125152086340864 +1662125152131341824 +1662125152173342720 +1662125152215343616 +1662125152254344448 +1662125152296345344 +1662125152344346368 +1662125152389347328 +1662125152428348160 +1662125152473349120 +1662125152518350080 +1662125152563351040 +1662125152611352064 +1662125152653352960 +1662125152698353920 +1662125152743354880 +1662125152782355712 +1662125152824356608 +1662125152869357568 +1662125152914358528 +1662125152956359424 +1662125152992360192 +1662125153031361024 +1662125153067361792 +1662125153109362688 +1662125153154363648 +1662125153199364608 +1662125153241365504 +1662125153283366400 +1662125153325367296 +1662125153367368192 +1662125153412369152 +1662125153454370048 +1662125153490370816 +1662125153535371776 +1662125153580372736 +1662125153622373632 +1662125153664374528 +1662125153706375424 +1662125153748376320 +1662125153790377216 +1662125153835378176 +1662125153874379008 +1662125153916379904 +1662125153958380800 +1662125154000381696 +1662125154045382656 +1662125154093383680 +1662125154135384576 +1662125154180385536 +1662125154228386560 +1662125154270387456 +1662125154312388352 +1662125154354389248 +1662125154402390272 +1662125154447391232 +1662125154492392192 +1662125154534393088 +1662125154576393984 +1662125154618394880 +1662125154660395776 +1662125154699396608 +1662125154741397504 +1662125154783398400 +1662125154831399424 +1662125154873400320 +1662125154915401216 +1662125154957402112 +1662125154996402944 +1662125155038403840 +1662125155080404736 +1662125155119405568 +1662125155167406592 +1662125155206407424 +1662125155245408256 +1662125155287409152 +1662125155332410112 +1662125155377411072 +1662125155419411968 +1662125155464412928 +1662125155503413760 +1662125155548414720 +1662125155593415680 +1662125155632416512 +1662125155671417344 +1662125155713418240 +1662125155755419136 +1662125155797420032 +1662125155842420992 +1662125155887421952 +1662125155929422848 +1662125155971423744 +1662125156013424640 +1662125156052425472 +1662125156094426368 +1662125156136427264 +1662125156181428224 +1662125156223429120 +1662125156265430016 +1662125156316431104 +1662125156355431936 +1662125156397432832 +1662125156436433664 +1662125156481434624 +1662125156523435520 +1662125156568436480 +1662125156610437376 +1662125156652438272 +1662125156697439232 +1662125156739440128 +1662125156778440960 +1662125156823441920 +1662125156865442816 +1662125156916443904 +1662125156958444800 +1662125157003445760 +1662125157051446784 +1662125157093447680 +1662125157138448640 +1662125157183449600 +1662125157228450560 +1662125157276451584 +1662125157321452544 +1662125157366453504 +1662125157414454528 +1662125157456455424 +1662125157498456320 +1662125157540457216 +1662125157582458112 +1662125157627459072 +1662125157672460032 +1662125157714460928 +1662125157759461888 +1662125157804462848 +1662125157846463744 +1662125157891464704 +1662125157933465600 +1662125157978466560 +1662125158026467584 +1662125158074468608 +1662125158116469504 +1662125158158470400 +1662125158200471296 +1662125158242472192 +1662125158284473088 +1662125158326473984 +1662125158368474880 +1662125158407475712 +1662125158449476608 +1662125158491477504 +1662125158536478464 +1662125158578479360 +1662125158626480384 +1662125158671481344 +1662125158713482240 +1662125158755483136 +1662125158800484096 +1662125158842484992 +1662125158890486016 +1662125158935486976 +1662125158980487936 +1662125159025488896 +1662125159067489792 +1662125159109490688 +1662125159151491584 +1662125159193492480 +1662125159235493376 +1662125159277494272 +1662125159319495168 +1662125159361496064 +1662125159406497024 +1662125159448497920 +1662125159490498816 +1662125159535499776 +1662125159583500800 +1662125159625501696 +1662125159667502592 +1662125159706503424 +1662125159742504192 +1662125159781505024 +1662125159823505920 +1662125159865506816 +1662125159913507840 +1662125159961508864 +1662125160003509760 +1662125160045510656 +1662125160090511616 +1662125160138512640 +1662125160180513536 +1662125160222514432 +1662125160261515264 +1662125160303516160 +1662125160348517120 +1662125160387517952 +1662125160432518912 +1662125160474519808 +1662125160519520768 +1662125160558521600 +1662125160597522432 +1662125160645523456 +1662125160687524352 +1662125160729525248 +1662125160771526144 +1662125160813527040 +1662125160855527936 +1662125160900528896 +1662125160942529792 +1662125160990530816 +1662125161038531840 +1662125161080532736 +1662125161128533760 +1662125161176534784 +1662125161218535680 +1662125161266536704 +1662125161314537728 +1662125161359538688 +1662125161401539584 +1662125161443540480 +1662125161491541504 +1662125161533542400 +1662125161578543360 +1662125161620544256 +1662125161662545152 +1662125161701545984 +1662125161749547008 +1662125161791547904 +1662125161833548800 +1662125161875549696 +1662125161923550720 +1662125161971551744 +1662125162013552640 +1662125162055553536 +1662125162100554496 +1662125162145555456 +1662125162187556352 +1662125162229557248 +1662125162271558144 +1662125162319559168 +1662125162355559936 +1662125162397560832 +1662125162442561792 +1662125162484562688 +1662125162532563712 +1662125162574564608 +1662125162616565504 +1662125162661566464 +1662125162703567360 +1662125162748568320 +1662125162793569280 +1662125162832570112 +1662125162877571072 +1662125162919571968 +1662125162961572864 +1662125163006573824 +1662125163048574720 +1662125163093575680 +1662125163138576640 +1662125163183577600 diff --git a/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt new file mode 100644 index 0000000000..7283c7fd50 --- /dev/null +++ b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt @@ -0,0 +1,2489 @@ +1662120285510217728 +1662120285552218624 +1662120285594219520 +1662120285636220416 +1662120285681221376 +1662120285723222272 +1662120285768223232 +1662120285810224128 +1662120285858225152 +1662120285897225984 +1662120285936226816 +1662120285981227776 +1662120286023228672 +1662120286065229568 +1662120286107230464 +1662120286149231360 +1662120286191232256 +1662120286233233152 +1662120286281234176 +1662120286323235072 +1662120286371236096 +1662120286413236992 +1662120286455237888 +1662120286497238784 +1662120286539239680 +1662120286581240576 +1662120286620241408 +1662120286662242304 +1662120286701243136 +1662120286740243968 +1662120286782244864 +1662120286827245824 +1662120286875246848 +1662120286920247808 +1662120286968248832 +1662120287010249728 +1662120287052250624 +1662120287097251584 +1662120287139252480 +1662120287181253376 +1662120287220254208 +1662120287265255168 +1662120287307256064 +1662120287352257024 +1662120287397257984 +1662120287436258816 +1662120287475259648 +1662120287517260544 +1662120287559261440 +1662120287601262336 +1662120287646263296 +1662120287688264192 +1662120287733265152 +1662120287772265984 +1662120287814266880 +1662120287862267904 +1662120287907268864 +1662120287952269824 +1662120288000270848 +1662120288039271680 +1662120288087272704 +1662120288135273728 +1662120288177274624 +1662120288225275648 +1662120288267276544 +1662120288309277440 +1662120288354278400 +1662120288396279296 +1662120288438280192 +1662120288483281152 +1662120288528282112 +1662120288576283136 +1662120288624284160 +1662120288666285056 +1662120288708285952 +1662120288747286784 +1662120288792287744 +1662120288834288640 +1662120288873289472 +1662120288918290432 +1662120288963291392 +1662120289008292352 +1662120289050293248 +1662120289092294144 +1662120289131294976 +1662120289176295936 +1662120289218296832 +1662120289260297728 +1662120289311298816 +1662120289356299776 +1662120289398300672 +1662120289440301568 +1662120289485302528 +1662120289527303424 +1662120289569304320 +1662120289608305152 +1662120289653306112 +1662120289695307008 +1662120289734307840 +1662120289773308672 +1662120289812309504 +1662120289854310400 +1662120289896311296 +1662120289938312192 +1662120289983313152 +1662120290025314048 +1662120290067314944 +1662120290115315968 +1662120290157316864 +1662120290202317824 +1662120290247318784 +1662120290292319744 +1662120290340320768 +1662120290385321728 +1662120290430322688 +1662120290478323712 +1662120290526324736 +1662120290568325632 +1662120290613326592 +1662120290652327424 +1662120290694328320 +1662120290730329088 +1662120290772329984 +1662120290814330880 +1662120290853331712 +1662120290898332672 +1662120290937333504 +1662120290979334400 +1662120291021335296 +1662120291060336128 +1662120291108337152 +1662120291150338048 +1662120291195339008 +1662120291240339968 +1662120291291341056 +1662120291336342016 +1662120291381342976 +1662120291423343872 +1662120291477345024 +1662120291519345920 +1662120291567346944 +1662120291606347776 +1662120291648348672 +1662120291690349568 +1662120291735350528 +1662120291777351424 +1662120291825352448 +1662120291870353408 +1662120291912354304 +1662120291954355200 +1662120291996356096 +1662120292041357056 +1662120292080357888 +1662120292119358720 +1662120292167359744 +1662120292209360640 +1662120292251361536 +1662120292293362432 +1662120292335363328 +1662120292377364224 +1662120292419365120 +1662120292470366208 +1662120292512367104 +1662120292560368128 +1662120292602369024 +1662120292647369984 +1662120292692370944 +1662120292734371840 +1662120292776372736 +1662120292818373632 +1662120292860374528 +1662120292902375424 +1662120292947376384 +1662120292989377280 +1662120293031378176 +1662120293076379136 +1662120293118380032 +1662120293160380928 +1662120293202381824 +1662120293244382720 +1662120293289383680 +1662120293331384576 +1662120293376385536 +1662120293418386432 +1662120293463387392 +1662120293505388288 +1662120293547389184 +1662120293592390144 +1662120293634391040 +1662120293679392000 +1662120293724392960 +1662120293766393856 +1662120293811394816 +1662120293856395776 +1662120293895396608 +1662120293940397568 +1662120293988398592 +1662120294033399552 +1662120294078400512 +1662120294123401472 +1662120294168402432 +1662120294213403392 +1662120294249404160 +1662120294291405056 +1662120294330405888 +1662120294372406784 +1662120294420407808 +1662120294462408704 +1662120294507409664 +1662120294546410496 +1662120294588411392 +1662120294633412352 +1662120294684413440 +1662120294729414400 +1662120294774415360 +1662120294816416256 +1662120294861417216 +1662120294903418112 +1662120294951419136 +1662120294996420096 +1662120295044421120 +1662120295083421952 +1662120295128422912 +1662120295170423808 +1662120295218424832 +1662120295263425792 +1662120295305426688 +1662120295347427584 +1662120295389428480 +1662120295434429440 +1662120295476430336 +1662120295521431296 +1662120295566432256 +1662120295605433088 +1662120295647433984 +1662120295692434944 +1662120295734435840 +1662120295776436736 +1662120295818437632 +1662120295866438656 +1662120295911439616 +1662120295953440512 +1662120295995441408 +1662120296037442304 +1662120296082443264 +1662120296130444288 +1662120296169445120 +1662120296208445952 +1662120296250446848 +1662120296295447808 +1662120296337448704 +1662120296379449600 +1662120296421450496 +1662120296457451264 +1662120296499452160 +1662120296541453056 +1662120296589454080 +1662120296637455104 +1662120296682456064 +1662120296724456960 +1662120296766457856 +1662120296808458752 +1662120296850459648 +1662120296892460544 +1662120296937461504 +1662120296979462400 +1662120297021463296 +1662120297066464256 +1662120297111465216 +1662120297153466112 +1662120297201467136 +1662120297246468096 +1662120297288468992 +1662120297327469824 +1662120297372470784 +1662120297414471680 +1662120297459472640 +1662120297504473600 +1662120297552474624 +1662120297597475584 +1662120297639476480 +1662120297684477440 +1662120297726478336 +1662120297765479168 +1662120297804480000 +1662120297843480832 +1662120297885481728 +1662120297927482624 +1662120297972483584 +1662120298005484288 +1662120298053485312 +1662120298095486208 +1662120298137487104 +1662120298179488000 +1662120298227489024 +1662120298269489920 +1662120298311490816 +1662120298350491648 +1662120298395492608 +1662120298446493696 +1662120298491494656 +1662120298533495552 +1662120298575496448 +1662120298617497344 +1662120298662498304 +1662120298713499392 +1662120298755500288 +1662120298800501248 +1662120298842502144 +1662120298884503040 +1662120298926503936 +1662120298968504832 +1662120299010505728 +1662120299052506624 +1662120299094507520 +1662120299136508416 +1662120299178509312 +1662120299220510208 +1662120299262511104 +1662120299307512064 +1662120299352513024 +1662120299391513856 +1662120299433514752 +1662120299481515776 +1662120299523516672 +1662120299568517632 +1662120299613518592 +1662120299658519552 +1662120299700520448 +1662120299742521344 +1662120299787522304 +1662120299832523264 +1662120299874524160 +1662120299916525056 +1662120299961526016 +1662120300006526976 +1662120300048527872 +1662120300084528640 +1662120300126529536 +1662120300171530496 +1662120300216531456 +1662120300261532416 +1662120300303533312 +1662120300348534272 +1662120300390535168 +1662120300432536064 +1662120300474536960 +1662120300516537856 +1662120300564538880 +1662120300609539840 +1662120300651540736 +1662120300693541632 +1662120300735542528 +1662120300777543424 +1662120300822544384 +1662120300864545280 +1662120300915546368 +1662120300960547328 +1662120301002548224 +1662120301044549120 +1662120301086550016 +1662120301128550912 +1662120301176551936 +1662120301221552896 +1662120301260553728 +1662120301308554752 +1662120301353555712 +1662120301401556736 +1662120301443557632 +1662120301485558528 +1662120301527559424 +1662120301572560384 +1662120301614561280 +1662120301662562304 +1662120301704563200 +1662120301746564096 +1662120301785564928 +1662120301827565824 +1662120301869566720 +1662120301911567616 +1662120301950568448 +1662120301995569408 +1662120302037570304 +1662120302085571328 +1662120302130572288 +1662120302175573248 +1662120302220574208 +1662120302265575168 +1662120302307576064 +1662120302346576896 +1662120302391577856 +1662120302439578880 +1662120302484579840 +1662120302532580864 +1662120302574581760 +1662120302616582656 +1662120302658583552 +1662120302697584384 +1662120302742585344 +1662120302787586304 +1662120302829587200 +1662120302871588096 +1662120302916589056 +1662120302958589952 +1662120303000590848 +1662120303051591936 +1662120303099592960 +1662120303141593856 +1662120303183594752 +1662120303231595776 +1662120303279596800 +1662120303321597696 +1662120303360598528 +1662120303399599360 +1662120303450600448 +1662120303495601408 +1662120303537602304 +1662120303576603136 +1662120303618604032 +1662120303657604864 +1662120303702605824 +1662120303750606848 +1662120303792607744 +1662120303837608704 +1662120303879609600 +1662120303930610688 +1662120303975611648 +1662120304017612544 +1662120304059613440 +1662120304104614400 +1662120304149615360 +1662120304191616256 +1662120304236617216 +1662120304278618112 +1662120304320619008 +1662120304362619904 +1662120304401620736 +1662120304443621632 +1662120304485622528 +1662120304530623488 +1662120304578624512 +1662120304623625472 +1662120304665626368 +1662120304710627328 +1662120304755628288 +1662120304800629248 +1662120304848630272 +1662120304893631232 +1662120304938632192 +1662120304980633088 +1662120305022633984 +1662120305067634944 +1662120305112635904 +1662120305148636672 +1662120305196637696 +1662120305235638528 +1662120305274639360 +1662120305319640320 +1662120305364641280 +1662120305403642112 +1662120305445643008 +1662120305490643968 +1662120305535644928 +1662120305577645824 +1662120305619646720 +1662120305664647680 +1662120305703648512 +1662120305745649408 +1662120305790650368 +1662120305838651392 +1662120305883652352 +1662120305928653312 +1662120305970654208 +1662120306012655104 +1662120306054656000 +1662120306102657024 +1662120306150658048 +1662120306192658944 +1662120306237659904 +1662120306282660864 +1662120306324661760 +1662120306369662720 +1662120306417663744 +1662120306462664704 +1662120306507665664 +1662120306549666560 +1662120306591667456 +1662120306633668352 +1662120306678669312 +1662120306723670272 +1662120306765671168 +1662120306810672128 +1662120306855673088 +1662120306897673984 +1662120306939674880 +1662120306978675712 +1662120307017676544 +1662120307065677568 +1662120307104678400 +1662120307149679360 +1662120307191680256 +1662120307236681216 +1662120307281682176 +1662120307323683072 +1662120307365683968 +1662120307407684864 +1662120307449685760 +1662120307491686656 +1662120307527687424 +1662120307572688384 +1662120307614689280 +1662120307656690176 +1662120307707691264 +1662120307752692224 +1662120307794693120 +1662120307836694016 +1662120307878694912 +1662120307923695872 +1662120307971696896 +1662120308016697856 +1662120308058698752 +1662120308100699648 +1662120308142700544 +1662120308181701376 +1662120308226702336 +1662120308271703296 +1662120308313704192 +1662120308355705088 +1662120308403706112 +1662120308451707136 +1662120308496708096 +1662120308538708992 +1662120308580709888 +1662120308622710784 +1662120308661711616 +1662120308709712640 +1662120308751713536 +1662120308790714368 +1662120308835715328 +1662120308880716288 +1662120308922717184 +1662120308964718080 +1662120309003718912 +1662120309045719808 +1662120309090720768 +1662120309135721728 +1662120309177722624 +1662120309216723456 +1662120309258724352 +1662120309300725248 +1662120309345726208 +1662120309390727168 +1662120309435728128 +1662120309474728960 +1662120309516729856 +1662120309561730816 +1662120309603731712 +1662120309645732608 +1662120309690733568 +1662120309729734400 +1662120309777735424 +1662120309819736320 +1662120309864737280 +1662120309915738368 +1662120309957739264 +1662120310002740224 +1662120310044741120 +1662120310092742144 +1662120310134743040 +1662120310179744000 +1662120310224744960 +1662120310266745856 +1662120310311746816 +1662120310353747712 +1662120310395748608 +1662120310440749568 +1662120310482750464 +1662120310527751424 +1662120310572752384 +1662120310611753216 +1662120310662754304 +1662120310704755200 +1662120310746756096 +1662120310788756992 +1662120310839758080 +1662120310881758976 +1662120310923759872 +1662120310971760896 +1662120311016761856 +1662120311061762816 +1662120311109763840 +1662120311151764736 +1662120311190765568 +1662120311241766656 +1662120311283767552 +1662120311325768448 +1662120311367769344 +1662120311412770304 +1662120311454771200 +1662120311505772288 +1662120311547773184 +1662120311592774144 +1662120311634775040 +1662120311676775936 +1662120311721776896 +1662120311763777792 +1662120311808778752 +1662120311850779648 +1662120311892780544 +1662120311937781504 +1662120311982782464 +1662120312027783424 +1662120312063784192 +1662120312108785152 +1662120312150786048 +1662120312195787008 +1662120312234787840 +1662120312279788800 +1662120312327789824 +1662120312369790720 +1662120312411791616 +1662120312453792512 +1662120312495793408 +1662120312540794368 +1662120312588795392 +1662120312636796416 +1662120312678797312 +1662120312723798272 +1662120312765799168 +1662120312804800000 +1662120312849800960 +1662120312894801920 +1662120312939802880 +1662120312981803776 +1662120313026804736 +1662120313068805632 +1662120313110806528 +1662120313152807424 +1662120313197808384 +1662120313242809344 +1662120313284810240 +1662120313326811136 +1662120313371812096 +1662120313413812992 +1662120313455813888 +1662120313497814784 +1662120313545815808 +1662120313584816640 +1662120313626817536 +1662120313668818432 +1662120313713819392 +1662120313755820288 +1662120313797821184 +1662120313839822080 +1662120313884823040 +1662120313929824000 +1662120313977825024 +1662120314031826176 +1662120314073827072 +1662120314115827968 +1662120314160828928 +1662120314202829824 +1662120314247830784 +1662120314295831808 +1662120314340832768 +1662120314379833600 +1662120314421834496 +1662120314466835456 +1662120314508836352 +1662120314553837312 +1662120314598838272 +1662120314637839104 +1662120314682840064 +1662120314724840960 +1662120314772841984 +1662120314811842816 +1662120314856843776 +1662120314898844672 +1662120314940845568 +1662120314988846592 +1662120315033847552 +1662120315078848512 +1662120315123849472 +1662120315168850432 +1662120315210851328 +1662120315252852224 +1662120315294853120 +1662120315345854208 +1662120315390855168 +1662120315435856128 +1662120315489857280 +1662120315537858304 +1662120315582859264 +1662120315630860288 +1662120315675861248 +1662120315717862144 +1662120315762863104 +1662120315807864064 +1662120315849864960 +1662120315891865856 +1662120315933866752 +1662120315975867648 +1662120316017868544 +1662120316062869504 +1662120316104870400 +1662120316149871360 +1662120316191872256 +1662120316230873088 +1662120316275874048 +1662120316317874944 +1662120316362875904 +1662120316404876800 +1662120316449877760 +1662120316494878720 +1662120316539879680 +1662120316581880576 +1662120316620881408 +1662120316665882368 +1662120316704883200 +1662120316746884096 +1662120316791885056 +1662120316836886016 +1662120316878886912 +1662120316917887744 +1662120316962888704 +1662120317001889536 +1662120317049890560 +1662120317100891648 +1662120317142892544 +1662120317187893504 +1662120317232894464 +1662120317277895424 +1662120317322896384 +1662120317367897344 +1662120317409898240 +1662120317454899200 +1662120317496900096 +1662120317544901120 +1662120317586902016 +1662120317628902912 +1662120317673903872 +1662120317715904768 +1662120317757905664 +1662120317802906624 +1662120317844907520 +1662120317886908416 +1662120317934909440 +1662120317976910336 +1662120318018911232 +1662120318060912128 +1662120318102913024 +1662120318147913984 +1662120318192914944 +1662120318231915776 +1662120318270916608 +1662120318315917568 +1662120318357918464 +1662120318399919360 +1662120318447920384 +1662120318492921344 +1662120318534922240 +1662120318576923136 +1662120318618924032 +1662120318663924992 +1662120318708925952 +1662120318753926912 +1662120318798927872 +1662120318843928832 +1662120318891929856 +1662120318936930816 +1662120318978931712 +1662120319017932544 +1662120319062933504 +1662120319104934400 +1662120319149935360 +1662120319191936256 +1662120319236937216 +1662120319278938112 +1662120319323939072 +1662120319365939968 +1662120319413940992 +1662120319455941888 +1662120319500942848 +1662120319542943744 +1662120319587944704 +1662120319632945664 +1662120319680946688 +1662120319725947648 +1662120319770948608 +1662120319812949504 +1662120319854950400 +1662120319899951360 +1662120319941952256 +1662120319986953216 +1662120320028954112 +1662120320073955072 +1662120320115955968 +1662120320160956928 +1662120320202957824 +1662120320247958784 +1662120320295959808 +1662120320340960768 +1662120320379961600 +1662120320424962560 +1662120320469963520 +1662120320511964416 +1662120320556965376 +1662120320601966336 +1662120320646967296 +1662120320688968192 +1662120320727969024 +1662120320769969920 +1662120320814970880 +1662120320862971904 +1662120320904972800 +1662120320946973696 +1662120320988974592 +1662120321033975552 +1662120321075976448 +1662120321120977408 +1662120321162978304 +1662120321210979328 +1662120321255980288 +1662120321306981376 +1662120321348982272 +1662120321393983232 +1662120321438984192 +1662120321477985024 +1662120321522985984 +1662120321561986816 +1662120321603987712 +1662120321651988736 +1662120321693989632 +1662120321732990464 +1662120321780991488 +1662120321822992384 +1662120321858993152 +1662120321900994048 +1662120321942994944 +1662120321987995904 +1662120322026996736 +1662120322068997632 +1662120322110998528 +1662120322149999360 +1662120322195000320 +1662120322237001216 +1662120322285002240 +1662120322330003200 +1662120322372004096 +1662120322417005056 +1662120322459005952 +1662120322501006848 +1662120322543007744 +1662120322585008640 +1662120322624009472 +1662120322666010368 +1662120322708011264 +1662120322750012160 +1662120322789012992 +1662120322828013824 +1662120322882014976 +1662120322924015872 +1662120322975016960 +1662120323014017792 +1662120323056018688 +1662120323101019648 +1662120323146020608 +1662120323185021440 +1662120323227022336 +1662120323272023296 +1662120323317024256 +1662120323359025152 +1662120323401026048 +1662120323443026944 +1662120323488027904 +1662120323530028800 +1662120323575029760 +1662120323620030720 +1662120323668031744 +1662120323710032640 +1662120323749033472 +1662120323794034432 +1662120323836035328 +1662120323875036160 +1662120323920037120 +1662120323959037952 +1662120324004038912 +1662120324046039808 +1662120324091040768 +1662120324139041792 +1662120324178042624 +1662120324223043584 +1662120324265044480 +1662120324304045312 +1662120324343046144 +1662120324385047040 +1662120324427047936 +1662120324469048832 +1662120324517049856 +1662120324559050752 +1662120324601051648 +1662120324640052480 +1662120324682053376 +1662120324724054272 +1662120324766055168 +1662120324808056064 +1662120324853057024 +1662120324901058048 +1662120324943058944 +1662120324988059904 +1662120325036060928 +1662120325078061824 +1662120325120062720 +1662120325159063552 +1662120325204064512 +1662120325255065600 +1662120325300066560 +1662120325342067456 +1662120325384068352 +1662120325429069312 +1662120325468070144 +1662120325510071040 +1662120325549071872 +1662120325603073024 +1662120325642073856 +1662120325687074816 +1662120325726075648 +1662120325768076544 +1662120325810077440 +1662120325852078336 +1662120325894079232 +1662120325939080192 +1662120325984081152 +1662120326026082048 +1662120326074083072 +1662120326119084032 +1662120326164084992 +1662120326209085952 +1662120326257086976 +1662120326302087936 +1662120326344088832 +1662120326386089728 +1662120326428090624 +1662120326470091520 +1662120326512092416 +1662120326554093312 +1662120326596094208 +1662120326638095104 +1662120326683096064 +1662120326725096960 +1662120326767097856 +1662120326809098752 +1662120326857099776 +1662120326902100736 +1662120326947101696 +1662120326995102720 +1662120327040103680 +1662120327088104704 +1662120327133105664 +1662120327175106560 +1662120327220107520 +1662120327268108544 +1662120327310109440 +1662120327355110400 +1662120327394111232 +1662120327436112128 +1662120327490113280 +1662120327532114176 +1662120327574115072 +1662120327619116032 +1662120327661116928 +1662120327706117888 +1662120327748118784 +1662120327793119744 +1662120327832120576 +1662120327874121472 +1662120327919122432 +1662120327964123392 +1662120328009124352 +1662120328054125312 +1662120328099126272 +1662120328144127232 +1662120328189128192 +1662120328231129088 +1662120328273129984 +1662120328312130816 +1662120328354131712 +1662120328396132608 +1662120328441133568 +1662120328486134528 +1662120328531135488 +1662120328573136384 +1662120328612137216 +1662120328660138240 +1662120328705139200 +1662120328747140096 +1662120328795141120 +1662120328837142016 +1662120328879142912 +1662120328921143808 +1662120328963144704 +1662120329005145600 +1662120329047146496 +1662120329089147392 +1662120329137148416 +1662120329182149376 +1662120329227150336 +1662120329272151296 +1662120329317152256 +1662120329362153216 +1662120329410154240 +1662120329455155200 +1662120329497156096 +1662120329536156928 +1662120329581157888 +1662120329623158784 +1662120329668159744 +1662120329713160704 +1662120329758161664 +1662120329800162560 +1662120329842163456 +1662120329884164352 +1662120329926165248 +1662120329971166208 +1662120330010167040 +1662120330052167936 +1662120330100168960 +1662120330145169920 +1662120330190170880 +1662120330235171840 +1662120330277172736 +1662120330316173568 +1662120330364174592 +1662120330406175488 +1662120330448176384 +1662120330487177216 +1662120330526178048 +1662120330571179008 +1662120330613179904 +1662120330658180864 +1662120330703181824 +1662120330748182784 +1662120330793183744 +1662120330838184704 +1662120330877185536 +1662120330928186624 +1662120330967187456 +1662120331006188288 +1662120331051189248 +1662120331090190080 +1662120331132190976 +1662120331174191872 +1662120331219192832 +1662120331261193728 +1662120331306194688 +1662120331354195712 +1662120331393196544 +1662120331435197440 +1662120331477198336 +1662120331513199104 +1662120331561200128 +1662120331609201152 +1662120331648201984 +1662120331690202880 +1662120331735203840 +1662120331780204800 +1662120331825205760 +1662120331864206592 +1662120331906207488 +1662120331951208448 +1662120331996209408 +1662120332038210304 +1662120332080211200 +1662120332125212160 +1662120332164212992 +1662120332206213888 +1662120332251214848 +1662120332293215744 +1662120332335216640 +1662120332374217472 +1662120332416218368 +1662120332458219264 +1662120332500220160 +1662120332545221120 +1662120332584221952 +1662120332629222912 +1662120332674223872 +1662120332719224832 +1662120332761225728 +1662120332806226688 +1662120332848227584 +1662120332890228480 +1662120332932229376 +1662120332974230272 +1662120333019231232 +1662120333064232192 +1662120333106233088 +1662120333154234112 +1662120333199235072 +1662120333238235904 +1662120333286236928 +1662120333328237824 +1662120333367238656 +1662120333409239552 +1662120333448240384 +1662120333490241280 +1662120333529242112 +1662120333571243008 +1662120333610243840 +1662120333649244672 +1662120333691245568 +1662120333736246528 +1662120333781247488 +1662120333826248448 +1662120333868249344 +1662120333913250304 +1662120333958251264 +1662120334003252224 +1662120334048253184 +1662120334090254080 +1662120334132254976 +1662120334171255808 +1662120334213256704 +1662120334258257664 +1662120334303258624 +1662120334348259584 +1662120334393260544 +1662120334438261504 +1662120334480262400 +1662120334525263360 +1662120334570264320 +1662120334612265216 +1662120334657266176 +1662120334702267136 +1662120334744268032 +1662120334795269120 +1662120334837270016 +1662120334882270976 +1662120334918271744 +1662120334960272640 +1662120335002273536 +1662120335047274496 +1662120335095275520 +1662120335137276416 +1662120335185277440 +1662120335230278400 +1662120335272279296 +1662120335314280192 +1662120335362281216 +1662120335404282112 +1662120335449283072 +1662120335485283840 +1662120335530284800 +1662120335572285696 +1662120335614286592 +1662120335656287488 +1662120335701288448 +1662120335746289408 +1662120335788290304 +1662120335833291264 +1662120335878292224 +1662120335923293184 +1662120335962294016 +1662120336010295040 +1662120336052295936 +1662120336088296704 +1662120336127297536 +1662120336172298496 +1662120336214299392 +1662120336250300160 +1662120336292301056 +1662120336334301952 +1662120336376302848 +1662120336427303936 +1662120336475304960 +1662120336517305856 +1662120336562306816 +1662120336601307648 +1662120336637308416 +1662120336679309312 +1662120336724310272 +1662120336763311104 +1662120336799311872 +1662120336838312704 +1662120336883313664 +1662120336922314496 +1662120336970315520 +1662120337015316480 +1662120337057317376 +1662120337102318336 +1662120337141319168 +1662120337186320128 +1662120337231321088 +1662120337276322048 +1662120337324323072 +1662120337369324032 +1662120337414324992 +1662120337459325952 +1662120337504326912 +1662120337546327808 +1662120337591328768 +1662120337636329728 +1662120337675330560 +1662120337711331328 +1662120337756332288 +1662120337801333248 +1662120337843334144 +1662120337882334976 +1662120337924335872 +1662120337969336832 +1662120338014337792 +1662120338059338752 +1662120338104339712 +1662120338146340608 +1662120338191341568 +1662120338233342464 +1662120338275343360 +1662120338323344384 +1662120338368345344 +1662120338416346368 +1662120338461347328 +1662120338503348224 +1662120338548349184 +1662120338590350080 +1662120338632350976 +1662120338674351872 +1662120338713352704 +1662120338752353536 +1662120338797354496 +1662120338842355456 +1662120338890356480 +1662120338932357376 +1662120338974358272 +1662120339016359168 +1662120339055360000 +1662120339100360960 +1662120339145361920 +1662120339190362880 +1662120339241363968 +1662120339286364928 +1662120339334365952 +1662120339382366976 +1662120339427367936 +1662120339466368768 +1662120339502369536 +1662120339544370432 +1662120339586371328 +1662120339625372160 +1662120339667373056 +1662120339706373888 +1662120339748374784 +1662120339793375744 +1662120339832376576 +1662120339874377472 +1662120339916378368 +1662120339958379264 +1662120340000380160 +1662120340042381056 +1662120340084381952 +1662120340126382848 +1662120340171383808 +1662120340216384768 +1662120340258385664 +1662120340306386688 +1662120340351387648 +1662120340393388544 +1662120340432389376 +1662120340480390400 +1662120340522391296 +1662120340564392192 +1662120340609393152 +1662120340651394048 +1662120340696395008 +1662120340738395904 +1662120340780396800 +1662120340825397760 +1662120340873398784 +1662120340912399616 +1662120340957400576 +1662120341002401536 +1662120341044402432 +1662120341089403392 +1662120341131404288 +1662120341176405248 +1662120341215406080 +1662120341263407104 +1662120341305408000 +1662120341344408832 +1662120341383409664 +1662120341428410624 +1662120341470411520 +1662120341512412416 +1662120341560413440 +1662120341605414400 +1662120341650415360 +1662120341692416256 +1662120341734417152 +1662120341773417984 +1662120341815418880 +1662120341857419776 +1662120341899420672 +1662120341938421504 +1662120341980422400 +1662120342025423360 +1662120342067424256 +1662120342112425216 +1662120342160426240 +1662120342202427136 +1662120342244428032 +1662120342286428928 +1662120342328429824 +1662120342373430784 +1662120342418431744 +1662120342466432768 +1662120342514433792 +1662120342556434688 +1662120342595435520 +1662120342637436416 +1662120342676437248 +1662120342718438144 +1662120342760439040 +1662120342799439872 +1662120342838440704 +1662120342877441536 +1662120342925442560 +1662120342964443392 +1662120343009444352 +1662120343048445184 +1662120343090446080 +1662120343135447040 +1662120343177447936 +1662120343222448896 +1662120343264449792 +1662120343309450752 +1662120343351451648 +1662120343402452736 +1662120343447453696 +1662120343489454592 +1662120343534455552 +1662120343579456512 +1662120343618457344 +1662120343663458304 +1662120343711459328 +1662120343762460416 +1662120343801461248 +1662120343849462272 +1662120343891463168 +1662120343936464128 +1662120343978465024 +1662120344023465984 +1662120344062466816 +1662120344107467776 +1662120344146468608 +1662120344188469504 +1662120344230470400 +1662120344275471360 +1662120344314472192 +1662120344356473088 +1662120344401474048 +1662120344443474944 +1662120344491475968 +1662120344533476864 +1662120344581477888 +1662120344620478720 +1662120344665479680 +1662120344713480704 +1662120344758481664 +1662120344800482560 +1662120344842483456 +1662120344884484352 +1662120344926485248 +1662120344968486144 +1662120345010487040 +1662120345055488000 +1662120345100488960 +1662120345145489920 +1662120345187490816 +1662120345229491712 +1662120345268492544 +1662120345310493440 +1662120345358494464 +1662120345397495296 +1662120345439496192 +1662120345484497152 +1662120345526498048 +1662120345568498944 +1662120345613499904 +1662120345655500800 +1662120345697501696 +1662120345736502528 +1662120345781503488 +1662120345826504448 +1662120345874505472 +1662120345919506432 +1662120345961507328 +1662120346006508288 +1662120346051509248 +1662120346096510208 +1662120346138511104 +1662120346180512000 +1662120346219512832 +1662120346264513792 +1662120346309514752 +1662120346354515712 +1662120346399516672 +1662120346441517568 +1662120346486518528 +1662120346528519424 +1662120346573520384 +1662120346618521344 +1662120346660522240 +1662120346702523136 +1662120346744524032 +1662120346786524928 +1662120346828525824 +1662120346876526848 +1662120346915527680 +1662120346957528576 +1662120347005529600 +1662120347047530496 +1662120347086531328 +1662120347128532224 +1662120347170533120 +1662120347212534016 +1662120347257534976 +1662120347299535872 +1662120347344536832 +1662120347389537792 +1662120347431538688 +1662120347476539648 +1662120347518540544 +1662120347560541440 +1662120347608542464 +1662120347653543424 +1662120347695544320 +1662120347737545216 +1662120347779546112 +1662120347824547072 +1662120347863547904 +1662120347905548800 +1662120347947549696 +1662120347986550528 +1662120348031551488 +1662120348073552384 +1662120348118553344 +1662120348157554176 +1662120348202555136 +1662120348244556032 +1662120348289556992 +1662120348331557888 +1662120348376558848 +1662120348421559808 +1662120348460560640 +1662120348502561536 +1662120348544562432 +1662120348589563392 +1662120348637564416 +1662120348679565312 +1662120348718566144 +1662120348760567040 +1662120348802567936 +1662120348841568768 +1662120348880569600 +1662120348922570496 +1662120348964571392 +1662120349009572352 +1662120349057573376 +1662120349102574336 +1662120349144575232 +1662120349186576128 +1662120349231577088 +1662120349273577984 +1662120349318578944 +1662120349363579904 +1662120349402580736 +1662120349444581632 +1662120349489582592 +1662120349531583488 +1662120349573584384 +1662120349612585216 +1662120349651586048 +1662120349696587008 +1662120349738587904 +1662120349780588800 +1662120349822589696 +1662120349864590592 +1662120349906591488 +1662120349948592384 +1662120349990593280 +1662120350032594176 +1662120350077595136 +1662120350122596096 +1662120350164596992 +1662120350209597952 +1662120350251598848 +1662120350293599744 +1662120350338600704 +1662120350380601600 +1662120350425602560 +1662120350467603456 +1662120350509604352 +1662120350551605248 +1662120350596606208 +1662120350638607104 +1662120350683608064 +1662120350728609024 +1662120350770609920 +1662120350812610816 +1662120350857611776 +1662120350902612736 +1662120350944613632 +1662120350986614528 +1662120351028615424 +1662120351067616256 +1662120351109617152 +1662120351151618048 +1662120351193618944 +1662120351235619840 +1662120351280620800 +1662120351325621760 +1662120351367622656 +1662120351409623552 +1662120351451624448 +1662120351496625408 +1662120351547626496 +1662120351589627392 +1662120351637628416 +1662120351679629312 +1662120351721630208 +1662120351766631168 +1662120351811632128 +1662120351856633088 +1662120351898633984 +1662120351940634880 +1662120351985635840 +1662120352027636736 +1662120352069637632 +1662120352111638528 +1662120352153639424 +1662120352195640320 +1662120352240641280 +1662120352285642240 +1662120352324643072 +1662120352366643968 +1662120352408644864 +1662120352447645696 +1662120352489646592 +1662120352534647552 +1662120352573648384 +1662120352621649408 +1662120352663650304 +1662120352705651200 +1662120352750652160 +1662120352795653120 +1662120352837654016 +1662120352882654976 +1662120352924655872 +1662120352972656896 +1662120353011657728 +1662120353053658624 +1662120353098659584 +1662120353143660544 +1662120353185661440 +1662120353227662336 +1662120353272663296 +1662120353320664320 +1662120353365665280 +1662120353410666240 +1662120353452667136 +1662120353494668032 +1662120353539668992 +1662120353581669888 +1662120353632670976 +1662120353683672064 +1662120353725672960 +1662120353767673856 +1662120353812674816 +1662120353854675712 +1662120353902676736 +1662120353947677696 +1662120353992678656 +1662120354037679616 +1662120354079680512 +1662120354121681408 +1662120354166682368 +1662120354208683264 +1662120354250684160 +1662120354292685056 +1662120354334685952 +1662120354376686848 +1662120354418687744 +1662120354463688704 +1662120354505689600 +1662120354547690496 +1662120354592691456 +1662120354637692416 +1662120354682693376 +1662120354727694336 +1662120354775695360 +1662120354817696256 +1662120354859697152 +1662120354901698048 +1662120354940698880 +1662120354982699776 +1662120355024700672 +1662120355066701568 +1662120355114702592 +1662120355162703616 +1662120355210704640 +1662120355249705472 +1662120355297706496 +1662120355336707328 +1662120355378708224 +1662120355420709120 +1662120355459709952 +1662120355504710912 +1662120355555712000 +1662120355600712960 +1662120355648713984 +1662120355690714880 +1662120355732715776 +1662120355777716736 +1662120355819717632 +1662120355861718528 +1662120355903719424 +1662120355945720320 +1662120355987721216 +1662120356029722112 +1662120356077723136 +1662120356122724096 +1662120356161724928 +1662120356203725824 +1662120356245726720 +1662120356290727680 +1662120356338728704 +1662120356383729664 +1662120356428730624 +1662120356470731520 +1662120356518732544 +1662120356560733440 +1662120356605734400 +1662120356647735296 +1662120356689736192 +1662120356731737088 +1662120356773737984 +1662120356815738880 +1662120356857739776 +1662120356896740608 +1662120356944741632 +1662120356986742528 +1662120357025743360 +1662120357070744320 +1662120357109745152 +1662120357154746112 +1662120357196747008 +1662120357241747968 +1662120357277748736 +1662120357319749632 +1662120357361750528 +1662120357406751488 +1662120357454752512 +1662120357499753472 +1662120357541754368 +1662120357586755328 +1662120357625756160 +1662120357664756992 +1662120357712758016 +1662120357754758912 +1662120357793759744 +1662120357835760640 +1662120357880761600 +1662120357925762560 +1662120357973763584 +1662120358015764480 +1662120358060765440 +1662120358102766336 +1662120358147767296 +1662120358195768320 +1662120358237769216 +1662120358285770240 +1662120358327771136 +1662120358375772160 +1662120358417773056 +1662120358459773952 +1662120358501774848 +1662120358543775744 +1662120358591776768 +1662120358636777728 +1662120358678778624 +1662120358726779648 +1662120358771780608 +1662120358813781504 +1662120358852782336 +1662120358894783232 +1662120358933784064 +1662120358975784960 +1662120359020785920 +1662120359065786880 +1662120359107787776 +1662120359158788864 +1662120359200789760 +1662120359242790656 +1662120359284791552 +1662120359326792448 +1662120359368793344 +1662120359407794176 +1662120359452795136 +1662120359494796032 +1662120359539796992 +1662120359581797888 +1662120359623798784 +1662120359671799808 +1662120359713800704 +1662120359755801600 +1662120359803802624 +1662120359845803520 +1662120359887804416 +1662120359926805248 +1662120359971806208 +1662120360013807104 +1662120360064808192 +1662120360106809088 +1662120360148809984 +1662120360190810880 +1662120360232811776 +1662120360274812672 +1662120360316813568 +1662120360361814528 +1662120360403815424 +1662120360445816320 +1662120360487817216 +1662120360529818112 +1662120360571819008 +1662120360613819904 +1662120360658820864 +1662120360703821824 +1662120360748822784 +1662120360787823616 +1662120360829824512 +1662120360877825536 +1662120360919826432 +1662120360964827392 +1662120361009828352 +1662120361054829312 +1662120361105830400 +1662120361150831360 +1662120361189832192 +1662120361231833088 +1662120361276834048 +1662120361318834944 +1662120361360835840 +1662120361408836864 +1662120361450837760 +1662120361489838592 +1662120361531839488 +1662120361573840384 +1662120361615841280 +1662120361660842240 +1662120361702843136 +1662120361747844096 +1662120361786844928 +1662120361831845888 +1662120361876846848 +1662120361918847744 +1662120361963848704 +1662120362008849664 +1662120362053850624 +1662120362092851456 +1662120362137852416 +1662120362179853312 +1662120362224854272 +1662120362266855168 +1662120362308856064 +1662120362347856896 +1662120362389857792 +1662120362428858624 +1662120362470859520 +1662120362515860480 +1662120362554861312 +1662120362596862208 +1662120362641863168 +1662120362680864000 +1662120362725864960 +1662120362767865856 +1662120362815866880 +1662120362857867776 +1662120362905868800 +1662120362947869696 +1662120362995870720 +1662120363037871616 +1662120363082872576 +1662120363124873472 +1662120363166874368 +1662120363208875264 +1662120363247876096 +1662120363289876992 +1662120363331877888 +1662120363373878784 +1662120363415879680 +1662120363454880512 +1662120363499881472 +1662120363544882432 +1662120363589883392 +1662120363634884352 +1662120363676885248 +1662120363718886144 +1662120363760887040 +1662120363802887936 +1662120363847888896 +1662120363886889728 +1662120363928890624 +1662120363973891584 +1662120364018892544 +1662120364060893440 +1662120364102894336 +1662120364147895296 +1662120364192896256 +1662120364231897088 +1662120364273897984 +1662120364315898880 +1662120364360899840 +1662120364405900800 +1662120364447901696 +1662120364489902592 +1662120364531903488 +1662120364573904384 +1662120364618905344 +1662120364666906368 +1662120364708907264 +1662120364756908288 +1662120364798909184 +1662120364843910144 +1662120364888911104 +1662120364930912000 +1662120364975912960 +1662120365020913920 +1662120365065914880 +1662120365110915840 +1662120365158916864 +1662120365200917760 +1662120365242918656 +1662120365284919552 +1662120365323920384 +1662120365365921280 +1662120365407922176 +1662120365449923072 +1662120365488923904 +1662120365527924736 +1662120365566925568 +1662120365611926528 +1662120365653927424 +1662120365698928384 +1662120365743929344 +1662120365788930304 +1662120365830931200 +1662120365872932096 +1662120365917933056 +1662120365959933952 +1662120365998934784 +1662120366040935680 +1662120366082936576 +1662120366124937472 +1662120366166938368 +1662120366211939328 +1662120366253940224 +1662120366301941248 +1662120366343942144 +1662120366397943296 +1662120366442944256 +1662120366484945152 +1662120366529946112 +1662120366574947072 +1662120366619948032 +1662120366661948928 +1662120366706949888 +1662120366748950784 +1662120366790951680 +1662120366835952640 +1662120366874953472 +1662120366916954368 +1662120366955955200 +1662120366994956032 +1662120367039956992 +1662120367081957888 +1662120367126958848 +1662120367168959744 +1662120367210960640 +1662120367249961472 +1662120367294962432 +1662120367336963328 +1662120367375964160 +1662120367420965120 +1662120367465966080 +1662120367507966976 +1662120367546967808 +1662120367591968768 +1662120367636969728 +1662120367675970560 +1662120367714971392 +1662120367759972352 +1662120367801973248 +1662120367846974208 +1662120367888975104 +1662120367933976064 +1662120367975976960 +1662120368020977920 +1662120368065978880 +1662120368110979840 +1662120368152980736 +1662120368194981632 +1662120368236982528 +1662120368275983360 +1662120368320984320 +1662120368359985152 +1662120368404986112 +1662120368446987008 +1662120368485987840 +1662120368530988800 +1662120368575989760 +1662120368617990656 +1662120368662991616 +1662120368704992512 +1662120368746993408 +1662120368791994368 +1662120368833995264 +1662120368875996160 +1662120368920997120 +1662120368965998080 +1662120369010999040 +1662120369056000000 +1662120369101000960 +1662120369146001920 +1662120369188002816 +1662120369230003712 +1662120369272004608 +1662120369317005568 +1662120369359006464 +1662120369404007424 +1662120369449008384 +1662120369500009472 +1662120369542010368 +1662120369584011264 +1662120369623012096 +1662120369665012992 +1662120369704013824 +1662120369749014784 +1662120369794015744 +1662120369836016640 +1662120369878017536 +1662120369923018496 +1662120369965019392 +1662120370007020288 +1662120370046021120 +1662120370088022016 +1662120370130022912 +1662120370175023872 +1662120370217024768 +1662120370259025664 +1662120370298026496 +1662120370340027392 +1662120370385028352 +1662120370427029248 +1662120370469030144 +1662120370511031040 +1662120370556032000 +1662120370604033024 +1662120370652034048 +1662120370697035008 +1662120370739035904 +1662120370781036800 +1662120370826037760 +1662120370877038848 +1662120370919039744 +1662120370961040640 +1662120371000041472 +1662120371045042432 +1662120371087043328 +1662120371126044160 +1662120371162044928 +1662120371207045888 +1662120371252046848 +1662120371294047744 +1662120371336048640 +1662120371381049600 +1662120371423050496 +1662120371468051456 +1662120371510052352 +1662120371552053248 +1662120371597054208 +1662120371642055168 +1662120371690056192 +1662120371735057152 +1662120371786058240 +1662120371828059136 +1662120371867059968 +1662120371912060928 +1662120371960061952 +1662120372005062912 +1662120372053063936 +1662120372098064896 +1662120372143065856 +1662120372185066752 +1662120372227067648 +1662120372272068608 +1662120372317069568 +1662120372362070528 +1662120372407071488 +1662120372452072448 +1662120372494073344 +1662120372536074240 +1662120372578075136 +1662120372623076096 +1662120372668077056 +1662120372713078016 +1662120372755078912 +1662120372800079872 +1662120372839080704 +1662120372881081600 +1662120372923082496 +1662120372968083456 +1662120373016084480 +1662120373055085312 +1662120373097086208 +1662120373139087104 +1662120373178087936 +1662120373220088832 +1662120373262089728 +1662120373307090688 +1662120373355091712 +1662120373394092544 +1662120373436093440 +1662120373481094400 +1662120373523095296 +1662120373565096192 +1662120373604097024 +1662120373652098048 +1662120373697099008 +1662120373748100096 +1662120373790100992 +1662120373832101888 +1662120373874102784 +1662120373919103744 +1662120373961104640 +1662120374000105472 +1662120374045106432 +1662120374090107392 +1662120374138108416 +1662120374183109376 +1662120374225110272 +1662120374270111232 +1662120374312112128 +1662120374354113024 +1662120374396113920 +1662120374438114816 +1662120374480115712 +1662120374525116672 +1662120374564117504 +1662120374609118464 +1662120374651119360 +1662120374699120384 +1662120374741121280 +1662120374786122240 +1662120374831123200 +1662120374873124096 +1662120374918125056 +1662120374966126080 +1662120375008126976 +1662120375056128000 +1662120375101128960 +1662120375146129920 +1662120375188130816 +1662120375236131840 +1662120375278132736 +1662120375323133696 +1662120375365134592 +1662120375413135616 +1662120375455136512 +1662120375497137408 +1662120375539138304 +1662120375581139200 +1662120375626140160 +1662120375668141056 +1662120375707141888 +1662120375752142848 +1662120375794143744 +1662120375839144704 +1662120375884145664 +1662120375929146624 +1662120375968147456 +1662120376010148352 +1662120376052149248 +1662120376094150144 +1662120376136151040 +1662120376175151872 +1662120376226152960 +1662120376268153856 +1662120376310154752 +1662120376355155712 +1662120376394156544 +1662120376436157440 +1662120376481158400 +1662120376523159296 +1662120376562160128 +1662120376604161024 +1662120376646161920 +1662120376688162816 +1662120376730163712 +1662120376775164672 +1662120376817165568 +1662120376859166464 +1662120376907167488 +1662120376952168448 +1662120376991169280 +1662120377036170240 +1662120377081171200 +1662120377123172096 +1662120377165172992 +1662120377204173824 +1662120377246174720 +1662120377288175616 +1662120377330176512 +1662120377372177408 +1662120377414178304 +1662120377456179200 +1662120377495180032 +1662120377537180928 +1662120377579181824 +1662120377621182720 +1662120377666183680 +1662120377711184640 +1662120377759185664 +1662120377801186560 +1662120377843187456 +1662120377882188288 +1662120377927189248 +1662120377966190080 +1662120378011191040 +1662120378053191936 +1662120378098192896 +1662120378140193792 +1662120378185194752 +1662120378224195584 +1662120378266196480 +1662120378308197376 +1662120378350198272 +1662120378392199168 +1662120378440200192 +1662120378482201088 +1662120378527202048 +1662120378569202944 +1662120378611203840 +1662120378656204800 +1662120378701205760 +1662120378746206720 +1662120378791207680 +1662120378833208576 +1662120378875209472 +1662120378917210368 +1662120378959211264 +1662120378998212096 +1662120379040212992 +1662120379082213888 +1662120379121214720 +1662120379160215552 +1662120379202216448 +1662120379247217408 +1662120379289218304 +1662120379331219200 +1662120379373220096 +1662120379418221056 +1662120379460221952 +1662120379505222912 +1662120379547223808 +1662120379604225024 +1662120379652226048 +1662120379691226880 +1662120379733227776 +1662120379775228672 +1662120379820229632 +1662120379868230656 +1662120379913231616 +1662120379955232512 +1662120379997233408 +1662120380042234368 +1662120380078235136 +1662120380123236096 +1662120380165236992 +1662120380216238080 +1662120380258238976 +1662120380300239872 +1662120380339240704 +1662120380384241664 +1662120380426242560 +1662120380468243456 +1662120380513244416 +1662120380564245504 +1662120380609246464 +1662120380654247424 +1662120380693248256 +1662120380735249152 +1662120380777250048 +1662120380816250880 +1662120380858251776 +1662120380906252800 +1662120380954253824 +1662120380999254784 +1662120381041255680 +1662120381083256576 +1662120381128257536 +1662120381170258432 +1662120381212259328 +1662120381251260160 +1662120381293261056 +1662120381335261952 +1662120381377262848 +1662120381428263936 +1662120381473264896 +1662120381512265728 +1662120381557266688 +1662120381599267584 +1662120381641268480 +1662120381686269440 +1662120381734270464 +1662120381776271360 +1662120381815272192 +1662120381857273088 +1662120381902274048 +1662120381950275072 +1662120381995276032 +1662120382037276928 +1662120382082277888 +1662120382127278848 +1662120382169279744 +1662120382214280704 +1662120382256281600 +1662120382301282560 +1662120382343283456 +1662120382385284352 +1662120382424285184 +1662120382463286016 +1662120382508286976 +1662120382547287808 +1662120382589288704 +1662120382631289600 +1662120382676290560 +1662120382721291520 +1662120382763292416 +1662120382808293376 +1662120382850294272 +1662120382898295296 +1662120382937296128 +1662120382976296960 +1662120383018297856 +1662120383063298816 +1662120383105299712 +1662120383147300608 +1662120383192301568 +1662120383234302464 +1662120383279303424 +1662120383321304320 +1662120383366305280 +1662120383417306368 +1662120383462307328 +1662120383504308224 +1662120383552309248 +1662120383594310144 +1662120383636311040 +1662120383678311936 +1662120383720312832 +1662120383768313856 +1662120383813314816 +1662120383858315776 +1662120383903316736 +1662120383945317632 +1662120383987318528 +1662120384032319488 +1662120384071320320 +1662120384113321216 +1662120384155322112 +1662120384200323072 +1662120384242323968 +1662120384287324928 +1662120384329325824 +1662120384371326720 +1662120384413327616 +1662120384455328512 +1662120384500329472 +1662120384542330368 +1662120384587331328 +1662120384632332288 +1662120384674333184 +1662120384719334144 +1662120384761335040 +1662120384803335936 +1662120384845336832 +1662120384890337792 +1662120384935338752 +1662120384974339584 +1662120385025340672 +1662120385070341632 +1662120385112342528 +1662120385160343552 +1662120385202344448 +1662120385241345280 +1662120385283346176 +1662120385325347072 +1662120385370348032 +1662120385418349056 +1662120385463350016 +1662120385514351104 +1662120385556352000 +1662120385598352896 +1662120385637353728 +1662120385679354624 +1662120385721355520 +1662120385766356480 +1662120385805357312 +1662120385847358208 +1662120385889359104 +1662120385934360064 +1662120385976360960 +1662120386021361920 +1662120386066362880 +1662120386108363776 +1662120386147364608 +1662120386186365440 +1662120386231366400 +1662120386270367232 +1662120386315368192 +1662120386360369152 +1662120386405370112 +1662120386447371008 +1662120386486371840 +1662120386531372800 +1662120386576373760 +1662120386615374592 +1662120386660375552 +1662120386699376384 +1662120386738377216 +1662120386783378176 +1662120386822379008 +1662120386870380032 +1662120386912380928 +1662120386951381760 +1662120386993382656 +1662120387032383488 +1662120387083384576 +1662120387122385408 +1662120387164386304 +1662120387206387200 +1662120387248388096 +1662120387293389056 +1662120387335389952 +1662120387371390720 +1662120387416391680 +1662120387461392640 +1662120387503393536 +1662120387548394496 +1662120387590395392 +1662120387629396224 +1662120387668397056 +1662120387713398016 +1662120387755398912 +1662120387800399872 +1662120387842400768 +1662120387887401728 +1662120387929402624 +1662120387971403520 +1662120388016404480 +1662120388055405312 +1662120388097406208 +1662120388142407168 +1662120388184408064 +1662120388223408896 +1662120388265409792 +1662120388304410624 +1662120388346411520 +1662120388388412416 +1662120388430413312 +1662120388472414208 +1662120388520415232 +1662120388565416192 +1662120388607417088 +1662120388649417984 +1662120388688418816 +1662120388733419776 +1662120388778420736 +1662120388823421696 +1662120388862422528 +1662120388904423424 +1662120388946424320 +1662120388991425280 +1662120389036426240 +1662120389078427136 +1662120389123428096 +1662120389165428992 +1662120389204429824 +1662120389252430848 +1662120389291431680 +1662120389333432576 +1662120389375433472 +1662120389414434304 +1662120389456435200 +1662120389498436096 +1662120389540436992 +1662120389585437952 +1662120389627438848 +1662120389669439744 +1662120389711440640 +1662120389756441600 +1662120389798442496 +1662120389846443520 +1662120389888444416 +1662120389933445376 +1662120389972446208 +1662120390014447104 +1662120390056448000 +1662120390101448960 +1662120390143449856 +1662120390185450752 +1662120390233451776 +1662120390278452736 +1662120390323453696 +1662120390365454592 +1662120390410455552 +1662120390455456512 +1662120390497457408 +1662120390533458176 +1662120390575459072 +1662120390617459968 +1662120390659460864 +1662120390704461824 +1662120390749462784 +1662120390791463680 +1662120390836464640 +1662120390878465536 +1662120390923466496 +1662120390974467584 +1662120391013468416 +1662120391055469312 +1662120391097470208 +1662120391145471232 +1662120391187472128 +1662120391229473024 +1662120391271473920 +1662120391319474944 +1662120391358475776 +1662120391403476736 +1662120391445477632 +1662120391487478528 +1662120391529479424 +1662120391571480320 +1662120391613481216 +1662120391655482112 +1662120391700483072 +1662120391739483904 +1662120391784484864 +1662120391835485952 +1662120391883486976 +1662120391925487872 +1662120391967488768 +1662120392012489728 +1662120392057490688 +1662120392099491584 +1662120392144492544 +1662120392186493440 +1662120392231494400 +1662120392273495296 +1662120392312496128 +1662120392357497088 +1662120392399497984 +1662120392444498944 +1662120392492499968 +1662120392543501056 +1662120392585501952 +1662120392630502912 +1662120392669503744 +1662120392711504640 +1662120392753505536 +1662120392801506560 +1662120392846507520 +1662120392891508480 +1662120392933509376 +1662120392981510400 +1662120393026511360 +1662120393068512256 +1662120393113513216 +1662120393158514176 +1662120393200515072 diff --git a/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_track0.txt b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_track0.txt new file mode 100644 index 0000000000..d40335079d --- /dev/null +++ b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_track0.txt @@ -0,0 +1,2847 @@ +1661868173547958016 +1661868173589958912 +1661868173628959744 +1661868173676960768 +1661868173715961600 +1661868173760962560 +1661868173802963456 +1661868173844964352 +1661868173886965248 +1661868173931966208 +1661868173973967104 +1661868174021968128 +1661868174063969024 +1661868174105969920 +1661868174147970816 +1661868174183971584 +1661868174225972480 +1661868174264973312 +1661868174306974208 +1661868174354975232 +1661868174399976192 +1661868174441977088 +1661868174483977984 +1661868174525978880 +1661868174564979712 +1661868174603980544 +1661868174645981440 +1661868174693982464 +1661868174735983360 +1661868174780984320 +1661868174828985344 +1661868174870986240 +1661868174912987136 +1661868174960988160 +1661868175002989056 +1661868175044989952 +1661868175086990848 +1661868175128991744 +1661868175170992640 +1661868175209993472 +1661868175251994368 +1661868175302995456 +1661868175341996288 +1661868175383997184 +1661868175425998080 +1661868175470999040 +1661868175509999872 +1661868175549000704 +1661868175591001600 +1661868175639002624 +1661868175681003520 +1661868175723004416 +1661868175765005312 +1661868175810006272 +1661868175849007104 +1661868175897008128 +1661868175939009024 +1661868175981009920 +1661868176029010944 +1661868176071011840 +1661868176113012736 +1661868176152013568 +1661868176197014528 +1661868176242015488 +1661868176284016384 +1661868176323017216 +1661868176368018176 +1661868176410019072 +1661868176452019968 +1661868176497020928 +1661868176536021760 +1661868176578022656 +1661868176617023488 +1661868176659024384 +1661868176701025280 +1661868176743026176 +1661868176785027072 +1661868176824027904 +1661868176869028864 +1661868176914029824 +1661868176953030656 +1661868176992031488 +1661868177034032384 +1661868177076033280 +1661868177118034176 +1661868177163035136 +1661868177208036096 +1661868177244036864 +1661868177283037696 +1661868177325038592 +1661868177367039488 +1661868177409040384 +1661868177451041280 +1661868177493042176 +1661868177535043072 +1661868177580044032 +1661868177625044992 +1661868177670045952 +1661868177712046848 +1661868177748047616 +1661868177793048576 +1661868177838049536 +1661868177877050368 +1661868177916051200 +1661868177958052096 +1661868178003053056 +1661868178048054016 +1661868178090054912 +1661868178132055808 +1661868178171056640 +1661868178207057408 +1661868178249058304 +1661868178297059328 +1661868178339060224 +1661868178384061184 +1661868178426062080 +1661868178468062976 +1661868178510063872 +1661868178546064640 +1661868178588065536 +1661868178630066432 +1661868178669067264 +1661868178711068160 +1661868178759069184 +1661868178804070144 +1661868178846071040 +1661868178888071936 +1661868178930072832 +1661868178972073728 +1661868179014074624 +1661868179059075584 +1661868179107076608 +1661868179152077568 +1661868179191078400 +1661868179233079296 +1661868179278080256 +1661868179320081152 +1661868179362082048 +1661868179407083008 +1661868179452083968 +1661868179494084864 +1661868179539085824 +1661868179581086720 +1661868179623087616 +1661868179665088512 +1661868179713089536 +1661868179758090496 +1661868179803091456 +1661868179845092352 +1661868179887093248 +1661868179926094080 +1661868179968094976 +1661868180010095872 +1661868180049096704 +1661868180088097536 +1661868180130098432 +1661868180175099392 +1661868180217100288 +1661868180256101120 +1661868180298102016 +1661868180340102912 +1661868180385103872 +1661868180427104768 +1661868180466105600 +1661868180508106496 +1661868180550107392 +1661868180589108224 +1661868180628109056 +1661868180670109952 +1661868180715110912 +1661868180760111872 +1661868180802112768 +1661868180844113664 +1661868180886114560 +1661868180922115328 +1661868180967116288 +1661868181009117184 +1661868181051118080 +1661868181090118912 +1661868181132119808 +1661868181174120704 +1661868181216121600 +1661868181258122496 +1661868181303123456 +1661868181348124416 +1661868181387125248 +1661868181432126208 +1661868181474127104 +1661868181516128000 +1661868181558128896 +1661868181597129728 +1661868181636130560 +1661868181678131456 +1661868181720132352 +1661868181762133248 +1661868181804134144 +1661868181846135040 +1661868181885135872 +1661868181927136768 +1661868181966137600 +1661868182008138496 +1661868182050139392 +1661868182095140352 +1661868182140141312 +1661868182182142208 +1661868182221143040 +1661868182263143936 +1661868182302144768 +1661868182344145664 +1661868182386146560 +1661868182428147456 +1661868182464148224 +1661868182506149120 +1661868182551150080 +1661868182590150912 +1661868182635151872 +1661868182677152768 +1661868182716153600 +1661868182758154496 +1661868182800155392 +1661868182839156224 +1661868182884157184 +1661868182926158080 +1661868182971159040 +1661868183010159872 +1661868183049160704 +1661868183091161600 +1661868183130162432 +1661868183172163328 +1661868183214164224 +1661868183256165120 +1661868183298166016 +1661868183340166912 +1661868183382167808 +1661868183427168768 +1661868183469169664 +1661868183511170560 +1661868183550171392 +1661868183595172352 +1661868183637173248 +1661868183679174144 +1661868183718174976 +1661868183769176064 +1661868183811176960 +1661868183850177792 +1661868183892178688 +1661868183931179520 +1661868183973180416 +1661868184018181376 +1661868184060182272 +1661868184102183168 +1661868184147184128 +1661868184192185088 +1661868184240186112 +1661868184282187008 +1661868184324187904 +1661868184366188800 +1661868184411189760 +1661868184447190528 +1661868184486191360 +1661868184528192256 +1661868184573193216 +1661868184618194176 +1661868184660195072 +1661868184705196032 +1661868184747196928 +1661868184786197760 +1661868184831198720 +1661868184873199616 +1661868184921200640 +1661868184960201472 +1661868185005202432 +1661868185047203328 +1661868185086204160 +1661868185125204992 +1661868185170205952 +1661868185215206912 +1661868185257207808 +1661868185299208704 +1661868185341209600 +1661868185383210496 +1661868185422211328 +1661868185464212224 +1661868185506213120 +1661868185545213952 +1661868185590214912 +1661868185632215808 +1661868185671216640 +1661868185707217408 +1661868185752218368 +1661868185794219264 +1661868185839220224 +1661868185875220992 +1661868185914221824 +1661868185962222848 +1661868186004223744 +1661868186046224640 +1661868186091225600 +1661868186130226432 +1661868186175227392 +1661868186220228352 +1661868186262229248 +1661868186307230208 +1661868186349231104 +1661868186391232000 +1661868186433232896 +1661868186478233856 +1661868186520234752 +1661868186562235648 +1661868186601236480 +1661868186643237376 +1661868186679238144 +1661868186718238976 +1661868186760239872 +1661868186805240832 +1661868186844241664 +1661868186883242496 +1661868186925243392 +1661868186964244224 +1661868187006245120 +1661868187048246016 +1661868187090246912 +1661868187129247744 +1661868187174248704 +1661868187216249600 +1661868187255250432 +1661868187297251328 +1661868187339252224 +1661868187381253120 +1661868187423254016 +1661868187465254912 +1661868187507255808 +1661868187549256704 +1661868187597257728 +1661868187639258624 +1661868187681259520 +1661868187726260480 +1661868187768261376 +1661868187807262208 +1661868187846263040 +1661868187888263936 +1661868187930264832 +1661868187978265856 +1661868188020266752 +1661868188062267648 +1661868188101268480 +1661868188143269376 +1661868188185270272 +1661868188224271104 +1661868188263271936 +1661868188302272768 +1661868188341273600 +1661868188380274432 +1661868188419275264 +1661868188464276224 +1661868188509277184 +1661868188551278080 +1661868188596279040 +1661868188641280000 +1661868188686280960 +1661868188728281856 +1661868188776282880 +1661868188824283904 +1661868188869284864 +1661868188911285760 +1661868188950286592 +1661868188992287488 +1661868189034288384 +1661868189079289344 +1661868189121290240 +1661868189163291136 +1661868189205292032 +1661868189247292928 +1661868189292293888 +1661868189328294656 +1661868189370295552 +1661868189412296448 +1661868189457297408 +1661868189502298368 +1661868189541299200 +1661868189580300032 +1661868189616300800 +1661868189661301760 +1661868189703302656 +1661868189742303488 +1661868189784304384 +1661868189832305408 +1661868189871306240 +1661868189913307136 +1661868189949307904 +1661868189988308736 +1661868190030309632 +1661868190072310528 +1661868190114311424 +1661868190156312320 +1661868190195313152 +1661868190237314048 +1661868190276314880 +1661868190321315840 +1661868190363316736 +1661868190405317632 +1661868190441318400 +1661868190486319360 +1661868190528320256 +1661868190570321152 +1661868190609321984 +1661868190654322944 +1661868190699323904 +1661868190741324800 +1661868190780325632 +1661868190822326528 +1661868190864327424 +1661868190906328320 +1661868190945329152 +1661868190990330112 +1661868191041331200 +1661868191086332160 +1661868191128333056 +1661868191170333952 +1661868191212334848 +1661868191254335744 +1661868191296336640 +1661868191338337536 +1661868191377338368 +1661868191425339392 +1661868191464340224 +1661868191509341184 +1661868191554342144 +1661868191596343040 +1661868191638343936 +1661868191683344896 +1661868191722345728 +1661868191776346880 +1661868191818347776 +1661868191857348608 +1661868191902349568 +1661868191941350400 +1661868191983351296 +1661868192028352256 +1661868192070353152 +1661868192112354048 +1661868192151354880 +1661868192193355776 +1661868192235356672 +1661868192277357568 +1661868192319358464 +1661868192361359360 +1661868192400360192 +1661868192442361088 +1661868192484361984 +1661868192526362880 +1661868192568363776 +1661868192613364736 +1661868192655365632 +1661868192700366592 +1661868192739367424 +1661868192781368320 +1661868192823369216 +1661868192862370048 +1661868192907371008 +1661868192946371840 +1661868192988372736 +1661868193027373568 +1661868193066374400 +1661868193105375232 +1661868193147376128 +1661868193192377088 +1661868193234377984 +1661868193276378880 +1661868193318379776 +1661868193354380544 +1661868193396381440 +1661868193441382400 +1661868193489383424 +1661868193531384320 +1661868193570385152 +1661868193609385984 +1661868193651386880 +1661868193693387776 +1661868193735388672 +1661868193789389824 +1661868193828390656 +1661868193870391552 +1661868193909392384 +1661868193951393280 +1661868193993394176 +1661868194038395136 +1661868194074395904 +1661868194119396864 +1661868194161397760 +1661868194203398656 +1661868194245399552 +1661868194287400448 +1661868194329401344 +1661868194371402240 +1661868194413403136 +1661868194455404032 +1661868194497404928 +1661868194539405824 +1661868194581406720 +1661868194620407552 +1661868194662408448 +1661868194707409408 +1661868194752410368 +1661868194791411200 +1661868194830412032 +1661868194869412864 +1661868194914413824 +1661868194956414720 +1661868194998415616 +1661868195040416512 +1661868195079417344 +1661868195121418240 +1661868195163419136 +1661868195205420032 +1661868195244420864 +1661868195286421760 +1661868195331422720 +1661868195376423680 +1661868195418424576 +1661868195460425472 +1661868195508426496 +1661868195550427392 +1661868195592428288 +1661868195640429312 +1661868195682430208 +1661868195724431104 +1661868195769432064 +1661868195811432960 +1661868195853433856 +1661868195895434752 +1661868195931435520 +1661868195973436416 +1661868196015437312 +1661868196060438272 +1661868196102439168 +1661868196147440128 +1661868196195441152 +1661868196237442048 +1661868196285443072 +1661868196330444032 +1661868196375444992 +1661868196414445824 +1661868196453446656 +1661868196495447552 +1661868196537448448 +1661868196579449344 +1661868196624450304 +1661868196666451200 +1661868196711452160 +1661868196747452928 +1661868196789453824 +1661868196831454720 +1661868196873455616 +1661868196921456640 +1661868196969457664 +1661868197020458752 +1661868197059459584 +1661868197098460416 +1661868197140461312 +1661868197182462208 +1661868197221463040 +1661868197263463936 +1661868197302464768 +1661868197344465664 +1661868197386466560 +1661868197428467456 +1661868197470468352 +1661868197509469184 +1661868197554470144 +1661868197593470976 +1661868197635471872 +1661868197677472768 +1661868197716473600 +1661868197758474496 +1661868197800475392 +1661868197848476416 +1661868197890477312 +1661868197932478208 +1661868197971479040 +1661868198010479872 +1661868198052480768 +1661868198100481792 +1661868198139482624 +1661868198181483520 +1661868198220484352 +1661868198262485248 +1661868198304486144 +1661868198349487104 +1661868198394488064 +1661868198439489024 +1661868198481489920 +1661868198523490816 +1661868198559491584 +1661868198604492544 +1661868198646493440 +1661868198685494272 +1661868198730495232 +1661868198775496192 +1661868198817497088 +1661868198862498048 +1661868198904498944 +1661868198946499840 +1661868198988500736 +1661868199030501632 +1661868199072502528 +1661868199114503424 +1661868199156504320 +1661868199198505216 +1661868199243506176 +1661868199285507072 +1661868199333508096 +1661868199375508992 +1661868199420509952 +1661868199462510848 +1661868199504511744 +1661868199546512640 +1661868199588513536 +1661868199630514432 +1661868199672515328 +1661868199714516224 +1661868199753517056 +1661868199795517952 +1661868199834518784 +1661868199876519680 +1661868199915520512 +1661868199954521344 +1661868199996522240 +1661868200038523136 +1661868200080524032 +1661868200119524864 +1661868200158525696 +1661868200200526592 +1661868200242527488 +1661868200284528384 +1661868200329529344 +1661868200365530112 +1661868200410531072 +1661868200452531968 +1661868200491532800 +1661868200533533696 +1661868200572534528 +1661868200614535424 +1661868200662536448 +1661868200710537472 +1661868200755538432 +1661868200797539328 +1661868200836540160 +1661868200872540928 +1661868200914541824 +1661868200956542720 +1661868200998543616 +1661868201037544448 +1661868201076545280 +1661868201118546176 +1661868201154546944 +1661868201193547776 +1661868201235548672 +1661868201280549632 +1661868201319550464 +1661868201364551424 +1661868201406552320 +1661868201451553280 +1661868201493554176 +1661868201532555008 +1661868201574555904 +1661868201616556800 +1661868201658557696 +1661868201700558592 +1661868201739559424 +1661868201778560256 +1661868201820561152 +1661868201862562048 +1661868201913563136 +1661868201955564032 +1661868202000564992 +1661868202042565888 +1661868202084566784 +1661868202129567744 +1661868202168568576 +1661868202210569472 +1661868202252570368 +1661868202288571136 +1661868202330572032 +1661868202372572928 +1661868202414573824 +1661868202462574848 +1661868202504575744 +1661868202546576640 +1661868202588577536 +1661868202630578432 +1661868202675579392 +1661868202717580288 +1661868202756581120 +1661868202801582080 +1661868202846583040 +1661868202885583872 +1661868202927584768 +1661868202972585728 +1661868203011586560 +1661868203056587520 +1661868203101588480 +1661868203140589312 +1661868203182590208 +1661868203230591232 +1661868203272592128 +1661868203314593024 +1661868203359593984 +1661868203401594880 +1661868203443595776 +1661868203485596672 +1661868203527597568 +1661868203569598464 +1661868203611599360 +1661868203653600256 +1661868203695601152 +1661868203737602048 +1661868203779602944 +1661868203824603904 +1661868203863604736 +1661868203905605632 +1661868203947606528 +1661868203989607424 +1661868204034608384 +1661868204079609344 +1661868204121610240 +1661868204163611136 +1661868204205612032 +1661868204247612928 +1661868204289613824 +1661868204328614656 +1661868204367615488 +1661868204400616192 +1661868204442617088 +1661868204490618112 +1661868204532619008 +1661868204574619904 +1661868204616620800 +1661868204658621696 +1661868204697622528 +1661868204733623296 +1661868204775624192 +1661868204820625152 +1661868204856625920 +1661868204898626816 +1661868204943627776 +1661868204988628736 +1661868205033629696 +1661868205075630592 +1661868205114631424 +1661868205156632320 +1661868205204633344 +1661868205249634304 +1661868205288635136 +1661868205330636032 +1661868205372636928 +1661868205414637824 +1661868205456638720 +1661868205498639616 +1661868205537640448 +1661868205579641344 +1661868205621642240 +1661868205654642944 +1661868205696643840 +1661868205738644736 +1661868205789645824 +1661868205828646656 +1661868205870647552 +1661868205915648512 +1661868205960649472 +1661868206002650368 +1661868206044651264 +1661868206083652096 +1661868206125652992 +1661868206170653952 +1661868206212654848 +1661868206254655744 +1661868206299656704 +1661868206341657600 +1661868206380658432 +1661868206422659328 +1661868206467660288 +1661868206509661184 +1661868206548662016 +1661868206590662912 +1661868206638663936 +1661868206677664768 +1661868206722665728 +1661868206767666688 +1661868206809667584 +1661868206851668480 +1661868206890669312 +1661868206932670208 +1661868206971671040 +1661868207013671936 +1661868207055672832 +1661868207097673728 +1661868207139674624 +1661868207187675648 +1661868207229676544 +1661868207271677440 +1661868207313678336 +1661868207355679232 +1661868207397680128 +1661868207442681088 +1661868207487682048 +1661868207526682880 +1661868207568683776 +1661868207613684736 +1661868207658685696 +1661868207700686592 +1661868207742687488 +1661868207790688512 +1661868207829689344 +1661868207868690176 +1661868207913691136 +1661868207955692032 +1661868207997692928 +1661868208039693824 +1661868208084694784 +1661868208132695808 +1661868208177696768 +1661868208216697600 +1661868208255698432 +1661868208297699328 +1661868208339700224 +1661868208375700992 +1661868208417701888 +1661868208459702784 +1661868208501703680 +1661868208549704704 +1661868208591705600 +1661868208630706432 +1661868208672707328 +1661868208714708224 +1661868208756709120 +1661868208795709952 +1661868208831710720 +1661868208876711680 +1661868208918712576 +1661868208960713472 +1661868209002714368 +1661868209047715328 +1661868209089716224 +1661868209131717120 +1661868209173718016 +1661868209218718976 +1661868209260719872 +1661868209299720704 +1661868209341721600 +1661868209386722560 +1661868209434723584 +1661868209476724480 +1661868209518725376 +1661868209563726336 +1661868209608727296 +1661868209647728128 +1661868209686728960 +1661868209731729920 +1661868209773730816 +1661868209809731584 +1661868209851732480 +1661868209899733504 +1661868209941734400 +1661868209980735232 +1661868210022736128 +1661868210067737088 +1661868210109737984 +1661868210148738816 +1661868210187739648 +1661868210226740480 +1661868210268741376 +1661868210310742272 +1661868210349743104 +1661868210391744000 +1661868210430744832 +1661868210472745728 +1661868210514746624 +1661868210556747520 +1661868210601748480 +1661868210640749312 +1661868210682750208 +1661868210724751104 +1661868210766752000 +1661868210811752960 +1661868210856753920 +1661868210898754816 +1661868210937755648 +1661868210979756544 +1661868211021757440 +1661868211063758336 +1661868211102759168 +1661868211150760192 +1661868211195761152 +1661868211237762048 +1661868211273762816 +1661868211315763712 +1661868211357764608 +1661868211396765440 +1661868211441766400 +1661868211480767232 +1661868211522768128 +1661868211567769088 +1661868211606769920 +1661868211648770816 +1661868211687771648 +1661868211729772544 +1661868211771773440 +1661868211813774336 +1661868211861775360 +1661868211906776320 +1661868211948777216 +1661868211993778176 +1661868212041779200 +1661868212083780096 +1661868212131781120 +1661868212173782016 +1661868212215782912 +1661868212257783808 +1661868212302784768 +1661868212347785728 +1661868212386786560 +1661868212431787520 +1661868212473788416 +1661868212515789312 +1661868212557790208 +1661868212599791104 +1661868212641792000 +1661868212683792896 +1661868212725793792 +1661868212767794688 +1661868212809795584 +1661868212851796480 +1661868212893797376 +1661868212935798272 +1661868212971799040 +1661868213016800000 +1661868213055800832 +1661868213094801664 +1661868213139802624 +1661868213178803456 +1661868213220804352 +1661868213259805184 +1661868213307806208 +1661868213343806976 +1661868213391808000 +1661868213430808832 +1661868213475809792 +1661868213523810816 +1661868213568811776 +1661868213610812672 +1661868213649813504 +1661868213691814400 +1661868213733815296 +1661868213772816128 +1661868213814817024 +1661868213850817792 +1661868213892818688 +1661868213937819648 +1661868213979820544 +1661868214015821312 +1661868214060822272 +1661868214099823104 +1661868214141824000 +1661868214180824832 +1661868214222825728 +1661868214264826624 +1661868214306827520 +1661868214351828480 +1661868214393829376 +1661868214432830208 +1661868214471831040 +1661868214513831936 +1661868214555832832 +1661868214594833664 +1661868214636834560 +1661868214678835456 +1661868214720836352 +1661868214762837248 +1661868214807838208 +1661868214849839104 +1661868214885839872 +1661868214927840768 +1661868214972841728 +1661868215014842624 +1661868215059843584 +1661868215101844480 +1661868215140845312 +1661868215188846336 +1661868215230847232 +1661868215278848256 +1661868215320849152 +1661868215362850048 +1661868215401850880 +1661868215443851776 +1661868215488852736 +1661868215530853632 +1661868215569854464 +1661868215611855360 +1661868215650856192 +1661868215692857088 +1661868215734857984 +1661868215776858880 +1661868215815859712 +1661868215860860672 +1661868215902861568 +1661868215944862464 +1661868215986863360 +1661868216034864384 +1661868216076865280 +1661868216121866240 +1661868216163867136 +1661868216202867968 +1661868216250868992 +1661868216295869952 +1661868216337870848 +1661868216385871872 +1661868216427872768 +1661868216475873792 +1661868216520874752 +1661868216562875648 +1661868216607876608 +1661868216649877504 +1661868216700878592 +1661868216742879488 +1661868216784880384 +1661868216823881216 +1661868216865882112 +1661868216913883136 +1661868216952883968 +1661868216991884800 +1661868217033885696 +1661868217075886592 +1661868217117887488 +1661868217162888448 +1661868217198889216 +1661868217240890112 +1661868217282891008 +1661868217321891840 +1661868217363892736 +1661868217405893632 +1661868217447894528 +1661868217489895424 +1661868217534896384 +1661868217576897280 +1661868217618898176 +1661868217666899200 +1661868217711900160 +1661868217753901056 +1661868217795901952 +1661868217837902848 +1661868217879903744 +1661868217921904640 +1661868217963905536 +1661868218005906432 +1661868218047907328 +1661868218092908288 +1661868218134909184 +1661868218182910208 +1661868218224911104 +1661868218266912000 +1661868218305912832 +1661868218350913792 +1661868218392914688 +1661868218437915648 +1661868218479916544 +1661868218521917440 +1661868218563918336 +1661868218605919232 +1661868218644920064 +1661868218686920960 +1661868218728921856 +1661868218770922752 +1661868218815923712 +1661868218857924608 +1661868218896925440 +1661868218944926464 +1661868218986927360 +1661868219028928256 +1661868219073929216 +1661868219115930112 +1661868219154930944 +1661868219202931968 +1661868219247932928 +1661868219295933952 +1661868219343934976 +1661868219385935872 +1661868219430936832 +1661868219469937664 +1661868219511938560 +1661868219553939456 +1661868219595940352 +1661868219637941248 +1661868219676942080 +1661868219715942912 +1661868219757943808 +1661868219796944640 +1661868219841945600 +1661868219883946496 +1661868219925947392 +1661868219967948288 +1661868220006949120 +1661868220045949952 +1661868220087950848 +1661868220129951744 +1661868220174952704 +1661868220213953536 +1661868220252954368 +1661868220291955200 +1661868220333956096 +1661868220375956992 +1661868220420957952 +1661868220462958848 +1661868220504959744 +1661868220549960704 +1661868220594961664 +1661868220636962560 +1661868220678963456 +1661868220717964288 +1661868220762965248 +1661868220804966144 +1661868220855967232 +1661868220897968128 +1661868220942969088 +1661868220984969984 +1661868221026970880 +1661868221068971776 +1661868221107972608 +1661868221146973440 +1661868221185974272 +1661868221224975104 +1661868221269976064 +1661868221311976960 +1661868221350977792 +1661868221395978752 +1661868221440979712 +1661868221479980544 +1661868221518981376 +1661868221560982272 +1661868221602983168 +1661868221647984128 +1661868221686984960 +1661868221731985920 +1661868221779986944 +1661868221821987840 +1661868221866988800 +1661868221908989696 +1661868221947990528 +1661868221995991552 +1661868222034992384 +1661868222076993280 +1661868222121994240 +1661868222166995200 +1661868222211996160 +1661868222253997056 +1661868222292997888 +1661868222331998720 +1661868222373999616 +1661868222416000512 +1661868222458001408 +1661868222500002304 +1661868222548003328 +1661868222584004096 +1661868222626004992 +1661868222671005952 +1661868222713006848 +1661868222764007936 +1661868222806008832 +1661868222848009728 +1661868222890010624 +1661868222932011520 +1661868222974012416 +1661868223022013440 +1661868223070014464 +1661868223109015296 +1661868223151016192 +1661868223190017024 +1661868223241018112 +1661868223283019008 +1661868223328019968 +1661868223367020800 +1661868223409021696 +1661868223457022720 +1661868223499023616 +1661868223541024512 +1661868223583025408 +1661868223625026304 +1661868223670027264 +1661868223709028096 +1661868223751028992 +1661868223793029888 +1661868223841030912 +1661868223883031808 +1661868223925032704 +1661868223967033600 +1661868224006034432 +1661868224045035264 +1661868224087036160 +1661868224129037056 +1661868224168037888 +1661868224207038720 +1661868224261039872 +1661868224300040704 +1661868224342041600 +1661868224384042496 +1661868224432043520 +1661868224474044416 +1661868224519045376 +1661868224561046272 +1661868224603047168 +1661868224645048064 +1661868224687048960 +1661868224732049920 +1661868224774050816 +1661868224816051712 +1661868224855052544 +1661868224897053440 +1661868224939054336 +1661868224981055232 +1661868225023056128 +1661868225074057216 +1661868225116058112 +1661868225161059072 +1661868225203059968 +1661868225248060928 +1661868225290061824 +1661868225338062848 +1661868225380063744 +1661868225422064640 +1661868225467065600 +1661868225509066496 +1661868225545067264 +1661868225590068224 +1661868225638069248 +1661868225686070272 +1661868225728071168 +1661868225770072064 +1661868225818073088 +1661868225860073984 +1661868225902074880 +1661868225944075776 +1661868225992076800 +1661868226034077696 +1661868226076078592 +1661868226118079488 +1661868226160080384 +1661868226199081216 +1661868226241082112 +1661868226289083136 +1661868226334084096 +1661868226376084992 +1661868226418085888 +1661868226454086656 +1661868226496087552 +1661868226535088384 +1661868226586089472 +1661868226628090368 +1661868226670091264 +1661868226709092096 +1661868226751092992 +1661868226799094016 +1661868226838094848 +1661868226883095808 +1661868226925096704 +1661868226967097600 +1661868227012098560 +1661868227054099456 +1661868227093100288 +1661868227141101312 +1661868227186102272 +1661868227225103104 +1661868227270104064 +1661868227312104960 +1661868227354105856 +1661868227396106752 +1661868227441107712 +1661868227483108608 +1661868227525109504 +1661868227567110400 +1661868227609111296 +1661868227651112192 +1661868227690113024 +1661868227732113920 +1661868227774114816 +1661868227819115776 +1661868227867116800 +1661868227912117760 +1661868227954118656 +1661868227996119552 +1661868228038120448 +1661868228086121472 +1661868228134122496 +1661868228179123456 +1661868228221124352 +1661868228263125248 +1661868228305126144 +1661868228353127168 +1661868228395128064 +1661868228434128896 +1661868228479129856 +1661868228524130816 +1661868228569131776 +1661868228611132672 +1661868228656133632 +1661868228698134528 +1661868228737135360 +1661868228776136192 +1661868228824137216 +1661868228866138112 +1661868228908139008 +1661868228950139904 +1661868228992140800 +1661868229031141632 +1661868229073142528 +1661868229124143616 +1661868229166144512 +1661868229208145408 +1661868229253146368 +1661868229295147264 +1661868229337148160 +1661868229379149056 +1661868229421149952 +1661868229463150848 +1661868229508151808 +1661868229547152640 +1661868229592153600 +1661868229634154496 +1661868229673155328 +1661868229715156224 +1661868229757157120 +1661868229796157952 +1661868229838158848 +1661868229880159744 +1661868229931160832 +1661868229973161728 +1661868230015162624 +1661868230057163520 +1661868230099164416 +1661868230141165312 +1661868230186166272 +1661868230228167168 +1661868230270168064 +1661868230309168896 +1661868230354169856 +1661868230396170752 +1661868230435171584 +1661868230480172544 +1661868230525173504 +1661868230561174272 +1661868230603175168 +1661868230642176000 +1661868230684176896 +1661868230723177728 +1661868230765178624 +1661868230807179520 +1661868230849180416 +1661868230891181312 +1661868230936182272 +1661868230978183168 +1661868231020184064 +1661868231059184896 +1661868231104185856 +1661868231146186752 +1661868231191187712 +1661868231233188608 +1661868231275189504 +1661868231317190400 +1661868231356191232 +1661868231401192192 +1661868231443193088 +1661868231482193920 +1661868231524194816 +1661868231569195776 +1661868231611196672 +1661868231653197568 +1661868231692198400 +1661868231731199232 +1661868231770200064 +1661868231812200960 +1661868231857201920 +1661868231902202880 +1661868231944203776 +1661868231986204672 +1661868232031205632 +1661868232070206464 +1661868232112207360 +1661868232157208320 +1661868232199209216 +1661868232241210112 +1661868232283211008 +1661868232328211968 +1661868232370212864 +1661868232412213760 +1661868232454214656 +1661868232496215552 +1661868232532216320 +1661868232574217216 +1661868232616218112 +1661868232652218880 +1661868232691219712 +1661868232733220608 +1661868232775221504 +1661868232817222400 +1661868232859223296 +1661868232901224192 +1661868232946225152 +1661868232991226112 +1661868233030226944 +1661868233075227904 +1661868233117228800 +1661868233159229696 +1661868233204230656 +1661868233240231424 +1661868233282232320 +1661868233324233216 +1661868233363234048 +1661868233405234944 +1661868233441235712 +1661868233483236608 +1661868233528237568 +1661868233576238592 +1661868233624239616 +1661868233669240576 +1661868233711241472 +1661868233756242432 +1661868233798243328 +1661868233840244224 +1661868233882245120 +1661868233924246016 +1661868233963246848 +1661868234005247744 +1661868234053248768 +1661868234095249664 +1661868234134250496 +1661868234179251456 +1661868234221252352 +1661868234263253248 +1661868234305254144 +1661868234347255040 +1661868234389255936 +1661868234431256832 +1661868234473257728 +1661868234518258688 +1661868234560259584 +1661868234602260480 +1661868234644261376 +1661868234686262272 +1661868234728263168 +1661868234770264064 +1661868234812264960 +1661868234848265728 +1661868234890266624 +1661868234929267456 +1661868234974268416 +1661868235013269248 +1661868235055270144 +1661868235103271168 +1661868235148272128 +1661868235187272960 +1661868235232273920 +1661868235274274816 +1661868235319275776 +1661868235361276672 +1661868235403277568 +1661868235448278528 +1661868235499279616 +1661868235544280576 +1661868235589281536 +1661868235631282432 +1661868235670283264 +1661868235715284224 +1661868235760285184 +1661868235802286080 +1661868235850287104 +1661868235892288000 +1661868235937288960 +1661868235979289856 +1661868236021290752 +1661868236069291776 +1661868236111292672 +1661868236153293568 +1661868236195294464 +1661868236240295424 +1661868236282296320 +1661868236333297408 +1661868236375298304 +1661868236417299200 +1661868236462300160 +1661868236507301120 +1661868236543301888 +1661868236585302784 +1661868236627303680 +1661868236666304512 +1661868236708305408 +1661868236756306432 +1661868236795307264 +1661868236834308096 +1661868236870308864 +1661868236915309824 +1661868236957310720 +1661868237005311744 +1661868237047312640 +1661868237089313536 +1661868237134314496 +1661868237176315392 +1661868237218316288 +1661868237263317248 +1661868237302318080 +1661868237344318976 +1661868237383319808 +1661868237425320704 +1661868237467321600 +1661868237506322432 +1661868237557323520 +1661868237599324416 +1661868237641325312 +1661868237683326208 +1661868237725327104 +1661868237770328064 +1661868237809328896 +1661868237851329792 +1661868237899330816 +1661868237941331712 +1661868237989332736 +1661868238028333568 +1661868238073334528 +1661868238118335488 +1661868238160336384 +1661868238202337280 +1661868238241338112 +1661868238292339200 +1661868238337340160 +1661868238379341056 +1661868238421341952 +1661868238463342848 +1661868238505343744 +1661868238547344640 +1661868238583345408 +1661868238628346368 +1661868238667347200 +1661868238709348096 +1661868238757349120 +1661868238799350016 +1661868238844350976 +1661868238889351936 +1661868238928352768 +1661868238967353600 +1661868239003354368 +1661868239045355264 +1661868239090356224 +1661868239138357248 +1661868239183358208 +1661868239234359296 +1661868239279360256 +1661868239321361152 +1661868239369362176 +1661868239411363072 +1661868239456364032 +1661868239504365056 +1661868239546365952 +1661868239591366912 +1661868239633367808 +1661868239678368768 +1661868239717369600 +1661868239759370496 +1661868239810371584 +1661868239852372480 +1661868239894373376 +1661868239936374272 +1661868239975375104 +1661868240023376128 +1661868240065377024 +1661868240107377920 +1661868240149378816 +1661868240191379712 +1661868240236380672 +1661868240281381632 +1661868240320382464 +1661868240359383296 +1661868240398384128 +1661868240437384960 +1661868240479385856 +1661868240521386752 +1661868240560387584 +1661868240599388416 +1661868240641389312 +1661868240683390208 +1661868240728391168 +1661868240770392064 +1661868240815393024 +1661868240857393920 +1661868240902394880 +1661868240947395840 +1661868240986396672 +1661868241028397568 +1661868241070398464 +1661868241121399552 +1661868241166400512 +1661868241208401408 +1661868241247402240 +1661868241289403136 +1661868241331404032 +1661868241373404928 +1661868241418405888 +1661868241460406784 +1661868241505407744 +1661868241544408576 +1661868241583409408 +1661868241625410304 +1661868241667411200 +1661868241709412096 +1661868241754413056 +1661868241796413952 +1661868241838414848 +1661868241880415744 +1661868241925416704 +1661868241979417856 +1661868242021418752 +1661868242060419584 +1661868242099420416 +1661868242141421312 +1661868242183422208 +1661868242225423104 +1661868242267424000 +1661868242312424960 +1661868242354425856 +1661868242390426624 +1661868242432427520 +1661868242471428352 +1661868242507429120 +1661868242549430016 +1661868242591430912 +1661868242633431808 +1661868242675432704 +1661868242717433600 +1661868242759434496 +1661868242801435392 +1661868242843436288 +1661868242885437184 +1661868242927438080 +1661868242969438976 +1661868243011439872 +1661868243053440768 +1661868243095441664 +1661868243140442624 +1661868243182443520 +1661868243221444352 +1661868243272445440 +1661868243317446400 +1661868243359447296 +1661868243401448192 +1661868243440449024 +1661868243488450048 +1661868243533451008 +1661868243575451904 +1661868243617452800 +1661868243656453632 +1661868243698454528 +1661868243740455424 +1661868243782456320 +1661868243824457216 +1661868243866458112 +1661868243914459136 +1661868243956460032 +1661868243998460928 +1661868244043461888 +1661868244085462784 +1661868244127463680 +1661868244172464640 +1661868244220465664 +1661868244265466624 +1661868244304467456 +1661868244349468416 +1661868244394469376 +1661868244439470336 +1661868244481471232 +1661868244520472064 +1661868244559472896 +1661868244601473792 +1661868244649474816 +1661868244691475712 +1661868244736476672 +1661868244778477568 +1661868244823478528 +1661868244865479424 +1661868244913480448 +1661868244961481472 +1661868245012482560 +1661868245054483456 +1661868245096484352 +1661868245138485248 +1661868245180486144 +1661868245222487040 +1661868245267488000 +1661868245309488896 +1661868245351489792 +1661868245396490752 +1661868245438491648 +1661868245483492608 +1661868245525493504 +1661868245570494464 +1661868245615495424 +1661868245657496320 +1661868245702497280 +1661868245741498112 +1661868245783499008 +1661868245822499840 +1661868245867500800 +1661868245909501696 +1661868245951502592 +1661868245993503488 +1661868246038504448 +1661868246080505344 +1661868246125506304 +1661868246182507520 +1661868246224508416 +1661868246263509248 +1661868246302510080 +1661868246344510976 +1661868246389511936 +1661868246434512896 +1661868246476513792 +1661868246521514752 +1661868246563515648 +1661868246602516480 +1661868246638517248 +1661868246686518272 +1661868246725519104 +1661868246767520000 +1661868246809520896 +1661868246851521792 +1661868246893522688 +1661868246944523776 +1661868246986524672 +1661868247028525568 +1661868247076526592 +1661868247118527488 +1661868247151528192 +1661868247190529024 +1661868247238530048 +1661868247280530944 +1661868247325531904 +1661868247370532864 +1661868247415533824 +1661868247457534720 +1661868247499535616 +1661868247541536512 +1661868247580537344 +1661868247622538240 +1661868247664539136 +1661868247709540096 +1661868247751540992 +1661868247790541824 +1661868247832542720 +1661868247874543616 +1661868247925544704 +1661868247967545600 +1661868248015546624 +1661868248057547520 +1661868248099548416 +1661868248141549312 +1661868248183550208 +1661868248222551040 +1661868248264551936 +1661868248312552960 +1661868248354553856 +1661868248399554816 +1661868248444555776 +1661868248486556672 +1661868248528557568 +1661868248567558400 +1661868248606559232 +1661868248645560064 +1661868248693561088 +1661868248735561984 +1661868248777562880 +1661868248819563776 +1661868248861564672 +1661868248906565632 +1661868248945566464 +1661868248987567360 +1661868249029568256 +1661868249077569280 +1661868249119570176 +1661868249164571136 +1661868249206572032 +1661868249248572928 +1661868249299574016 +1661868249341574912 +1661868249386575872 +1661868249425576704 +1661868249470577664 +1661868249509578496 +1661868249554579456 +1661868249599580416 +1661868249641581312 +1661868249686582272 +1661868249728583168 +1661868249767584000 +1661868249806584832 +1661868249851585792 +1661868249896586752 +1661868249932587520 +1661868249974588416 +1661868250016589312 +1661868250055590144 +1661868250097591040 +1661868250139591936 +1661868250181592832 +1661868250223593728 +1661868250265594624 +1661868250304595456 +1661868250343596288 +1661868250385597184 +1661868250430598144 +1661868250472599040 +1661868250523600128 +1661868250574601216 +1661868250619602176 +1661868250658603008 +1661868250703603968 +1661868250754605056 +1661868250796605952 +1661868250838606848 +1661868250880607744 +1661868250922608640 +1661868250964609536 +1661868251006610432 +1661868251048611328 +1661868251090612224 +1661868251129613056 +1661868251177614080 +1661868251219614976 +1661868251261615872 +1661868251303616768 +1661868251342617600 +1661868251384618496 +1661868251426619392 +1661868251471620352 +1661868251513621248 +1661868251555622144 +1661868251597623040 +1661868251642624000 +1661868251693625088 +1661868251732625920 +1661868251771626752 +1661868251810627584 +1661868251855628544 +1661868251897629440 +1661868251939630336 +1661868251984631296 +1661868252035632384 +1661868252074633216 +1661868252122634240 +1661868252164635136 +1661868252206636032 +1661868252245636864 +1661868252287637760 +1661868252338638848 +1661868252380639744 +1661868252422640640 +1661868252464641536 +1661868252506642432 +1661868252545643264 +1661868252590644224 +1661868252632645120 +1661868252677646080 +1661868252722647040 +1661868252764647936 +1661868252806648832 +1661868252842649600 +1661868252884650496 +1661868252938651648 +1661868252980652544 +1661868253022653440 +1661868253064654336 +1661868253100655104 +1661868253145656064 +1661868253184656896 +1661868253226657792 +1661868253268658688 +1661868253307659520 +1661868253349660416 +1661868253391661312 +1661868253433662208 +1661868253478663168 +1661868253520664064 +1661868253562664960 +1661868253610665984 +1661868253652666880 +1661868253694667776 +1661868253736668672 +1661868253778669568 +1661868253817670400 +1661868253859671296 +1661868253901672192 +1661868253943673088 +1661868253985673984 +1661868254027674880 +1661868254069675776 +1661868254111676672 +1661868254153677568 +1661868254195678464 +1661868254234679296 +1661868254279680256 +1661868254318681088 +1661868254360681984 +1661868254402682880 +1661868254444683776 +1661868254489684736 +1661868254534685696 +1661868254582686720 +1661868254624687616 +1661868254666688512 +1661868254708689408 +1661868254750690304 +1661868254798691328 +1661868254843692288 +1661868254885693184 +1661868254924694016 +1661868254969694976 +1661868255011695872 +1661868255053696768 +1661868255095697664 +1661868255137698560 +1661868255179699456 +1661868255224700416 +1661868255266701312 +1661868255317702400 +1661868255359703296 +1661868255398704128 +1661868255437704960 +1661868255479705856 +1661868255518706688 +1661868255557707520 +1661868255599708416 +1661868255641709312 +1661868255680710144 +1661868255722711040 +1661868255761711872 +1661868255803712768 +1661868255845713664 +1661868255887714560 +1661868255932715520 +1661868255977716480 +1661868256019717376 +1661868256061718272 +1661868256103719168 +1661868256145720064 +1661868256196721152 +1661868256238722048 +1661868256280722944 +1661868256319723776 +1661868256361724672 +1661868256403725568 +1661868256442726400 +1661868256490727424 +1661868256529728256 +1661868256568729088 +1661868256607729920 +1661868256649730816 +1661868256691731712 +1661868256727732480 +1661868256766733312 +1661868256808734208 +1661868256847735040 +1661868256892736000 +1661868256934736896 +1661868256979737856 +1661868257021738752 +1661868257063739648 +1661868257105740544 +1661868257150741504 +1661868257192742400 +1661868257234743296 +1661868257276744192 +1661868257318745088 +1661868257360745984 +1661868257408747008 +1661868257450747904 +1661868257492748800 +1661868257534749696 +1661868257582750720 +1661868257621751552 +1661868257663752448 +1661868257702753280 +1661868257741754112 +1661868257783755008 +1661868257828755968 +1661868257873756928 +1661868257915757824 +1661868257960758784 +1661868257999759616 +1661868258044760576 +1661868258092761600 +1661868258134762496 +1661868258170763264 +1661868258209764096 +1661868258251764992 +1661868258293765888 +1661868258332766720 +1661868258374767616 +1661868258416768512 +1661868258458769408 +1661868258503770368 +1661868258545771264 +1661868258587772160 +1661868258629773056 +1661868258674774016 +1661868258713774848 +1661868258749775616 +1661868258788776448 +1661868258830777344 +1661868258872778240 +1661868258914779136 +1661868258950779904 +1661868258992780800 +1661868259034781696 +1661868259073782528 +1661868259118783488 +1661868259160784384 +1661868259202785280 +1661868259244786176 +1661868259286787072 +1661868259328787968 +1661868259373788928 +1661868259415789824 +1661868259460790784 +1661868259502791680 +1661868259544792576 +1661868259592793600 +1661868259631794432 +1661868259673795328 +1661868259715796224 +1661868259757797120 +1661868259799798016 +1661868259838798848 +1661868259883799808 +1661868259928800768 +1661868259973801728 +1661868260015802624 +1661868260054803456 +1661868260096804352 +1661868260138805248 +1661868260180806144 +1661868260219806976 +1661868260261807872 +1661868260303808768 +1661868260348809728 +1661868260390810624 +1661868260432811520 +1661868260477812480 +1661868260519813376 +1661868260564814336 +1661868260606815232 +1661868260648816128 +1661868260690817024 +1661868260732817920 +1661868260774818816 +1661868260816819712 +1661868260861820672 +1661868260903821568 +1661868260939822336 +1661868260981823232 +1661868261020824064 +1661868261059824896 +1661868261104825856 +1661868261149826816 +1661868261188827648 +1661868261224828416 +1661868261272829440 +1661868261314830336 +1661868261359831296 +1661868261398832128 +1661868261443833088 +1661868261488834048 +1661868261530834944 +1661868261572835840 +1661868261620836864 +1661868261662837760 +1661868261707838720 +1661868261752839680 +1661868261791840512 +1661868261833841408 +1661868261875842304 +1661868261923843328 +1661868261965844224 +1661868262010845184 +1661868262052846080 +1661868262100847104 +1661868262139847936 +1661868262178848768 +1661868262217849600 +1661868262259850496 +1661868262301851392 +1661868262343852288 +1661868262388853248 +1661868262430854144 +1661868262472855040 +1661868262511855872 +1661868262559856896 +1661868262601857792 +1661868262646858752 +1661868262691859712 +1661868262733860608 +1661868262775861504 +1661868262820862464 +1661868262868863488 +1661868262907864320 +1661868262949865216 +1661868262991866112 +1661868263033867008 +1661868263075867904 +1661868263117868800 +1661868263159869696 +1661868263198870528 +1661868263240871424 +1661868263279872256 +1661868263321873152 +1661868263363874048 +1661868263408875008 +1661868263444875776 +1661868263486876672 +1661868263528877568 +1661868263567878400 +1661868263609879296 +1661868263651880192 +1661868263696881152 +1661868263738882048 +1661868263780882944 +1661868263822883840 +1661868263867884800 +1661868263906885632 +1661868263954886656 +1661868263996887552 +1661868264035888384 +1661868264074889216 +1661868264119890176 +1661868264161891072 +1661868264203891968 +1661868264242892800 +1661868264287893760 +1661868264329894656 +1661868264371895552 +1661868264413896448 +1661868264461897472 +1661868264500898304 +1661868264539899136 +1661868264584900096 +1661868264626900992 +1661868264665901824 +1661868264707902720 +1661868264752903680 +1661868264800904704 +1661868264851905792 +1661868264893906688 +1661868264935907584 +1661868264977908480 +1661868265016909312 +1661868265058910208 +1661868265100911104 +1661868265142912000 +1661868265187912960 +1661868265229913856 +1661868265274914816 +1661868265322915840 +1661868265361916672 +1661868265403917568 +1661868265445918464 +1661868265484919296 +1661868265526920192 +1661868265565921024 +1661868265619922176 +1661868265664923136 +1661868265706924032 +1661868265748924928 +1661868265790925824 +1661868265829926656 +1661868265874927616 +1661868265916928512 +1661868265955929344 +1661868265997930240 +1661868266036931072 +1661868266081932032 +1661868266123932928 +1661868266162933760 +1661868266204934656 +1661868266246935552 +1661868266288936448 +1661868266330937344 +1661868266369938176 +1661868266408939008 +1661868266450939904 +1661868266492940800 +1661868266540941824 +1661868266588942848 +1661868266633943808 +1661868266675944704 +1661868266729945856 +1661868266768946688 +1661868266813947648 +1661868266852948480 +1661868266894949376 +1661868266939950336 +1661868266978951168 +1661868267020952064 +1661868267065953024 +1661868267110953984 +1661868267149954816 +1661868267194955776 +1661868267236956672 +1661868267278957568 +1661868267317958400 +1661868267359959296 +1661868267398960128 +1661868267440961024 +1661868267485961984 +1661868267527962880 +1661868267569963776 +1661868267611964672 +1661868267650965504 +1661868267686966272 +1661868267728967168 +1661868267770968064 +1661868267818969088 +1661868267860969984 +1661868267902970880 +1661868267950971904 +1661868268001972992 +1661868268043973888 +1661868268091974912 +1661868268133975808 +1661868268175976704 +1661868268217977600 +1661868268259978496 +1661868268301979392 +1661868268340980224 +1661868268382981120 +1661868268427982080 +1661868268472983040 +1661868268511983872 +1661868268553984768 +1661868268598985728 +1661868268640986624 +1661868268685987584 +1661868268727988480 +1661868268766989312 +1661868268811990272 +1661868268853991168 +1661868268892992000 +1661868268937992960 +1661868268979993856 +1661868269021994752 +1661868269063995648 +1661868269105996544 +1661868269147997440 +1661868269192998400 +1661868269234999296 +1661868269277000192 +1661868269316001024 +1661868269361001984 +1661868269400002816 +1661868269442003712 +1661868269484004608 +1661868269529005568 +1661868269568006400 +1661868269607007232 +1661868269649008128 +1661868269694009088 +1661868269736009984 +1661868269784011008 +1661868269829011968 +1661868269877012992 +1661868269919013888 +1661868269961014784 +1661868270009015808 +1661868270051016704 +1661868270096017664 +1661868270147018752 +1661868270186019584 +1661868270225020416 +1661868270264021248 +1661868270300022016 +1661868270339022848 +1661868270384023808 +1661868270423024640 +1661868270474025728 +1661868270516026624 +1661868270558027520 +1661868270600028416 +1661868270639029248 +1661868270681030144 +1661868270723031040 +1661868270762031872 +1661868270807032832 +1661868270849033728 +1661868270897034752 +1661868270939035648 +1661868270978036480 +1661868271026037504 +1661868271071038464 +1661868271113039360 +1661868271152040192 +1661868271194041088 +1661868271248042240 +1661868271290043136 +1661868271335044096 +1661868271380045056 +1661868271422045952 +1661868271467046912 +1661868271506047744 +1661868271545048576 +1661868271587049472 +1661868271629050368 +1661868271668051200 +1661868271713052160 +1661868271758053120 +1661868271803054080 +1661868271845054976 +1661868271887055872 +1661868271929056768 +1661868271971057664 +1661868272010058496 +1661868272052059392 +1661868272094060288 +1661868272136061184 +1661868272181062144 +1661868272223063040 +1661868272265063936 +1661868272307064832 +1661868272352065792 +1661868272391066624 +1661868272427067392 +1661868272469068288 +1661868272508069120 +1661868272550070016 +1661868272592070912 +1661868272631071744 +1661868272673072640 +1661868272715073536 +1661868272757074432 +1661868272796075264 +1661868272838076160 +1661868272880077056 +1661868272922077952 +1661868272964078848 +1661868273006079744 +1661868273045080576 +1661868273087081472 +1661868273129082368 +1661868273171083264 +1661868273213084160 +1661868273255085056 +1661868273297085952 +1661868273342086912 +1661868273387087872 +1661868273429088768 +1661868273471089664 +1661868273516090624 +1661868273558091520 +1661868273606092544 +1661868273651093504 +1661868273693094400 +1661868273735095296 +1661868273777096192 +1661868273822097152 +1661868273864098048 +1661868273909099008 +1661868273957100032 +1661868273999100928 +1661868274041101824 +1661868274092102912 +1661868274131103744 +1661868274173104640 +1661868274215105536 +1661868274260106496 +1661868274299107328 +1661868274341108224 +1661868274386109184 +1661868274428110080 +1661868274476111104 +1661868274521112064 +1661868274566113024 +1661868274605113856 +1661868274656114944 +1661868274701115904 +1661868274743116800 +1661868274785117696 +1661868274827118592 +1661868274869119488 +1661868274911120384 +1661868274953121280 +1661868274989122048 +1661868275031122944 +1661868275070123776 +1661868275109124608 +1661868275151125504 +1661868275193126400 +1661868275238127360 +1661868275280128256 +1661868275322129152 +1661868275364130048 +1661868275403130880 +1661868275451131904 +1661868275493132800 +1661868275538133760 +1661868275580134656 +1661868275622135552 +1661868275670136576 +1661868275706137344 +1661868275745138176 +1661868275784139008 +1661868275829139968 +1661868275874140928 +1661868275916141824 +1661868275958142720 +1661868275997143552 +1661868276039144448 +1661868276081145344 +1661868276123146240 +1661868276168147200 +1661868276210148096 +1661868276249148928 +1661868276291149824 +1661868276333150720 +1661868276378151680 +1661868276417152512 +1661868276459153408 +1661868276501154304 +1661868276546155264 +1661868276588156160 +1661868276630157056 +1661868276675158016 +1661868276717158912 +1661868276759159808 +1661868276804160768 +1661868276846161664 +1661868276885162496 +1661868276924163328 +1661868276963164160 +1661868277002164992 +1661868277044165888 +1661868277086166784 +1661868277128167680 +1661868277170168576 +1661868277215169536 +1661868277260170496 +1661868277308171520 +1661868277347172352 +1661868277389173248 +1661868277431174144 +1661868277470174976 +1661868277512175872 +1661868277554176768 +1661868277596177664 +1661868277641178624 +1661868277686179584 +1661868277728180480 +1661868277770181376 +1661868277812182272 +1661868277851183104 +1661868277893184000 +1661868277932184832 +1661868277971185664 +1661868278013186560 +1661868278055187456 +1661868278100188416 +1661868278145189376 +1661868278187190272 +1661868278229191168 +1661868278271192064 +1661868278310192896 +1661868278349193728 +1661868278391194624 +1661868278427195392 +1661868278469196288 +1661868278511197184 +1661868278550198016 +1661868278598199040 +1661868278637199872 +1661868278676200704 +1661868278721201664 +1661868278763202560 +1661868278805203456 +1661868278847204352 +1661868278886205184 +1661868278925206016 +1661868278967206912 +1661868279009207808 +1661868279048208640 +1661868279090209536 +1661868279132210432 +1661868279177211392 +1661868279216212224 +1661868279264213248 +1661868279309214208 +1661868279351215104 +1661868279393216000 +1661868279435216896 +1661868279477217792 +1661868279522218752 +1661868279570219776 +1661868279612220672 +1661868279651221504 +1661868279687222272 +1661868279732223232 +1661868279774224128 +1661868279816225024 +1661868279858225920 +1661868279900226816 +1661868279945227776 +1661868279990228736 +1661868280035229696 +1661868280077230592 +1661868280125231616 +1661868280167232512 +1661868280209233408 +1661868280251234304 +1661868280293235200 +1661868280338236160 +1661868280380237056 +1661868280422237952 +1661868280464238848 +1661868280503239680 +1661868280548240640 +1661868280590241536 +1661868280635242496 +1661868280680243456 +1661868280722244352 +1661868280764245248 +1661868280800246016 +1661868280851247104 +1661868280905248256 +1661868280956249344 +1661868280998250240 +1661868281040251136 +1661868281082252032 +1661868281124252928 +1661868281166253824 +1661868281208254720 +1661868281253255680 +1661868281292256512 +1661868281337257472 +1661868281379258368 +1661868281424259328 +1661868281466260224 +1661868281511261184 +1661868281550262016 +1661868281592262912 +1661868281631263744 +1661868281676264704 +1661868281718265600 +1661868281763266560 +1661868281808267520 +1661868281850268416 +1661868281892269312 +1661868281937270272 +1661868281985271296 +1661868282024272128 +1661868282066273024 +1661868282111273984 +1661868282159275008 +1661868282204275968 +1661868282249276928 +1661868282288277760 +1661868282330278656 +1661868282378279680 +1661868282417280512 +1661868282459281408 +1661868282513282560 +1661868282555283456 +1661868282597284352 +1661868282639285248 +1661868282681286144 +1661868282726287104 +1661868282768288000 +1661868282813288960 +1661868282852289792 +1661868282894290688 +1661868282939291648 +1661868282984292608 +1661868283023293440 +1661868283068294400 +1661868283116295424 +1661868283158296320 +1661868283203297280 +1661868283245298176 +1661868283284299008 +1661868283329299968 +1661868283371300864 +1661868283419301888 +1661868283461302784 +1661868283500303616 +1661868283548304640 +1661868283590305536 +1661868283638306560 +1661868283677307392 +1661868283725308416 +1661868283770309376 +1661868283812310272 +1661868283857311232 +1661868283899312128 +1661868283941313024 +1661868283989314048 +1661868284028314880 +1661868284067315712 +1661868284109316608 +1661868284157317632 +1661868284199318528 +1661868284247319552 +1661868284286320384 +1661868284328321280 +1661868284379322368 +1661868284421323264 +1661868284457324032 +1661868284496324864 +1661868284538325760 +1661868284580326656 +1661868284622327552 +1661868284667328512 +1661868284709329408 +1661868284763330560 +1661868284805331456 +1661868284850332416 +1661868284895333376 +1661868284937334272 +1661868284976335104 +1661868285021336064 +1661868285066337024 +1661868285105337856 +1661868285156338944 +1661868285201339904 +1661868285243340800 +1661868285294341888 +1661868285336342784 +1661868285378343680 +1661868285420344576 +1661868285459345408 +1661868285501346304 +1661868285543347200 +1661868285585348096 +1661868285624348928 +1661868285666349824 +1661868285711350784 +1661868285753351680 +1661868285795352576 +1661868285834353408 +1661868285885354496 +1661868285927355392 +1661868285969356288 +1661868286011357184 +1661868286050358016 +1661868286089358848 +1661868286131359744 +1661868286176360704 +1661868286221361664 +1661868286263362560 +1661868286314363648 +1661868286353364480 +1661868286398365440 +1661868286440366336 +1661868286482367232 +1661868286524368128 +1661868286560368896 +1661868286602369792 +1661868286644370688 +1661868286686371584 +1661868286728372480 +1661868286770373376 +1661868286821374464 +1661868286863375360 +1661868286908376320 +1661868286950377216 +1661868286992378112 +1661868287037379072 +1661868287079379968 +1661868287127380992 +1661868287169381888 +1661868287208382720 +1661868287253383680 +1661868287298384640 +1661868287340385536 +1661868287382386432 +1661868287424387328 +1661868287466388224 +1661868287508389120 +1661868287550390016 +1661868287592390912 +1661868287634391808 +1661868287676392704 +1661868287718393600 +1661868287760394496 +1661868287805395456 +1661868287847396352 +1661868287895397376 +1661868287937398272 +1661868287976399104 +1661868288015399936 +1661868288063400960 +1661868288105401856 +1661868288147402752 +1661868288189403648 +1661868288231404544 +1661868288273405440 +1661868288315406336 +1661868288354407168 +1661868288396408064 +1661868288438408960 +1661868288483409920 +1661868288525410816 +1661868288570411776 +1661868288606412544 +1661868288648413440 +1661868288690414336 +1661868288732415232 +1661868288774416128 +1661868288816417024 +1661868288858417920 +1661868288900418816 +1661868288951419904 +1661868288993420800 +1661868289041421824 +1661868289083422720 +1661868289128423680 +1661868289170424576 +1661868289212425472 +1661868289257426432 +1661868289296427264 +1661868289338428160 +1661868289380429056 +1661868289428430080 +1661868289476431104 +1661868289518432000 +1661868289560432896 +1661868289602433792 +1661868289641434624 +1661868289683435520 +1661868289725436416 +1661868289767437312 +1661868289809438208 +1661868289851439104 +1661868289890439936 +1661868289935440896 +1661868289983441920 +1661868290025442816 +1661868290067443712 +1661868290115444736 +1661868290154445568 +1661868290199446528 +1661868290244447488 +1661868290289448448 +1661868290328449280 +1661868290364450048 +1661868290412451072 +1661868290454451968 +1661868290496452864 +1661868290535453696 +1661868290580454656 +1661868290622455552 +1661868290664456448 +1661868290706457344 +1661868290754458368 +1661868290802459392 +1661868290841460224 +1661868290883461120 +1661868290925462016 +1661868290967462912 +1661868291015463936 +1661868291060464896 +1661868291102465792 +1661868291144466688 +1661868291186467584 +1661868291231468544 +1661868291270469376 +1661868291312470272 +1661868291354471168 +1661868291396472064 +1661868291438472960 +1661868291483473920 +1661868291525474816 +1661868291567475712 +1661868291609476608 +1661868291648477440 +1661868291690478336 +1661868291732479232 +1661868291771480064 +1661868291813480960 +1661868291855481856 +1661868291900482816 +1661868291942483712 +1661868291984484608 +1661868292026485504 +1661868292071486464 +1661868292113487360 +1661868292152488192 +1661868292194489088 +1661868292233489920 +1661868292281490944 +1661868292320491776 +1661868292359492608 +1661868292401493504 +1661868292443494400 +1661868292485495296 +1661868292530496256 +1661868292572497152 +1661868292614498048 +1661868292656498944 +1661868292698499840 +1661868292743500800 +1661868292785501696 +1661868292821502464 +1661868292869503488 +1661868292911504384 +1661868292959505408 +1661868293001506304 +1661868293043507200 +1661868293085508096 +1661868293130509056 +1661868293175510016 +1661868293217510912 +1661868293265511936 +1661868293313512960 +1661868293352513792 +1661868293391514624 +1661868293430515456 +1661868293472516352 +1661868293520517376 +1661868293562518272 +1661868293601519104 +1661868293643520000 +1661868293685520896 +1661868293730521856 +1661868293772522752 +1661868293811523584 +1661868293853524480 +1661868293898525440 +1661868293940526336 +1661868293985527296 +1661868294027528192 +1661868294069529088 +1661868294111529984 +1661868294162531072 +1661868294204531968 +1661868294246532864 +1661868294285533696 +1661868294324534528 +1661868294366535424 diff --git a/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_track1.txt b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_track1.txt new file mode 100644 index 0000000000..f8502440d4 --- /dev/null +++ b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_track1.txt @@ -0,0 +1,2030 @@ +1662015311059723520 +1662015311101724416 +1662015311146725376 +1662015311203726592 +1662015311248727552 +1662015311293728512 +1662015311335729408 +1662015311377730304 +1662015311422731264 +1662015311464732160 +1662015311506733056 +1662015311548733952 +1662015311590734848 +1662015311635735808 +1662015311677736704 +1662015311719737600 +1662015311761738496 +1662015311809739520 +1662015311857740544 +1662015311902741504 +1662015311944742400 +1662015311986743296 +1662015312031744256 +1662015312076745216 +1662015312130746368 +1662015312169747200 +1662015312208748032 +1662015312253748992 +1662015312295749888 +1662015312340750848 +1662015312379751680 +1662015312424752640 +1662015312463753472 +1662015312508754432 +1662015312550755328 +1662015312592756224 +1662015312631757056 +1662015312679758080 +1662015312724759040 +1662015312766759936 +1662015312811760896 +1662015312856761856 +1662015312901762816 +1662015312943763712 +1662015312985764608 +1662015313027765504 +1662015313075766528 +1662015313117767424 +1662015313159768320 +1662015313201769216 +1662015313240770048 +1662015313282770944 +1662015313327771904 +1662015313369772800 +1662015313411773696 +1662015313456774656 +1662015313498775552 +1662015313540776448 +1662015313591777536 +1662015313630778368 +1662015313672779264 +1662015313717780224 +1662015313756781056 +1662015313801782016 +1662015313843782912 +1662015313885783808 +1662015313927784704 +1662015313972785664 +1662015314014786560 +1662015314056787456 +1662015314101788416 +1662015314143789312 +1662015314185790208 +1662015314227791104 +1662015314272792064 +1662015314317793024 +1662015314362793984 +1662015314413795072 +1662015314455795968 +1662015314497796864 +1662015314539797760 +1662015314581798656 +1662015314626799616 +1662015314668800512 +1662015314716801536 +1662015314761802496 +1662015314803803392 +1662015314848804352 +1662015314896805376 +1662015314938806272 +1662015314980807168 +1662015315028808192 +1662015315073809152 +1662015315115810048 +1662015315154810880 +1662015315199811840 +1662015315238812672 +1662015315280813568 +1662015315328814592 +1662015315379815680 +1662015315427816704 +1662015315475817728 +1662015315532818944 +1662015315577819904 +1662015315619820800 +1662015315670821888 +1662015315721822976 +1662015315766823936 +1662015315814824960 +1662015315859825920 +1662015315904826880 +1662015315949827840 +1662015315991828736 +1662015316033829632 +1662015316078830592 +1662015316126831616 +1662015316174832640 +1662015316219833600 +1662015316270834688 +1662015316315835648 +1662015316366836736 +1662015316414837760 +1662015316462838784 +1662015316507839744 +1662015316552840704 +1662015316597841664 +1662015316648842752 +1662015316690843648 +1662015316729844480 +1662015316774845440 +1662015316822846464 +1662015316867847424 +1662015316909848320 +1662015316951849216 +1662015316993850112 +1662015317038851072 +1662015317083852032 +1662015317128852992 +1662015317170853888 +1662015317218854912 +1662015317260855808 +1662015317302856704 +1662015317344857600 +1662015317389858560 +1662015317434859520 +1662015317473860352 +1662015317515861248 +1662015317560862208 +1662015317605863168 +1662015317647864064 +1662015317692865024 +1662015317740866048 +1662015317782866944 +1662015317830867968 +1662015317872868864 +1662015317914869760 +1662015317962870784 +1662015318010871808 +1662015318058872832 +1662015318109873920 +1662015318148874752 +1662015318193875712 +1662015318235876608 +1662015318280877568 +1662015318325878528 +1662015318367879424 +1662015318412880384 +1662015318454881280 +1662015318499882240 +1662015318547883264 +1662015318589884160 +1662015318631885056 +1662015318682886144 +1662015318727887104 +1662015318769888000 +1662015318814888960 +1662015318859889920 +1662015318907890944 +1662015318952891904 +1662015318994892800 +1662015319036893696 +1662015319078894592 +1662015319120895488 +1662015319162896384 +1662015319207897344 +1662015319249898240 +1662015319291899136 +1662015319339900160 +1662015319387901184 +1662015319432902144 +1662015319474903040 +1662015319516903936 +1662015319561904896 +1662015319609905920 +1662015319654906880 +1662015319699907840 +1662015319741908736 +1662015319792909824 +1662015319840910848 +1662015319891911936 +1662015319939912960 +1662015319981913856 +1662015320023914752 +1662015320077915904 +1662015320125916928 +1662015320167917824 +1662015320209918720 +1662015320251919616 +1662015320296920576 +1662015320338921472 +1662015320389922560 +1662015320437923584 +1662015320485924608 +1662015320530925568 +1662015320575926528 +1662015320617927424 +1662015320659928320 +1662015320704929280 +1662015320746930176 +1662015320791931136 +1662015320839932160 +1662015320881933056 +1662015320926934016 +1662015320968934912 +1662015321010935808 +1662015321058936832 +1662015321103937792 +1662015321145938688 +1662015321193939712 +1662015321241940736 +1662015321283941632 +1662015321328942592 +1662015321373943552 +1662015321415944448 +1662015321454945280 +1662015321499946240 +1662015321541947136 +1662015321592948224 +1662015321637949184 +1662015321685950208 +1662015321727951104 +1662015321775952128 +1662015321817953024 +1662015321859953920 +1662015321901954816 +1662015321943955712 +1662015321985956608 +1662015322033957632 +1662015322084958720 +1662015322126959616 +1662015322171960576 +1662015322222961664 +1662015322267962624 +1662015322309963520 +1662015322351964416 +1662015322396965376 +1662015322438966272 +1662015322483967232 +1662015322528968192 +1662015322567969024 +1662015322609969920 +1662015322651970816 +1662015322699971840 +1662015322741972736 +1662015322786973696 +1662015322828974592 +1662015322876975616 +1662015322918976512 +1662015322966977536 +1662015323008978432 +1662015323059979520 +1662015323101980416 +1662015323143981312 +1662015323188982272 +1662015323230983168 +1662015323272984064 +1662015323314984960 +1662015323359985920 +1662015323404986880 +1662015323455987968 +1662015323494988800 +1662015323542989824 +1662015323584990720 +1662015323629991680 +1662015323671992576 +1662015323713993472 +1662015323755994368 +1662015323803995392 +1662015323848996352 +1662015323896997376 +1662015323938998272 +1662015323980999168 +1662015324026000128 +1662015324071001088 +1662015324113001984 +1662015324164003072 +1662015324206003968 +1662015324251004928 +1662015324293005824 +1662015324338006784 +1662015324386007808 +1662015324431008768 +1662015324473009664 +1662015324515010560 +1662015324560011520 +1662015324605012480 +1662015324653013504 +1662015324695014400 +1662015324740015360 +1662015324785016320 +1662015324827017216 +1662015324875018240 +1662015324917019136 +1662015324965020160 +1662015325013021184 +1662015325055022080 +1662015325100023040 +1662015325145024000 +1662015325190024960 +1662015325232025856 +1662015325274026752 +1662015325322027776 +1662015325367028736 +1662015325412029696 +1662015325457030656 +1662015325505031680 +1662015325547032576 +1662015325592033536 +1662015325634034432 +1662015325676035328 +1662015325718036224 +1662015325760037120 +1662015325805038080 +1662015325847038976 +1662015325889039872 +1662015325934040832 +1662015325985041920 +1662015326036043008 +1662015326084044032 +1662015326126044928 +1662015326177046016 +1662015326225047040 +1662015326276048128 +1662015326321049088 +1662015326363049984 +1662015326408050944 +1662015326453051904 +1662015326495052800 +1662015326537053696 +1662015326582054656 +1662015326627055616 +1662015326681056768 +1662015326723057664 +1662015326771058688 +1662015326813059584 +1662015326855060480 +1662015326897061376 +1662015326942062336 +1662015326987063296 +1662015327029064192 +1662015327074065152 +1662015327116066048 +1662015327161067008 +1662015327203067904 +1662015327245068800 +1662015327290069760 +1662015327335070720 +1662015327380071680 +1662015327419072512 +1662015327464073472 +1662015327509074432 +1662015327554075392 +1662015327596076288 +1662015327644077312 +1662015327686078208 +1662015327731079168 +1662015327776080128 +1662015327818081024 +1662015327863081984 +1662015327905082880 +1662015327950083840 +1662015327992084736 +1662015328034085632 +1662015328076086528 +1662015328118087424 +1662015328163088384 +1662015328205089280 +1662015328247090176 +1662015328292091136 +1662015328334092032 +1662015328376092928 +1662015328418093824 +1662015328457094656 +1662015328499095552 +1662015328544096512 +1662015328589097472 +1662015328634098432 +1662015328682099456 +1662015328724100352 +1662015328775101440 +1662015328820102400 +1662015328868103424 +1662015328907104256 +1662015328955105280 +1662015329012106496 +1662015329066107648 +1662015329108108544 +1662015329153109504 +1662015329198110464 +1662015329243111424 +1662015329288112384 +1662015329336113408 +1662015329378114304 +1662015329423115264 +1662015329468116224 +1662015329513117184 +1662015329555118080 +1662015329597118976 +1662015329639119872 +1662015329681120768 +1662015329726121728 +1662015329771122688 +1662015329816123648 +1662015329861124608 +1662015329906125568 +1662015329948126464 +1662015329996127488 +1662015330044128512 +1662015330086129408 +1662015330134130432 +1662015330185131520 +1662015330227132416 +1662015330272133376 +1662015330320134400 +1662015330368135424 +1662015330413136384 +1662015330458137344 +1662015330506138368 +1662015330548139264 +1662015330596140288 +1662015330638141184 +1662015330683142144 +1662015330725143040 +1662015330770144000 +1662015330815144960 +1662015330857145856 +1662015330914147072 +1662015330959148032 +1662015331010149120 +1662015331049149952 +1662015331094150912 +1662015331136151808 +1662015331178152704 +1662015331223153664 +1662015331265154560 +1662015331310155520 +1662015331355156480 +1662015331397157376 +1662015331442158336 +1662015331487159296 +1662015331529160192 +1662015331571161088 +1662015331619162112 +1662015331667163136 +1662015331709164032 +1662015331751164928 +1662015331796165888 +1662015331847166976 +1662015331895168000 +1662015331940168960 +1662015331994170112 +1662015332039171072 +1662015332081171968 +1662015332123172864 +1662015332165173760 +1662015332213174784 +1662015332255175680 +1662015332300176640 +1662015332342177536 +1662015332384178432 +1662015332432179456 +1662015332477180416 +1662015332525181440 +1662015332567182336 +1662015332609183232 +1662015332654184192 +1662015332699185152 +1662015332747186176 +1662015332792187136 +1662015332837188096 +1662015332885189120 +1662015332930190080 +1662015332972190976 +1662015333017191936 +1662015333065192960 +1662015333107193856 +1662015333149194752 +1662015333191195648 +1662015333242196736 +1662015333293197824 +1662015333335198720 +1662015333380199680 +1662015333422200576 +1662015333470201600 +1662015333515202560 +1662015333557203456 +1662015333602204416 +1662015333647205376 +1662015333689206272 +1662015333734207232 +1662015333776208128 +1662015333821209088 +1662015333863209984 +1662015333905210880 +1662015333947211776 +1662015333992212736 +1662015334037213696 +1662015334082214656 +1662015334124215552 +1662015334169216512 +1662015334214217472 +1662015334259218432 +1662015334301219328 +1662015334343220224 +1662015334385221120 +1662015334427222016 +1662015334472222976 +1662015334520224000 +1662015334559224832 +1662015334604225792 +1662015334649226752 +1662015334694227712 +1662015334739228672 +1662015334781229568 +1662015334826230528 +1662015334874231552 +1662015334925232640 +1662015334967233536 +1662015335018234624 +1662015335063235584 +1662015335111236608 +1662015335153237504 +1662015335195238400 +1662015335240239360 +1662015335285240320 +1662015335330241280 +1662015335369242112 +1662015335423243264 +1662015335465244160 +1662015335507245056 +1662015335552246016 +1662015335597246976 +1662015335639247872 +1662015335690248960 +1662015335735249920 +1662015335774250752 +1662015335822251776 +1662015335864252672 +1662015335909253632 +1662015335957254656 +1662015336005255680 +1662015336047256576 +1662015336101257728 +1662015336149258752 +1662015336191259648 +1662015336233260544 +1662015336275261440 +1662015336317262336 +1662015336365263360 +1662015336407264256 +1662015336449265152 +1662015336497266176 +1662015336536267008 +1662015336581267968 +1662015336626268928 +1662015336671269888 +1662015336716270848 +1662015336767271936 +1662015336812272896 +1662015336857273856 +1662015336902274816 +1662015336950275840 +1662015336992276736 +1662015337034277632 +1662015337076278528 +1662015337118279424 +1662015337163280384 +1662015337208281344 +1662015337250282240 +1662015337295283200 +1662015337343284224 +1662015337385285120 +1662015337427286016 +1662015337469286912 +1662015337517287936 +1662015337568289024 +1662015337610289920 +1662015337652290816 +1662015337694291712 +1662015337733292544 +1662015337778293504 +1662015337826294528 +1662015337871295488 +1662015337913296384 +1662015337958297344 +1662015338000298240 +1662015338042299136 +1662015338087300096 +1662015338135301120 +1662015338177302016 +1662015338219302912 +1662015338258303744 +1662015338300304640 +1662015338345305600 +1662015338396306688 +1662015338438307584 +1662015338474308352 +1662015338519309312 +1662015338561310208 +1662015338606311168 +1662015338645312000 +1662015338687312896 +1662015338732313856 +1662015338774314752 +1662015338816315648 +1662015338858316544 +1662015338900317440 +1662015338942318336 +1662015338984319232 +1662015339026320128 +1662015339068321024 +1662015339113321984 +1662015339161323008 +1662015339206323968 +1662015339248324864 +1662015339296325888 +1662015339338326784 +1662015339380327680 +1662015339422328576 +1662015339467329536 +1662015339509330432 +1662015339551331328 +1662015339596332288 +1662015339641333248 +1662015339686334208 +1662015339728335104 +1662015339770336000 +1662015339809336832 +1662015339857337856 +1662015339902338816 +1662015339944339712 +1662015339986340608 +1662015340028341504 +1662015340079342592 +1662015340121343488 +1662015340163344384 +1662015340205345280 +1662015340259346432 +1662015340301347328 +1662015340346348288 +1662015340388349184 +1662015340433350144 +1662015340475351040 +1662015340520352000 +1662015340565352960 +1662015340613353984 +1662015340655354880 +1662015340697355776 +1662015340745356800 +1662015340793357824 +1662015340835358720 +1662015340874359552 +1662015340919360512 +1662015340964361472 +1662015341006362368 +1662015341051363328 +1662015341093364224 +1662015341141365248 +1662015341183366144 +1662015341225367040 +1662015341270368000 +1662015341312368896 +1662015341354369792 +1662015341399370752 +1662015341438371584 +1662015341480372480 +1662015341525373440 +1662015341570374400 +1662015341615375360 +1662015341663376384 +1662015341705377280 +1662015341750378240 +1662015341798379264 +1662015341840380160 +1662015341882381056 +1662015341930382080 +1662015341969382912 +1662015342011383808 +1662015342053384704 +1662015342095385600 +1662015342140386560 +1662015342185387520 +1662015342230388480 +1662015342278389504 +1662015342326390528 +1662015342371391488 +1662015342416392448 +1662015342458393344 +1662015342500394240 +1662015342539395072 +1662015342581395968 +1662015342632397056 +1662015342674397952 +1662015342716398848 +1662015342764399872 +1662015342803400704 +1662015342845401600 +1662015342884402432 +1662015342926403328 +1662015342968404224 +1662015343013405184 +1662015343055406080 +1662015343097406976 +1662015343148408064 +1662015343193409024 +1662015343238409984 +1662015343286411008 +1662015343331411968 +1662015343373412864 +1662015343418413824 +1662015343466414848 +1662015343511415808 +1662015343553416704 +1662015343595417600 +1662015343637418496 +1662015343685419520 +1662015343727420416 +1662015343772421376 +1662015343823422464 +1662015343865423360 +1662015343907424256 +1662015343952425216 +1662015343997426176 +1662015344039427072 +1662015344084428032 +1662015344129428992 +1662015344177430016 +1662015344219430912 +1662015344264431872 +1662015344315432960 +1662015344357433856 +1662015344405434880 +1662015344447435776 +1662015344495436800 +1662015344537437696 +1662015344585438720 +1662015344627439616 +1662015344672440576 +1662015344717441536 +1662015344759442432 +1662015344810443520 +1662015344855444480 +1662015344894445312 +1662015344939446272 +1662015344987447296 +1662015345029448192 +1662015345074449152 +1662015345119450112 +1662015345161451008 +1662015345206451968 +1662015345248452864 +1662015345296453888 +1662015345338454784 +1662015345380455680 +1662015345428456704 +1662015345476457728 +1662015345521458688 +1662015345560459520 +1662015345608460544 +1662015345656461568 +1662015345695462400 +1662015345737463296 +1662015345779464192 +1662015345824465152 +1662015345866466048 +1662015345914467072 +1662015345956467968 +1662015346001468928 +1662015346052470016 +1662015346094470912 +1662015346136471808 +1662015346184472832 +1662015346229473792 +1662015346277474816 +1662015346322475776 +1662015346364476672 +1662015346406477568 +1662015346448478464 +1662015346490479360 +1662015346535480320 +1662015346577481216 +1662015346622482176 +1662015346661483008 +1662015346706483968 +1662015346748484864 +1662015346790485760 +1662015346835486720 +1662015346883487744 +1662015346922488576 +1662015346964489472 +1662015347009490432 +1662015347051491328 +1662015347093492224 +1662015347138493184 +1662015347180494080 +1662015347222494976 +1662015347270496000 +1662015347315496960 +1662015347354497792 +1662015347396498688 +1662015347438499584 +1662015347483500544 +1662015347525501440 +1662015347567502336 +1662015347609503232 +1662015347663504384 +1662015347705505280 +1662015347750506240 +1662015347798507264 +1662015347840508160 +1662015347885509120 +1662015347933510144 +1662015347975511040 +1662015348017511936 +1662015348062512896 +1662015348107513856 +1662015348155514880 +1662015348197515776 +1662015348239516672 +1662015348284517632 +1662015348332518656 +1662015348377519616 +1662015348419520512 +1662015348464521472 +1662015348509522432 +1662015348557523456 +1662015348602524416 +1662015348644525312 +1662015348683526144 +1662015348725527040 +1662015348770528000 +1662015348812528896 +1662015348854529792 +1662015348899530752 +1662015348944531712 +1662015348992532736 +1662015349034533632 +1662015349076534528 +1662015349121535488 +1662015349163536384 +1662015349205537280 +1662015349247538176 +1662015349292539136 +1662015349343540224 +1662015349391541248 +1662015349433542144 +1662015349475543040 +1662015349517543936 +1662015349562544896 +1662015349604545792 +1662015349649546752 +1662015349694547712 +1662015349739548672 +1662015349781549568 +1662015349826550528 +1662015349865551360 +1662015349907552256 +1662015349949553152 +1662015349994554112 +1662015350045555200 +1662015350090556160 +1662015350135557120 +1662015350177558016 +1662015350219558912 +1662015350255559680 +1662015350297560576 +1662015350339561472 +1662015350387562496 +1662015350438563584 +1662015350480564480 +1662015350522565376 +1662015350564566272 +1662015350606567168 +1662015350651568128 +1662015350693569024 +1662015350738569984 +1662015350786571008 +1662015350831571968 +1662015350873572864 +1662015350918573824 +1662015350963574784 +1662015351005575680 +1662015351050576640 +1662015351095577600 +1662015351140578560 +1662015351182579456 +1662015351224580352 +1662015351269581312 +1662015351314582272 +1662015351359583232 +1662015351398584064 +1662015351443585024 +1662015351488585984 +1662015351530586880 +1662015351575587840 +1662015351626588928 +1662015351668589824 +1662015351716590848 +1662015351767591936 +1662015351809592832 +1662015351857593856 +1662015351905594880 +1662015351950595840 +1662015351992596736 +1662015352037597696 +1662015352082598656 +1662015352127599616 +1662015352166600448 +1662015352214601472 +1662015352256602368 +1662015352298603264 +1662015352340604160 +1662015352373604864 +1662015352412605696 +1662015352454606592 +1662015352499607552 +1662015352544608512 +1662015352592609536 +1662015352637610496 +1662015352679611392 +1662015352724612352 +1662015352769613312 +1662015352814614272 +1662015352859615232 +1662015352901616128 +1662015352949617152 +1662015352994618112 +1662015353036619008 +1662015353081619968 +1662015353126620928 +1662015353174621952 +1662015353219622912 +1662015353264623872 +1662015353309624832 +1662015353351625728 +1662015353396626688 +1662015353438627584 +1662015353483628544 +1662015353525629440 +1662015353564630272 +1662015353606631168 +1662015353648632064 +1662015353690632960 +1662015353738633984 +1662015353780634880 +1662015353822635776 +1662015353861636608 +1662015353909637632 +1662015353954638592 +1662015353993639424 +1662015354035640320 +1662015354083641344 +1662015354122642176 +1662015354164643072 +1662015354209644032 +1662015354251644928 +1662015354299645952 +1662015354341646848 +1662015354380647680 +1662015354425648640 +1662015354470649600 +1662015354512650496 +1662015354554651392 +1662015354599652352 +1662015354647653376 +1662015354689654272 +1662015354731655168 +1662015354779656192 +1662015354824657152 +1662015354863657984 +1662015354911659008 +1662015354953659904 +1662015354992660736 +1662015355037661696 +1662015355085662720 +1662015355130663680 +1662015355172664576 +1662015355217665536 +1662015355259666432 +1662015355301667328 +1662015355343668224 +1662015355388669184 +1662015355433670144 +1662015355475671040 +1662015355520672000 +1662015355565672960 +1662015355604673792 +1662015355649674752 +1662015355691675648 +1662015355739676672 +1662015355781677568 +1662015355823678464 +1662015355865679360 +1662015355907680256 +1662015355949681152 +1662015355997682176 +1662015356042683136 +1662015356087684096 +1662015356129684992 +1662015356174685952 +1662015356216686848 +1662015356261687808 +1662015356303688704 +1662015356351689728 +1662015356399690752 +1662015356441691648 +1662015356480692480 +1662015356522693376 +1662015356564694272 +1662015356612695296 +1662015356654696192 +1662015356699697152 +1662015356741698048 +1662015356783698944 +1662015356828699904 +1662015356864700672 +1662015356906701568 +1662015356951702528 +1662015356993703424 +1662015357035704320 +1662015357083705344 +1662015357128706304 +1662015357170707200 +1662015357212708096 +1662015357254708992 +1662015357293709824 +1662015357338710784 +1662015357383711744 +1662015357428712704 +1662015357482713856 +1662015357524714752 +1662015357566715648 +1662015357611716608 +1662015357659717632 +1662015357704718592 +1662015357746719488 +1662015357794720512 +1662015357836721408 +1662015357884722432 +1662015357929723392 +1662015357971724288 +1662015358013725184 +1662015358058726144 +1662015358103727104 +1662015358145728000 +1662015358187728896 +1662015358241730048 +1662015358280730880 +1662015358325731840 +1662015358367732736 +1662015358409733632 +1662015358451734528 +1662015358493735424 +1662015358544736512 +1662015358586737408 +1662015358631738368 +1662015358676739328 +1662015358718740224 +1662015358763741184 +1662015358811742208 +1662015358853743104 +1662015358895744000 +1662015358943745024 +1662015358988745984 +1662015359036747008 +1662015359078747904 +1662015359123748864 +1662015359165749760 +1662015359207750656 +1662015359246751488 +1662015359294752512 +1662015359336753408 +1662015359381754368 +1662015359423755264 +1662015359462756096 +1662015359504756992 +1662015359546757888 +1662015359588758784 +1662015359630759680 +1662015359675760640 +1662015359714761472 +1662015359756762368 +1662015359798763264 +1662015359843764224 +1662015359888765184 +1662015359927766016 +1662015359969766912 +1662015360011767808 +1662015360053768704 +1662015360098769664 +1662015360143770624 +1662015360185771520 +1662015360230772480 +1662015360275773440 +1662015360320774400 +1662015360371775488 +1662015360413776384 +1662015360452777216 +1662015360503778304 +1662015360542779136 +1662015360590780160 +1662015360635781120 +1662015360680782080 +1662015360722782976 +1662015360767783936 +1662015360812784896 +1662015360863785984 +1662015360905786880 +1662015360947787776 +1662015360989788672 +1662015361037789696 +1662015361079790592 +1662015361121791488 +1662015361169792512 +1662015361214793472 +1662015361259794432 +1662015361301795328 +1662015361346796288 +1662015361394797312 +1662015361436798208 +1662015361478799104 +1662015361520800000 +1662015361571801088 +1662015361613801984 +1662015361658802944 +1662015361700803840 +1662015361751804928 +1662015361793805824 +1662015361838806784 +1662015361880807680 +1662015361922808576 +1662015361967809536 +1662015362012810496 +1662015362054811392 +1662015362099812352 +1662015362144813312 +1662015362189814272 +1662015362234815232 +1662015362279816192 +1662015362321817088 +1662015362363817984 +1662015362408818944 +1662015362444819712 +1662015362480820480 +1662015362522821376 +1662015362567822336 +1662015362612823296 +1662015362654824192 +1662015362702825216 +1662015362744826112 +1662015362792827136 +1662015362840828160 +1662015362885829120 +1662015362927830016 +1662015362969830912 +1662015363014831872 +1662015363056832768 +1662015363098833664 +1662015363140834560 +1662015363185835520 +1662015363230836480 +1662015363269837312 +1662015363311838208 +1662015363353839104 +1662015363401840128 +1662015363446841088 +1662015363494842112 +1662015363536843008 +1662015363581843968 +1662015363623844864 +1662015363665845760 +1662015363716846848 +1662015363758847744 +1662015363800848640 +1662015363842849536 +1662015363884850432 +1662015363926851328 +1662015363971852288 +1662015364016853248 +1662015364061854208 +1662015364106855168 +1662015364151856128 +1662015364196857088 +1662015364241858048 +1662015364283858944 +1662015364325859840 +1662015364370860800 +1662015364421861888 +1662015364469862912 +1662015364508863744 +1662015364556864768 +1662015364601865728 +1662015364643866624 +1662015364685867520 +1662015364730868480 +1662015364778869504 +1662015364823870464 +1662015364865871360 +1662015364904872192 +1662015364946873088 +1662015364991874048 +1662015365042875136 +1662015365087876096 +1662015365129876992 +1662015365177878016 +1662015365225879040 +1662015365267879936 +1662015365315880960 +1662015365357881856 +1662015365399882752 +1662015365441883648 +1662015365483884544 +1662015365525885440 +1662015365570886400 +1662015365612887296 +1662015365657888256 +1662015365696889088 +1662015365741890048 +1662015365783890944 +1662015365828891904 +1662015365870892800 +1662015365915893760 +1662015365960894720 +1662015366002895616 +1662015366050896640 +1662015366092897536 +1662015366137898496 +1662015366179899392 +1662015366224900352 +1662015366266901248 +1662015366314902272 +1662015366359903232 +1662015366407904256 +1662015366449905152 +1662015366503906304 +1662015366545907200 +1662015366590908160 +1662015366635909120 +1662015366680910080 +1662015366722910976 +1662015366773912064 +1662015366818913024 +1662015366863913984 +1662015366914915072 +1662015366959916032 +1662015367004916992 +1662015367046917888 +1662015367091918848 +1662015367145920000 +1662015367190920960 +1662015367232921856 +1662015367274922752 +1662015367319923712 +1662015367364924672 +1662015367409925632 +1662015367451926528 +1662015367496927488 +1662015367538928384 +1662015367583929344 +1662015367628930304 +1662015367667931136 +1662015367712932096 +1662015367757933056 +1662015367799933952 +1662015367841934848 +1662015367880935680 +1662015367922936576 +1662015367970937600 +1662015368012938496 +1662015368054939392 +1662015368099940352 +1662015368144941312 +1662015368183942144 +1662015368228943104 +1662015368273944064 +1662015368315944960 +1662015368360945920 +1662015368402946816 +1662015368453947904 +1662015368495948800 +1662015368537949696 +1662015368579950592 +1662015368627951616 +1662015368672952576 +1662015368723953664 +1662015368768954624 +1662015368816955648 +1662015368861956608 +1662015368900957440 +1662015368948958464 +1662015368990959360 +1662015369035960320 +1662015369077961216 +1662015369119962112 +1662015369158962944 +1662015369200963840 +1662015369242964736 +1662015369284965632 +1662015369329966592 +1662015369377967616 +1662015369419968512 +1662015369461969408 +1662015369509970432 +1662015369560971520 +1662015369602972416 +1662015369641973248 +1662015369686974208 +1662015369725975040 +1662015369770976000 +1662015369809976832 +1662015369854977792 +1662015369896978688 +1662015369935979520 +1662015369977980416 +1662015370022981376 +1662015370064982272 +1662015370103983104 +1662015370151984128 +1662015370196985088 +1662015370238985984 +1662015370280986880 +1662015370322987776 +1662015370373988864 +1662015370415989760 +1662015370457990656 +1662015370502991616 +1662015370547992576 +1662015370592993536 +1662015370640994560 +1662015370682995456 +1662015370724996352 +1662015370775997440 +1662015370820998400 +1662015370862999296 +1662015370908000256 +1662015370950001152 +1662015370995002112 +1662015371040003072 +1662015371085004032 +1662015371133005056 +1662015371172005888 +1662015371214006784 +1662015371256007680 +1662015371298008576 +1662015371340009472 +1662015371385010432 +1662015371430011392 +1662015371478012416 +1662015371526013440 +1662015371571014400 +1662015371616015360 +1662015371661016320 +1662015371703017216 +1662015371742018048 +1662015371781018880 +1662015371826019840 +1662015371865020672 +1662015371913021696 +1662015371958022656 +1662015372003023616 +1662015372045024512 +1662015372087025408 +1662015372129026304 +1662015372177027328 +1662015372216028160 +1662015372258029056 +1662015372303030016 +1662015372345030912 +1662015372384031744 +1662015372438032896 +1662015372483033856 +1662015372525034752 +1662015372570035712 +1662015372615036672 +1662015372660037632 +1662015372702038528 +1662015372747039488 +1662015372792040448 +1662015372834041344 +1662015372876042240 +1662015372915043072 +1662015372960044032 +1662015373005044992 +1662015373047045888 +1662015373089046784 +1662015373134047744 +1662015373179048704 +1662015373227049728 +1662015373278050816 +1662015373323051776 +1662015373368052736 +1662015373416053760 +1662015373464054784 +1662015373512055808 +1662015373557056768 +1662015373590057472 +1662015373635058432 +1662015373677059328 +1662015373722060288 +1662015373770061312 +1662015373812062208 +1662015373854063104 +1662015373896064000 +1662015373941064960 +1662015373986065920 +1662015374028066816 +1662015374070067712 +1662015374112068608 +1662015374157069568 +1662015374199070464 +1662015374244071424 +1662015374292072448 +1662015374334073344 +1662015374373074176 +1662015374415075072 +1662015374460076032 +1662015374511077120 +1662015374553078016 +1662015374595078912 +1662015374643079936 +1662015374697081088 +1662015374742082048 +1662015374784082944 +1662015374823083776 +1662015374868084736 +1662015374913085696 +1662015374958086656 +1662015375003087616 +1662015375045088512 +1662015375087089408 +1662015375129090304 +1662015375180091392 +1662015375225092352 +1662015375276093440 +1662015375315094272 +1662015375360095232 +1662015375402096128 +1662015375453097216 +1662015375498098176 +1662015375549099264 +1662015375591100160 +1662015375636101120 +1662015375678102016 +1662015375720102912 +1662015375765103872 +1662015375813104896 +1662015375858105856 +1662015375903106816 +1662015375948107776 +1662015375996108800 +1662015376038109696 +1662015376080110592 +1662015376119111424 +1662015376167112448 +1662015376209113344 +1662015376257114368 +1662015376305115392 +1662015376347116288 +1662015376392117248 +1662015376434118144 +1662015376479119104 +1662015376524120064 +1662015376569121024 +1662015376614121984 +1662015376656122880 +1662015376707123968 +1662015376752124928 +1662015376803126016 +1662015376848126976 +1662015376893127936 +1662015376938128896 +1662015376980129792 +1662015377028130816 +1662015377073131776 +1662015377115132672 +1662015377154133504 +1662015377196134400 +1662015377238135296 +1662015377286136320 +1662015377337137408 +1662015377379138304 +1662015377424139264 +1662015377466140160 +1662015377514141184 +1662015377556142080 +1662015377604143104 +1662015377649144064 +1662015377694145024 +1662015377739145984 +1662015377781146880 +1662015377823147776 +1662015377868148736 +1662015377907149568 +1662015377949150464 +1662015377991151360 +1662015378036152320 +1662015378081153280 +1662015378120154112 +1662015378165155072 +1662015378207155968 +1662015378249156864 +1662015378285157632 +1662015378327158528 +1662015378366159360 +1662015378408160256 +1662015378456161280 +1662015378495162112 +1662015378546163200 +1662015378591164160 +1662015378636165120 +1662015378684166144 +1662015378726167040 +1662015378768167936 +1662015378813168896 +1662015378855169792 +1662015378894170624 +1662015378936171520 +1662015378978172416 +1662015379023173376 +1662015379065174272 +1662015379107175168 +1662015379149176064 +1662015379194177024 +1662015379236177920 +1662015379278178816 +1662015379323179776 +1662015379365180672 +1662015379419181824 +1662015379461182720 +1662015379500183552 +1662015379542184448 +1662015379584185344 +1662015379629186304 +1662015379680187392 +1662015379722188288 +1662015379767189248 +1662015379812190208 +1662015379854191104 +1662015379896192000 +1662015379941192960 +1662015379989193984 +1662015380037195008 +1662015380082195968 +1662015380130196992 +1662015380175197952 +1662015380220198912 +1662015380265199872 +1662015380313200896 +1662015380355201792 +1662015380397202688 +1662015380439203584 +1662015380481204480 +1662015380526205440 +1662015380568206336 +1662015380616207360 +1662015380658208256 +1662015380706209280 +1662015380760210432 +1662015380805211392 +1662015380853212416 +1662015380895213312 +1662015380937214208 +1662015380982215168 +1662015381027216128 +1662015381078217216 +1662015381120218112 +1662015381162219008 +1662015381204219904 +1662015381246220800 +1662015381288221696 +1662015381333222656 +1662015381378223616 +1662015381423224576 +1662015381468225536 +1662015381513226496 +1662015381558227456 +1662015381600228352 +1662015381639229184 +1662015381681230080 +1662015381723230976 +1662015381768231936 +1662015381816232960 +1662015381861233920 +1662015381903234816 +1662015381945235712 +1662015381990236672 +1662015382038237696 +1662015382086238720 +1662015382134239744 +1662015382182240768 +1662015382230241792 +1662015382278242816 +1662015382323243776 +1662015382365244672 +1662015382407245568 +1662015382458246656 +1662015382500247552 +1662015382545248512 +1662015382581249280 +1662015382623250176 +1662015382662251008 +1662015382713252096 +1662015382755252992 +1662015382797253888 +1662015382839254784 +1662015382878255616 +1662015382923256576 +1662015382965257472 +1662015383007258368 +1662015383052259328 +1662015383097260288 +1662015383145261312 +1662015383193262336 +1662015383238263296 +1662015383277264128 +1662015383319265024 +1662015383364265984 +1662015383409266944 +1662015383454267904 +1662015383496268800 +1662015383541269760 +1662015383583270656 +1662015383631271680 +1662015383676272640 +1662015383718273536 +1662015383763274496 +1662015383808275456 +1662015383850276352 +1662015383892277248 +1662015383934278144 +1662015383985279232 +1662015384024280064 +1662015384066280960 +1662015384108281856 +1662015384153282816 +1662015384198283776 +1662015384246284800 +1662015384288285696 +1662015384336286720 +1662015384381287680 +1662015384423288576 +1662015384465289472 +1662015384507290368 +1662015384558291456 +1662015384603292416 +1662015384642293248 +1662015384687294208 +1662015384732295168 +1662015384789296384 +1662015384831297280 +1662015384879298304 +1662015384921299200 +1662015384963300096 +1662015385005300992 +1662015385047301888 +1662015385089302784 +1662015385131303680 +1662015385176304640 +1662015385218305536 +1662015385263306496 +1662015385305307392 +1662015385347308288 +1662015385392309248 +1662015385434310144 +1662015385476311040 +1662015385518311936 +1662015385563312896 +1662015385608313856 +1662015385653314816 +1662015385710316032 +1662015385755316992 +1662015385797317888 +1662015385839318784 +1662015385884319744 +1662015385929320704 +1662015385974321664 +1662015386022322688 +1662015386061323520 +1662015386103324416 +1662015386145325312 +1662015386187326208 +1662015386229327104 +1662015386274328064 +1662015386322329088 +1662015386370330112 +1662015386412331008 +1662015386457331968 +1662015386502332928 +1662015386547333888 +1662015386595334912 +1662015386637335808 +1662015386688336896 +1662015386733337856 +1662015386778338816 +1662015386820339712 +1662015386868340736 +1662015386916341760 +1662015386961342720 +1662015387003343616 +1662015387048344576 +1662015387093345536 +1662015387141346560 +1662015387186347520 +1662015387228348416 +1662015387282349568 +1662015387330350592 +1662015387366351360 +1662015387408352256 +1662015387447353088 +1662015387489353984 +1662015387534354944 +1662015387579355904 +1662015387627356928 +1662015387669357824 +1662015387714358784 +1662015387759359744 +1662015387804360704 +1662015387858361856 +1662015387900362752 +1662015387945363712 +1662015387987364608 +1662015388029365504 +1662015388071366400 +1662015388119367424 +1662015388164368384 +1662015388209369344 +1662015388251370240 +1662015388293371136 +1662015388332371968 +1662015388374372864 +1662015388419373824 +1662015388464374784 +1662015388506375680 +1662015388548376576 +1662015388593377536 +1662015388644378624 +1662015388689379584 +1662015388731380480 +1662015388776381440 +1662015388818382336 +1662015388860383232 +1662015388905384192 +1662015388944385024 +1662015388992386048 +1662015389040387072 +1662015389082387968 +1662015389124388864 +1662015389163389696 +1662015389205390592 +1662015389247391488 +1662015389295392512 +1662015389337393408 +1662015389382394368 +1662015389424395264 +1662015389466396160 +1662015389508397056 +1662015389556398080 +1662015389598398976 +1662015389643399936 +1662015389682400768 +1662015389724401664 +1662015389766402560 +1662015389814403584 +1662015389859404544 +1662015389904405504 +1662015389940406272 +1662015389979407104 +1662015390021408000 +1662015390072409088 +1662015390120410112 +1662015390162411008 +1662015390210412032 +1662015390255412992 +1662015390300413952 +1662015390342414848 +1662015390384415744 +1662015390429416704 +1662015390468417536 +1662015390510418432 +1662015390555419392 +1662015390597420288 +1662015390639421184 +1662015390684422144 +1662015390726423040 +1662015390771424000 +1662015390813424896 +1662015390855425792 +1662015390897426688 +1662015390936427520 +1662015390978428416 +1662015391020429312 +1662015391062430208 +1662015391104431104 +1662015391152432128 +1662015391194433024 +1662015391236433920 +1662015391278434816 +1662015391326435840 +1662015391371436800 +1662015391416437760 +1662015391461438720 +1662015391503439616 +1662015391545440512 +1662015391587441408 +1662015391632442368 +1662015391677443328 +1662015391722444288 +1662015391764445184 +1662015391806446080 +1662015391848446976 +1662015391890447872 +1662015391932448768 +1662015391974449664 +1662015392019450624 +1662015392070451712 +1662015392112452608 +1662015392160453632 +1662015392202454528 +1662015392247455488 +1662015392289456384 +1662015392334457344 +1662015392379458304 +1662015392424459264 +1662015392469460224 +1662015392520461312 +1662015392562462208 +1662015392607463168 +1662015392652464128 +1662015392694465024 +1662015392739465984 +1662015392784466944 +1662015392829467904 +1662015392877468928 +1662015392916469760 +1662015392955470592 +1662015392997471488 +1662015393054472704 +1662015393102473728 +1662015393147474688 +1662015393192475648 +1662015393240476672 +1662015393282477568 +1662015393324478464 +1662015393372479488 +1662015393423480576 +1662015393468481536 +1662015393510482432 +1662015393552483328 +1662015393597484288 +1662015393642485248 +1662015393690486272 +1662015393732487168 +1662015393771488000 +1662015393819489024 +1662015393864489984 +1662015393906490880 +1662015393948491776 +1662015393993492736 +1662015394038493696 +1662015394089494784 +1662015394131495680 +1662015394173496576 +1662015394218497536 +1662015394260498432 +1662015394302499328 +1662015394347500288 +1662015394392501248 +1662015394434502144 +1662015394479503104 +1662015394521504000 +1662015394566504960 +1662015394608505856 +1662015394653506816 +1662015394698507776 +1662015394746508800 +1662015394788509696 +1662015394833510656 +1662015394878511616 +1662015394923512576 +1662015394965513472 +1662015395010514432 +1662015395061515520 +1662015395097516288 +1662015395139517184 +1662015395181518080 +1662015395223518976 +1662015395274520064 +1662015395316520960 +1662015395367522048 +1662015395409522944 +1662015395454523904 +1662015395499524864 +1662015395550525952 +1662015395589526784 +1662015395631527680 +1662015395679528704 +1662015395724529664 +1662015395766530560 +1662015395814531584 +1662015395856532480 +1662015395898533376 +1662015395943534336 +1662015395991535360 +1662015396036536320 +1662015396078537216 +1662015396126538240 +1662015396168539136 +1662015396216540160 +1662015396264541184 +1662015396309542144 +1662015396357543168 +1662015396399544064 +1662015396447545088 +1662015396492546048 +1662015396540547072 +1662015396582547968 +1662015396627548928 +1662015396675549952 +1662015396720550912 +1662015396765551872 +1662015396807552768 +1662015396852553728 +1662015396894554624 +1662015396939555584 +1662015396987556608 +1662015397020557312 +1662015397068558336 +1662015397116559360 +1662015397161560320 +1662015397203561216 +1662015397248562176 +1662015397287563008 +1662015397332563968 +1662015397377564928 +1662015397416565760 +1662015397458566656 +1662015397503567616 +1662015397545568512 +1662015397584569344 +1662015397632570368 +1662015397677571328 +1662015397722572288 +1662015397767573248 +1662015397815574272 +1662015397860575232 +1662015397905576192 +1662015397953577216 +1662015397995578112 +1662015398040579072 +1662015398085580032 +1662015398130580992 +1662015398172581888 +1662015398217582848 +1662015398259583744 +1662015398301584640 +1662015398349585664 +1662015398391586560 +1662015398436587520 +1662015398481588480 +1662015398523589376 +1662015398568590336 +1662015398613591296 +1662015398655592192 +1662015398700593152 +1662015398742594048 +1662015398793595136 +1662015398835596032 +1662015398883597056 +1662015398928598016 +1662015398967598848 +1662015399009599744 +1662015399054600704 +1662015399102601728 +1662015399150602752 +1662015399198603776 +1662015399240604672 +1662015399282605568 +1662015399330606592 +1662015399375607552 +1662015399423608576 +1662015399465609472 +1662015399507610368 +1662015399552611328 +1662015399591612160 +1662015399636613120 +1662015399678614016 +1662015399723614976 +1662015399765615872 +1662015399819617024 +1662015399867618048 +1662015399921619200 +1662015399960620032 +1662015400005620992 +1662015400050621952 +1662015400098622976 +1662015400140623872 +1662015400182624768 +1662015400227625728 +1662015400272626688 +1662015400311627520 +1662015400353628416 +1662015400404629504 +1662015400446630400 +1662015400488631296 +1662015400530632192 +1662015400575633152 +1662015400617634048 +1662015400665635072 +1662015400710636032 +1662015400752636928 diff --git a/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_track2.txt b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_track2.txt new file mode 100644 index 0000000000..c35350d63a --- /dev/null +++ b/Examples/Monocular-Inertial/MIMIR_TimeStamps/SeaFloor_track2.txt @@ -0,0 +1,2537 @@ +1662122091767260928 +1662122091809261824 +1662122091851262720 +1662122091893263616 +1662122091935264512 +1662122091980265472 +1662122092022266368 +1662122092064267264 +1662122092106268160 +1662122092148269056 +1662122092193270016 +1662122092232270848 +1662122092280271872 +1662122092322272768 +1662122092364273664 +1662122092412274688 +1662122092454275584 +1662122092493276416 +1662122092535277312 +1662122092580278272 +1662122092625279232 +1662122092667280128 +1662122092709281024 +1662122092751281920 +1662122092796282880 +1662122092847283968 +1662122092889284864 +1662122092931285760 +1662122092970286592 +1662122093015287552 +1662122093060288512 +1662122093105289472 +1662122093153290496 +1662122093201291520 +1662122093240292352 +1662122093282293248 +1662122093324294144 +1662122093366295040 +1662122093408295936 +1662122093453296896 +1662122093501297920 +1662122093543298816 +1662122093591299840 +1662122093633300736 +1662122093675301632 +1662122093723302656 +1662122093768303616 +1662122093810304512 +1662122093855305472 +1662122093894306304 +1662122093939307264 +1662122093981308160 +1662122094023309056 +1662122094065309952 +1662122094110310912 +1662122094146311680 +1662122094191312640 +1662122094227313408 +1662122094275314432 +1662122094317315328 +1662122094359316224 +1662122094395316992 +1662122094437317888 +1662122094482318848 +1662122094524319744 +1662122094566320640 +1662122094611321600 +1662122094653322496 +1662122094695323392 +1662122094740324352 +1662122094782325248 +1662122094824326144 +1662122094872327168 +1662122094917328128 +1662122094965329152 +1662122095007330048 +1662122095052331008 +1662122095094331904 +1662122095139332864 +1662122095181333760 +1662122095220334592 +1662122095265335552 +1662122095316336640 +1662122095358337536 +1662122095406338560 +1662122095454339584 +1662122095496340480 +1662122095541341440 +1662122095586342400 +1662122095625343232 +1662122095667344128 +1662122095709345024 +1662122095751345920 +1662122095793346816 +1662122095835347712 +1662122095874348544 +1662122095916349440 +1662122095958350336 +1662122096000351232 +1662122096045352192 +1662122096084353024 +1662122096120353792 +1662122096162354688 +1662122096204355584 +1662122096243356416 +1662122096279357184 +1662122096327358208 +1662122096375359232 +1662122096417360128 +1662122096453360896 +1662122096495361792 +1662122096540362752 +1662122096585363712 +1662122096627364608 +1662122096669365504 +1662122096717366528 +1662122096759367424 +1662122096801368320 +1662122096843369216 +1662122096885370112 +1662122096924370944 +1662122096966371840 +1662122097005372672 +1662122097047373568 +1662122097089374464 +1662122097134375424 +1662122097179376384 +1662122097221377280 +1662122097263378176 +1662122097305379072 +1662122097347379968 +1662122097395380992 +1662122097437381888 +1662122097479382784 +1662122097521383680 +1662122097563384576 +1662122097605385472 +1662122097656386560 +1662122097704387584 +1662122097743388416 +1662122097785389312 +1662122097836390400 +1662122097881391360 +1662122097923392256 +1662122097968393216 +1662122098010394112 +1662122098052395008 +1662122098094395904 +1662122098136396800 +1662122098178397696 +1662122098226398720 +1662122098271399680 +1662122098316400640 +1662122098358401536 +1662122098397402368 +1662122098439403264 +1662122098481404160 +1662122098529405184 +1662122098577406208 +1662122098628407296 +1662122098670408192 +1662122098712409088 +1662122098757410048 +1662122098796410880 +1662122098841411840 +1662122098883412736 +1662122098922413568 +1662122098970414592 +1662122099012415488 +1662122099054416384 +1662122099096417280 +1662122099141418240 +1662122099183419136 +1662122099222419968 +1662122099267420928 +1662122099315421952 +1662122099360422912 +1662122099405423872 +1662122099450424832 +1662122099498425856 +1662122099537426688 +1662122099585427712 +1662122099624428544 +1662122099669429504 +1662122099711430400 +1662122099753431296 +1662122099798432256 +1662122099843433216 +1662122099888434176 +1662122099933435136 +1662122099969435904 +1662122100014436864 +1662122100056437760 +1662122100101438720 +1662122100146439680 +1662122100197440768 +1662122100236441600 +1662122100281442560 +1662122100323443456 +1662122100365444352 +1662122100410445312 +1662122100449446144 +1662122100494447104 +1662122100536448000 +1662122100578448896 +1662122100617449728 +1662122100659450624 +1662122100701451520 +1662122100743452416 +1662122100785453312 +1662122100824454144 +1662122100866455040 +1662122100908455936 +1662122100950456832 +1662122100992457728 +1662122101037458688 +1662122101079459584 +1662122101124460544 +1662122101160461312 +1662122101205462272 +1662122101244463104 +1662122101298464256 +1662122101340465152 +1662122101379465984 +1662122101421466880 +1662122101466467840 +1662122101514468864 +1662122101556469760 +1662122101601470720 +1662122101649471744 +1662122101694472704 +1662122101733473536 +1662122101784474624 +1662122101826475520 +1662122101865476352 +1662122101904477184 +1662122101949478144 +1662122101997479168 +1662122102042480128 +1662122102090481152 +1662122102129481984 +1662122102171482880 +1662122102213483776 +1662122102255484672 +1662122102297485568 +1662122102342486528 +1662122102384487424 +1662122102423488256 +1662122102465489152 +1662122102507490048 +1662122102546490880 +1662122102588491776 +1662122102627492608 +1662122102663493376 +1662122102705494272 +1662122102747495168 +1662122102789496064 +1662122102834497024 +1662122102876497920 +1662122102918498816 +1662122102960499712 +1662122103005500672 +1662122103044501504 +1662122103089502464 +1662122103131503360 +1662122103176504320 +1662122103221505280 +1662122103263506176 +1662122103308507136 +1662122103350508032 +1662122103392508928 +1662122103437509888 +1662122103479510784 +1662122103515511552 +1662122103557512448 +1662122103593513216 +1662122103635514112 +1662122103680515072 +1662122103725516032 +1662122103767516928 +1662122103809517824 +1662122103845518592 +1662122103887519488 +1662122103932520448 +1662122103974521344 +1662122104019522304 +1662122104061523200 +1662122104106524160 +1662122104148525056 +1662122104184525824 +1662122104223526656 +1662122104268527616 +1662122104310528512 +1662122104355529472 +1662122104397530368 +1662122104439531264 +1662122104478532096 +1662122104520532992 +1662122104562533888 +1662122104604534784 +1662122104646535680 +1662122104688536576 +1662122104730537472 +1662122104772538368 +1662122104814539264 +1662122104859540224 +1662122104904541184 +1662122104949542144 +1662122104988542976 +1662122105027543808 +1662122105072544768 +1662122105114545664 +1662122105159546624 +1662122105201547520 +1662122105243548416 +1662122105285549312 +1662122105327550208 +1662122105366551040 +1662122105408551936 +1662122105450552832 +1662122105489553664 +1662122105531554560 +1662122105573555456 +1662122105615556352 +1662122105657557248 +1662122105699558144 +1662122105747559168 +1662122105789560064 +1662122105834561024 +1662122105882562048 +1662122105924562944 +1662122105969563904 +1662122106008564736 +1662122106053565696 +1662122106092566528 +1662122106134567424 +1662122106173568256 +1662122106215569152 +1662122106251569920 +1662122106290570752 +1662122106326571520 +1662122106374572544 +1662122106416573440 +1662122106461574400 +1662122106506575360 +1662122106548576256 +1662122106584577024 +1662122106626577920 +1662122106665578752 +1662122106707579648 +1662122106752580608 +1662122106794581504 +1662122106836582400 +1662122106881583360 +1662122106923584256 +1662122106965585152 +1662122107007586048 +1662122107055587072 +1662122107097587968 +1662122107136588800 +1662122107172589568 +1662122107214590464 +1662122107259591424 +1662122107307592448 +1662122107349593344 +1662122107394594304 +1662122107433595136 +1662122107472595968 +1662122107517596928 +1662122107556597760 +1662122107598598656 +1662122107643599616 +1662122107682600448 +1662122107724601344 +1662122107769602304 +1662122107814603264 +1662122107862604288 +1662122107904605184 +1662122107949606144 +1662122107991607040 +1662122108030607872 +1662122108075608832 +1662122108117609728 +1662122108159610624 +1662122108207611648 +1662122108249612544 +1662122108291613440 +1662122108339614464 +1662122108387615488 +1662122108429616384 +1662122108471617280 +1662122108516618240 +1662122108558619136 +1662122108600620032 +1662122108642620928 +1662122108687621888 +1662122108729622784 +1662122108774623744 +1662122108816624640 +1662122108861625600 +1662122108909626624 +1662122108951627520 +1662122108990628352 +1662122109035629312 +1662122109083630336 +1662122109125631232 +1662122109164632064 +1662122109206632960 +1662122109245633792 +1662122109287634688 +1662122109332635648 +1662122109368636416 +1662122109410637312 +1662122109452638208 +1662122109491639040 +1662122109539640064 +1662122109587641088 +1662122109635642112 +1662122109674642944 +1662122109716643840 +1662122109761644800 +1662122109803645696 +1662122109845646592 +1662122109887647488 +1662122109929648384 +1662122109968649216 +1662122110010650112 +1662122110055651072 +1662122110097651968 +1662122110136652800 +1662122110178653696 +1662122110220654592 +1662122110265655552 +1662122110307656448 +1662122110352657408 +1662122110394658304 +1662122110436659200 +1662122110481660160 +1662122110526661120 +1662122110571662080 +1662122110613662976 +1662122110661664000 +1662122110703664896 +1662122110748665856 +1662122110793666816 +1662122110835667712 +1662122110880668672 +1662122110919669504 +1662122110970670592 +1662122111012671488 +1662122111054672384 +1662122111093673216 +1662122111138674176 +1662122111186675200 +1662122111225676032 +1662122111267676928 +1662122111309677824 +1662122111351678720 +1662122111393679616 +1662122111435680512 +1662122111477681408 +1662122111522682368 +1662122111570683392 +1662122111615684352 +1662122111657685248 +1662122111702686208 +1662122111747687168 +1662122111789688064 +1662122111834689024 +1662122111876689920 +1662122111918690816 +1662122111963691776 +1662122112005692672 +1662122112047693568 +1662122112089694464 +1662122112134695424 +1662122112182696448 +1662122112224697344 +1662122112266698240 +1662122112308699136 +1662122112353700096 +1662122112395700992 +1662122112434701824 +1662122112476702720 +1662122112521703680 +1662122112572704768 +1662122112617705728 +1662122112656706560 +1662122112698707456 +1662122112746708480 +1662122112788709376 +1662122112833710336 +1662122112875711232 +1662122112914712064 +1662122112953712896 +1662122112998713856 +1662122113037714688 +1662122113079715584 +1662122113118716416 +1662122113154717184 +1662122113196718080 +1662122113235718912 +1662122113277719808 +1662122113319720704 +1662122113355721472 +1662122113400722432 +1662122113448723456 +1662122113487724288 +1662122113529725184 +1662122113571726080 +1662122113613726976 +1662122113655727872 +1662122113700728832 +1662122113742729728 +1662122113784730624 +1662122113826731520 +1662122113871732480 +1662122113913733376 +1662122113958734336 +1662122114006735360 +1662122114048736256 +1662122114090737152 +1662122114132738048 +1662122114177739008 +1662122114222739968 +1662122114264740864 +1662122114309741824 +1662122114354742784 +1662122114396743680 +1662122114438744576 +1662122114489745664 +1662122114534746624 +1662122114579747584 +1662122114627748608 +1662122114669749504 +1662122114708750336 +1662122114750751232 +1662122114792752128 +1662122114837753088 +1662122114882754048 +1662122114921754880 +1662122114966755840 +1662122115008756736 +1662122115059757824 +1662122115110758912 +1662122115149759744 +1662122115194760704 +1662122115236761600 +1662122115278762496 +1662122115320763392 +1662122115365764352 +1662122115404765184 +1662122115446766080 +1662122115491767040 +1662122115533767936 +1662122115575768832 +1662122115620769792 +1662122115662770688 +1662122115707771648 +1662122115749772544 +1662122115788773376 +1662122115830774272 +1662122115875775232 +1662122115917776128 +1662122115959777024 +1662122115998777856 +1662122116043778816 +1662122116088779776 +1662122116136780800 +1662122116175781632 +1662122116217782528 +1662122116265783552 +1662122116307784448 +1662122116352785408 +1662122116394786304 +1662122116430787072 +1662122116475788032 +1662122116517788928 +1662122116562789888 +1662122116604790784 +1662122116643791616 +1662122116685792512 +1662122116727793408 +1662122116769794304 +1662122116811795200 +1662122116856796160 +1662122116901797120 +1662122116943798016 +1662122116985798912 +1662122117033799936 +1662122117075800832 +1662122117114801664 +1662122117153802496 +1662122117192803328 +1662122117240804352 +1662122117282805248 +1662122117324806144 +1662122117363806976 +1662122117408807936 +1662122117450808832 +1662122117495809792 +1662122117540810752 +1662122117582811648 +1662122117627812608 +1662122117669813504 +1662122117711814400 +1662122117759815424 +1662122117798816256 +1662122117846817280 +1662122117888818176 +1662122117933819136 +1662122117978820096 +1662122118023821056 +1662122118068822016 +1662122118113822976 +1662122118161824000 +1662122118206824960 +1662122118248825856 +1662122118287826688 +1662122118332827648 +1662122118374828544 +1662122118416829440 +1662122118461830400 +1662122118503831296 +1662122118548832256 +1662122118593833216 +1662122118638834176 +1662122118680835072 +1662122118722835968 +1662122118764836864 +1662122118806837760 +1662122118848838656 +1662122118890839552 +1662122118935840512 +1662122118977841408 +1662122119019842304 +1662122119061843200 +1662122119100844032 +1662122119145844992 +1662122119187845888 +1662122119226846720 +1662122119271847680 +1662122119319848704 +1662122119364849664 +1662122119403850496 +1662122119442851328 +1662122119484852224 +1662122119526853120 +1662122119571854080 +1662122119613854976 +1662122119652855808 +1662122119697856768 +1662122119739857664 +1662122119778858496 +1662122119823859456 +1662122119874860544 +1662122119922861568 +1662122119964862464 +1662122120009863424 +1662122120054864384 +1662122120096865280 +1662122120138866176 +1662122120180867072 +1662122120222867968 +1662122120270868992 +1662122120315869952 +1662122120360870912 +1662122120405871872 +1662122120450872832 +1662122120486873600 +1662122120525874432 +1662122120567875328 +1662122120609876224 +1662122120648877056 +1662122120690877952 +1662122120732878848 +1662122120777879808 +1662122120819880704 +1662122120858881536 +1662122120903882496 +1662122120948883456 +1662122120987884288 +1662122121023885056 +1662122121068886016 +1662122121110886912 +1662122121152887808 +1662122121194888704 +1662122121239889664 +1662122121281890560 +1662122121320891392 +1662122121365892352 +1662122121407893248 +1662122121449894144 +1662122121491895040 +1662122121536896000 +1662122121581896960 +1662122121626897920 +1662122121668898816 +1662122121710899712 +1662122121752900608 +1662122121797901568 +1662122121836902400 +1662122121878903296 +1662122121923904256 +1662122121968905216 +1662122122007906048 +1662122122049906944 +1662122122091907840 +1662122122136908800 +1662122122178909696 +1662122122223910656 +1662122122265911552 +1662122122307912448 +1662122122349913344 +1662122122394914304 +1662122122436915200 +1662122122481916160 +1662122122520916992 +1662122122568918016 +1662122122616919040 +1662122122661920000 +1662122122703920896 +1662122122745921792 +1662122122790922752 +1662122122832923648 +1662122122874924544 +1662122122913925376 +1662122122955926272 +1662122123000927232 +1662122123042928128 +1662122123087929088 +1662122123132930048 +1662122123171930880 +1662122123210931712 +1662122123249932544 +1662122123288933376 +1662122123330934272 +1662122123372935168 +1662122123414936064 +1662122123456936960 +1662122123498937856 +1662122123540938752 +1662122123579939584 +1662122123621940480 +1662122123663941376 +1662122123708942336 +1662122123753943296 +1662122123795944192 +1662122123837945088 +1662122123879945984 +1662122123918946816 +1662122123960947712 +1662122124005948672 +1662122124047949568 +1662122124092950528 +1662122124134951424 +1662122124179952384 +1662122124224953344 +1662122124266954240 +1662122124311955200 +1662122124359956224 +1662122124398957056 +1662122124440957952 +1662122124482958848 +1662122124530959872 +1662122124572960768 +1662122124617961728 +1662122124659962624 +1662122124701963520 +1662122124743964416 +1662122124788965376 +1662122124833966336 +1662122124878967296 +1662122124923968256 +1662122124968969216 +1662122125013970176 +1662122125058971136 +1662122125097971968 +1662122125139972864 +1662122125181973760 +1662122125226974720 +1662122125271975680 +1662122125310976512 +1662122125361977600 +1662122125400978432 +1662122125445979392 +1662122125493980416 +1662122125535981312 +1662122125583982336 +1662122125625983232 +1662122125670984192 +1662122125709985024 +1662122125751985920 +1662122125793986816 +1662122125835987712 +1662122125874988544 +1662122125916989440 +1662122125961990400 +1662122126003991296 +1662122126045992192 +1662122126087993088 +1662122126129993984 +1662122126171994880 +1662122126219995904 +1662122126264996864 +1662122126303997696 +1662122126351998720 +1662122126393999616 +1662122126436000512 +1662122126478001408 +1662122126523002368 +1662122126565003264 +1662122126601004032 +1662122126640004864 +1662122126685005824 +1662122126727006720 +1662122126769007616 +1662122126808008448 +1662122126850009344 +1662122126895010304 +1662122126940011264 +1662122126985012224 +1662122127021012992 +1662122127063013888 +1662122127105014784 +1662122127144015616 +1662122127189016576 +1662122127231017472 +1662122127273018368 +1662122127315019264 +1662122127363020288 +1662122127408021248 +1662122127462022400 +1662122127507023360 +1662122127549024256 +1662122127594025216 +1662122127639026176 +1662122127681027072 +1662122127729028096 +1662122127783029248 +1662122127828030208 +1662122127867031040 +1662122127909031936 +1662122127954032896 +1662122127999033856 +1662122128044034816 +1662122128086035712 +1662122128125036544 +1662122128170037504 +1662122128212038400 +1662122128257039360 +1662122128302040320 +1662122128347041280 +1662122128389042176 +1662122128440043264 +1662122128479044096 +1662122128518044928 +1662122128557045760 +1662122128599046656 +1662122128644047616 +1662122128689048576 +1662122128737049600 +1662122128776050432 +1662122128824051456 +1662122128866052352 +1662122128908053248 +1662122128950054144 +1662122128992055040 +1662122129034055936 +1662122129073056768 +1662122129115057664 +1662122129160058624 +1662122129208059648 +1662122129247060480 +1662122129295061504 +1662122129340062464 +1662122129382063360 +1662122129427064320 +1662122129472065280 +1662122129517066240 +1662122129559067136 +1662122129601068032 +1662122129640068864 +1662122129679069696 +1662122129727070720 +1662122129766071552 +1662122129808072448 +1662122129844073216 +1662122129889074176 +1662122129934075136 +1662122129976076032 +1662122130021076992 +1662122130066077952 +1662122130114078976 +1662122130159079936 +1662122130198080768 +1662122130240081664 +1662122130282082560 +1662122130330083584 +1662122130369084416 +1662122130414085376 +1662122130456086272 +1662122130498087168 +1662122130540088064 +1662122130582088960 +1662122130624089856 +1662122130669090816 +1662122130711091712 +1662122130753092608 +1662122130798093568 +1662122130840094464 +1662122130885095424 +1662122130927096320 +1662122130969097216 +1662122131011098112 +1662122131056099072 +1662122131095099904 +1662122131137100800 +1662122131182101760 +1662122131227102720 +1662122131263103488 +1662122131305104384 +1662122131350105344 +1662122131395106304 +1662122131437107200 +1662122131482108160 +1662122131527109120 +1662122131566109952 +1662122131605110784 +1662122131647111680 +1662122131689112576 +1662122131737113600 +1662122131776114432 +1662122131821115392 +1662122131863116288 +1662122131905117184 +1662122131947118080 +1662122131989118976 +1662122132028119808 +1662122132073120768 +1662122132115121664 +1662122132154122496 +1662122132205123584 +1662122132247124480 +1662122132286125312 +1662122132325126144 +1662122132370127104 +1662122132409127936 +1662122132454128896 +1662122132502129920 +1662122132541130752 +1662122132583131648 +1662122132628132608 +1662122132670133504 +1662122132712134400 +1662122132754135296 +1662122132799136256 +1662122132838137088 +1662122132877137920 +1662122132919138816 +1662122132964139776 +1662122133006140672 +1662122133051141632 +1662122133093142528 +1662122133135143424 +1662122133180144384 +1662122133225145344 +1662122133267146240 +1662122133309147136 +1662122133351148032 +1662122133393148928 +1662122133438149888 +1662122133480150784 +1662122133525151744 +1662122133567152640 +1662122133609153536 +1662122133654154496 +1662122133696155392 +1662122133744156416 +1662122133786157312 +1662122133831158272 +1662122133876159232 +1662122133921160192 +1662122133966161152 +1662122134011162112 +1662122134059163136 +1662122134101164032 +1662122134143164928 +1662122134188165888 +1662122134233166848 +1662122134281167872 +1662122134326168832 +1662122134368169728 +1662122134410170624 +1662122134452171520 +1662122134500172544 +1662122134539173376 +1662122134584174336 +1662122134626175232 +1662122134668176128 +1662122134710177024 +1662122134755177984 +1662122134797178880 +1662122134839179776 +1662122134887180800 +1662122134932181760 +1662122134971182592 +1662122135013183488 +1662122135052184320 +1662122135094185216 +1662122135133186048 +1662122135175186944 +1662122135217187840 +1662122135262188800 +1662122135310189824 +1662122135355190784 +1662122135400191744 +1662122135442192640 +1662122135487193600 +1662122135526194432 +1662122135571195392 +1662122135613196288 +1662122135652197120 +1662122135697198080 +1662122135736198912 +1662122135781199872 +1662122135823200768 +1662122135868201728 +1662122135907202560 +1662122135952203520 +1662122135994204416 +1662122136039205376 +1662122136081206272 +1662122136123207168 +1662122136168208128 +1662122136207208960 +1662122136252209920 +1662122136297210880 +1662122136342211840 +1662122136381212672 +1662122136426213632 +1662122136471214592 +1662122136516215552 +1662122136561216512 +1662122136600217344 +1662122136642218240 +1662122136684219136 +1662122136726220032 +1662122136771220992 +1662122136813221888 +1662122136861222912 +1662122136903223808 +1662122136951224832 +1662122136993225728 +1662122137035226624 +1662122137083227648 +1662122137125228544 +1662122137167229440 +1662122137209230336 +1662122137254231296 +1662122137290232064 +1662122137335233024 +1662122137371233792 +1662122137416234752 +1662122137461235712 +1662122137503236608 +1662122137551237632 +1662122137596238592 +1662122137641239552 +1662122137683240448 +1662122137728241408 +1662122137770242304 +1662122137815243264 +1662122137857244160 +1662122137902245120 +1662122137950246144 +1662122137998247168 +1662122138037248000 +1662122138082248960 +1662122138127249920 +1662122138169250816 +1662122138214251776 +1662122138265252864 +1662122138307253760 +1662122138349254656 +1662122138391255552 +1662122138433256448 +1662122138478257408 +1662122138520258304 +1662122138565259264 +1662122138610260224 +1662122138652261120 +1662122138688261888 +1662122138730262784 +1662122138772263680 +1662122138817264640 +1662122138862265600 +1662122138901266432 +1662122138940267264 +1662122138991268352 +1662122139030269184 +1662122139072270080 +1662122139117271040 +1662122139159271936 +1662122139201272832 +1662122139240273664 +1662122139282274560 +1662122139327275520 +1662122139369276416 +1662122139411277312 +1662122139450278144 +1662122139492279040 +1662122139534279936 +1662122139579280896 +1662122139621281792 +1662122139660282624 +1662122139702283520 +1662122139747284480 +1662122139792285440 +1662122139837286400 +1662122139879287296 +1662122139921288192 +1662122139963289088 +1662122140002289920 +1662122140044290816 +1662122140089291776 +1662122140128292608 +1662122140170293504 +1662122140209294336 +1662122140251295232 +1662122140296296192 +1662122140338297088 +1662122140383298048 +1662122140428299008 +1662122140470299904 +1662122140512300800 +1662122140560301824 +1662122140611302912 +1662122140659303936 +1662122140704304896 +1662122140746305792 +1662122140791306752 +1662122140833307648 +1662122140872308480 +1662122140914309376 +1662122140959310336 +1662122141004311296 +1662122141049312256 +1662122141094313216 +1662122141136314112 +1662122141178315008 +1662122141223315968 +1662122141268316928 +1662122141313317888 +1662122141352318720 +1662122141394319616 +1662122141436320512 +1662122141478321408 +1662122141523322368 +1662122141565323264 +1662122141610324224 +1662122141658325248 +1662122141706326272 +1662122141742327040 +1662122141790328064 +1662122141832328960 +1662122141871329792 +1662122141916330752 +1662122141961331712 +1662122142006332672 +1662122142045333504 +1662122142087334400 +1662122142129335296 +1662122142174336256 +1662122142216337152 +1662122142261338112 +1662122142303339008 +1662122142351340032 +1662122142393340928 +1662122142435341824 +1662122142480342784 +1662122142522343680 +1662122142561344512 +1662122142603345408 +1662122142648346368 +1662122142693347328 +1662122142735348224 +1662122142783349248 +1662122142825350144 +1662122142867351040 +1662122142915352064 +1662122142960353024 +1662122143002353920 +1662122143041354752 +1662122143086355712 +1662122143131356672 +1662122143173357568 +1662122143215358464 +1662122143260359424 +1662122143299360256 +1662122143341361152 +1662122143383362048 +1662122143425362944 +1662122143467363840 +1662122143512364800 +1662122143563365888 +1662122143605366784 +1662122143644367616 +1662122143683368448 +1662122143725369344 +1662122143767370240 +1662122143812371200 +1662122143854372096 +1662122143893372928 +1662122143935373824 +1662122143980374784 +1662122144022375680 +1662122144064376576 +1662122144112377600 +1662122144154378496 +1662122144199379456 +1662122144247380480 +1662122144289381376 +1662122144331382272 +1662122144373383168 +1662122144418384128 +1662122144454384896 +1662122144499385856 +1662122144541386752 +1662122144583387648 +1662122144628388608 +1662122144664389376 +1662122144709390336 +1662122144754391296 +1662122144793392128 +1662122144838393088 +1662122144883394048 +1662122144925394944 +1662122144973395968 +1662122145021396992 +1662122145063397888 +1662122145105398784 +1662122145144399616 +1662122145189400576 +1662122145231401472 +1662122145270402304 +1662122145315403264 +1662122145360404224 +1662122145408405248 +1662122145459406336 +1662122145504407296 +1662122145546408192 +1662122145588409088 +1662122145633410048 +1662122145678411008 +1662122145720411904 +1662122145765412864 +1662122145813413888 +1662122145855414784 +1662122145903415808 +1662122145948416768 +1662122145987417600 +1662122146032418560 +1662122146074419456 +1662122146122420480 +1662122146167421440 +1662122146212422400 +1662122146257423360 +1662122146302424320 +1662122146344425216 +1662122146389426176 +1662122146434427136 +1662122146476428032 +1662122146521428992 +1662122146563429888 +1662122146605430784 +1662122146647431680 +1662122146689432576 +1662122146734433536 +1662122146779434496 +1662122146821435392 +1662122146863436288 +1662122146908437248 +1662122146950438144 +1662122146992439040 +1662122147034439936 +1662122147070440704 +1662122147112441600 +1662122147163442688 +1662122147205443584 +1662122147244444416 +1662122147289445376 +1662122147331446272 +1662122147373447168 +1662122147415448064 +1662122147454448896 +1662122147496449792 +1662122147541450752 +1662122147583451648 +1662122147625452544 +1662122147670453504 +1662122147712454400 +1662122147754455296 +1662122147796456192 +1662122147838457088 +1662122147886458112 +1662122147931459072 +1662122147973459968 +1662122148018460928 +1662122148063461888 +1662122148105462784 +1662122148150463744 +1662122148192464640 +1662122148240465664 +1662122148279466496 +1662122148321467392 +1662122148366468352 +1662122148408469248 +1662122148447470080 +1662122148492471040 +1662122148534471936 +1662122148576472832 +1662122148621473792 +1662122148663474688 +1662122148705475584 +1662122148747476480 +1662122148792477440 +1662122148837478400 +1662122148882479360 +1662122148930480384 +1662122148972481280 +1662122149014482176 +1662122149059483136 +1662122149104484096 +1662122149146484992 +1662122149191485952 +1662122149233486848 +1662122149281487872 +1662122149323488768 +1662122149365489664 +1662122149407490560 +1662122149449491456 +1662122149491492352 +1662122149536493312 +1662122149575494144 +1662122149617495040 +1662122149659495936 +1662122149704496896 +1662122149746497792 +1662122149788498688 +1662122149830499584 +1662122149872500480 +1662122149914501376 +1662122149956502272 +1662122150001503232 +1662122150043504128 +1662122150088505088 +1662122150127505920 +1662122150169506816 +1662122150208507648 +1662122150250508544 +1662122150292509440 +1662122150334510336 +1662122150379511296 +1662122150421512192 +1662122150463513088 +1662122150511514112 +1662122150553515008 +1662122150592515840 +1662122150634516736 +1662122150679517696 +1662122150721518592 +1662122150763519488 +1662122150805520384 +1662122150847521280 +1662122150895522304 +1662122150940523264 +1662122150988524288 +1662122151033525248 +1662122151078526208 +1662122151123527168 +1662122151165528064 +1662122151210529024 +1662122151252529920 +1662122151297530880 +1662122151342531840 +1662122151384532736 +1662122151423533568 +1662122151465534464 +1662122151513535488 +1662122151561536512 +1662122151603537408 +1662122151648538368 +1662122151690539264 +1662122151735540224 +1662122151777541120 +1662122151819542016 +1662122151858542848 +1662122151903543808 +1662122151942544640 +1662122151987545600 +1662122152035546624 +1662122152077547520 +1662122152119548416 +1662122152164549376 +1662122152209550336 +1662122152254551296 +1662122152293552128 +1662122152335553024 +1662122152374553856 +1662122152416554752 +1662122152455555584 +1662122152497556480 +1662122152548557568 +1662122152587558400 +1662122152632559360 +1662122152674560256 +1662122152725561344 +1662122152770562304 +1662122152815563264 +1662122152857564160 +1662122152902565120 +1662122152941565952 +1662122152986566912 +1662122153028567808 +1662122153073568768 +1662122153115569664 +1662122153157570560 +1662122153199571456 +1662122153244572416 +1662122153286573312 +1662122153331574272 +1662122153376575232 +1662122153418576128 +1662122153463577088 +1662122153505577984 +1662122153550578944 +1662122153586579712 +1662122153637580800 +1662122153679581696 +1662122153721582592 +1662122153760583424 +1662122153805584384 +1662122153853585408 +1662122153901586432 +1662122153943587328 +1662122153982588160 +1662122154021588992 +1662122154063589888 +1662122154111590912 +1662122154153591808 +1662122154198592768 +1662122154243593728 +1662122154285594624 +1662122154324595456 +1662122154369596416 +1662122154411597312 +1662122154447598080 +1662122154489598976 +1662122154534599936 +1662122154579600896 +1662122154624601856 +1662122154666602752 +1662122154708603648 +1662122154750604544 +1662122154795605504 +1662122154837606400 +1662122154879607296 +1662122154924608256 +1662122154972609280 +1662122155014610176 +1662122155056611072 +1662122155095611904 +1662122155137612800 +1662122155179613696 +1662122155221614592 +1662122155260615424 +1662122155305616384 +1662122155347617280 +1662122155389618176 +1662122155434619136 +1662122155479620096 +1662122155524621056 +1662122155569622016 +1662122155611622912 +1662122155650623744 +1662122155695624704 +1662122155737625600 +1662122155779626496 +1662122155824627456 +1662122155866628352 +1662122155914629376 +1662122155953630208 +1662122155995631104 +1662122156043632128 +1662122156088633088 +1662122156130633984 +1662122156172634880 +1662122156214635776 +1662122156259636736 +1662122156307637760 +1662122156349638656 +1662122156397639680 +1662122156436640512 +1662122156481641472 +1662122156535642624 +1662122156574643456 +1662122156619644416 +1662122156667645440 +1662122156709646336 +1662122156751647232 +1662122156799648256 +1662122156841649152 +1662122156883650048 +1662122156928651008 +1662122156973651968 +1662122157015652864 +1662122157057653760 +1662122157102654720 +1662122157144655616 +1662122157183656448 +1662122157231657472 +1662122157273658368 +1662122157315659264 +1662122157363660288 +1662122157408661248 +1662122157450662144 +1662122157498663168 +1662122157537664000 +1662122157576664832 +1662122157618665728 +1662122157663666688 +1662122157705667584 +1662122157747668480 +1662122157789669376 +1662122157837670400 +1662122157882671360 +1662122157924672256 +1662122157966673152 +1662122158014674176 +1662122158062675200 +1662122158101676032 +1662122158149677056 +1662122158191677952 +1662122158236678912 +1662122158275679744 +1662122158317680640 +1662122158353681408 +1662122158395682304 +1662122158440683264 +1662122158482684160 +1662122158524685056 +1662122158572686080 +1662122158617687040 +1662122158662688000 +1662122158704688896 +1662122158746689792 +1662122158791690752 +1662122158830691584 +1662122158872692480 +1662122158911693312 +1662122158953694208 +1662122158998695168 +1662122159043696128 +1662122159085697024 +1662122159127697920 +1662122159163698688 +1662122159205699584 +1662122159247700480 +1662122159292701440 +1662122159337702400 +1662122159382703360 +1662122159421704192 +1662122159463705088 +1662122159502705920 +1662122159550706944 +1662122159589707776 +1662122159634708736 +1662122159673709568 +1662122159727710720 +1662122159766711552 +1662122159808712448 +1662122159850713344 +1662122159895714304 +1662122159940715264 +1662122159982716160 +1662122160021716992 +1662122160063717888 +1662122160108718848 +1662122160153719808 +1662122160201720832 +1662122160240721664 +1662122160282722560 +1662122160324723456 +1662122160366724352 +1662122160408725248 +1662122160456726272 +1662122160501727232 +1662122160546728192 +1662122160588729088 +1662122160636730112 +1662122160684731136 +1662122160732732160 +1662122160774733056 +1662122160816733952 +1662122160861734912 +1662122160903735808 +1662122160942736640 +1662122160984737536 +1662122161026738432 +1662122161068739328 +1662122161113740288 +1662122161158741248 +1662122161203742208 +1662122161245743104 +1662122161287744000 +1662122161332744960 +1662122161377745920 +1662122161419746816 +1662122161461747712 +1662122161503748608 +1662122161545749504 +1662122161593750528 +1662122161635751424 +1662122161680752384 +1662122161722753280 +1662122161764754176 +1662122161806755072 +1662122161845755904 +1662122161884756736 +1662122161926757632 +1662122161974758656 +1662122162016759552 +1662122162052760320 +1662122162091761152 +1662122162133762048 +1662122162178763008 +1662122162223763968 +1662122162265764864 +1662122162313765888 +1662122162355766784 +1662122162397767680 +1662122162439768576 +1662122162484769536 +1662122162523770368 +1662122162565771264 +1662122162607772160 +1662122162652773120 +1662122162694774016 +1662122162733774848 +1662122162778775808 +1662122162823776768 +1662122162868777728 +1662122162910778624 +1662122162949779456 +1662122162991780352 +1662122163039781376 +1662122163084782336 +1662122163126783232 +1662122163168784128 +1662122163213785088 +1662122163258786048 +1662122163297786880 +1662122163339787776 +1662122163378788608 +1662122163420789504 +1662122163456790272 +1662122163504791296 +1662122163549792256 +1662122163591793152 +1662122163633794048 +1662122163675794944 +1662122163717795840 +1662122163762796800 +1662122163804797696 +1662122163849798656 +1662122163888799488 +1662122163930800384 +1662122163972801280 +1662122164011802112 +1662122164050802944 +1662122164092803840 +1662122164134804736 +1662122164176805632 +1662122164221806592 +1662122164263807488 +1662122164305808384 +1662122164347809280 +1662122164392810240 +1662122164431811072 +1662122164470811904 +1662122164512812800 +1662122164548813568 +1662122164593814528 +1662122164635815424 +1662122164677816320 +1662122164719817216 +1662122164764818176 +1662122164812819200 +1662122164857820160 +1662122164893820928 +1662122164938821888 +1662122164980822784 +1662122165025823744 +1662122165070824704 +1662122165112825600 +1662122165157826560 +1662122165202827520 +1662122165244828416 +1662122165283829248 +1662122165325830144 +1662122165367831040 +1662122165412832000 +1662122165454832896 +1662122165499833856 +1662122165544834816 +1662122165586835712 +1662122165628836608 +1662122165670837504 +1662122165715838464 +1662122165760839424 +1662122165805840384 +1662122165853841408 +1662122165895842304 +1662122165934843136 +1662122165979844096 +1662122166021844992 +1662122166063845888 +1662122166105846784 +1662122166147847680 +1662122166189848576 +1662122166231849472 +1662122166276850432 +1662122166321851392 +1662122166360852224 +1662122166405853184 +1662122166450854144 +1662122166492855040 +1662122166531855872 +1662122166570856704 +1662122166615857664 +1662122166657858560 +1662122166702859520 +1662122166744860416 +1662122166786861312 +1662122166831862272 +1662122166876863232 +1662122166912864000 +1662122166951864832 +1662122166993865728 +1662122167035866624 +1662122167077867520 +1662122167116868352 +1662122167161869312 +1662122167206870272 +1662122167248871168 +1662122167296872192 +1662122167344873216 +1662122167386874112 +1662122167428875008 +1662122167470875904 +1662122167515876864 +1662122167560877824 +1662122167599878656 +1662122167638879488 +1662122167680880384 +1662122167722881280 +1662122167767882240 +1662122167815883264 +1662122167857884160 +1662122167899885056 +1662122167944886016 +1662122167989886976 +1662122168034887936 +1662122168079888896 +1662122168121889792 +1662122168163890688 +1662122168211891712 +1662122168253892608 +1662122168298893568 +1662122168331894272 +1662122168373895168 +1662122168415896064 +1662122168460897024 +1662122168502897920 +1662122168544898816 +1662122168586899712 +1662122168631900672 +1662122168670901504 +1662122168721902592 +1662122168763903488 +1662122168808904448 +1662122168850905344 +1662122168892906240 +1662122168931907072 +1662122168970907904 +1662122169012908800 +1662122169057909760 +1662122169096910592 +1662122169138911488 +1662122169180912384 +1662122169219913216 +1662122169264914176 +1662122169306915072 +1662122169354916096 +1662122169393916928 +1662122169438917888 +1662122169483918848 +1662122169522919680 +1662122169567920640 +1662122169609921536 +1662122169657922560 +1662122169702923520 +1662122169744924416 +1662122169786925312 +1662122169828926208 +1662122169870927104 +1662122169912928000 +1662122169957928960 +1662122169999929856 +1662122170041930752 +1662122170089931776 +1662122170128932608 +1662122170170933504 +1662122170209934336 +1662122170254935296 +1662122170296936192 +1662122170341937152 +1662122170389938176 +1662122170434939136 +1662122170476940032 +1662122170521940992 +1662122170563941888 +1662122170611942912 +1662122170659943936 +1662122170707944960 +1662122170749945856 +1662122170794946816 +1662122170839947776 +1662122170881948672 +1662122170920949504 +1662122170965950464 +1662122171016951552 +1662122171061952512 +1662122171106953472 +1662122171148954368 +1662122171193955328 +1662122171235956224 +1662122171280957184 +1662122171322958080 +1662122171364958976 +1662122171406959872 +1662122171451960832 +1662122171493961728 +1662122171541962752 +1662122171583963648 +1662122171625964544 +1662122171667965440 +1662122171715966464 +1662122171763967488 +1662122171805968384 +1662122171847969280 +1662122171892970240 +1662122171940971264 +1662122171982972160 +1662122172024973056 +1662122172066973952 +1662122172111974912 +1662122172153975808 +1662122172195976704 +1662122172237977600 +1662122172279978496 +1662122172318979328 +1662122172357980160 +1662122172402981120 +1662122172444982016 +1662122172489982976 +1662122172531983872 +1662122172576984832 +1662122172618985728 +1662122172663986688 +1662122172705987584 +1662122172750988544 +1662122172795989504 +1662122172837990400 +1662122172882991360 +1662122172924992256 +1662122172966993152 +1662122173011994112 +1662122173053995008 +1662122173095995904 +1662122173134996736 +1662122173185997824 +1662122173227998720 +1662122173275999744 +1662122173318000640 +1662122173363001600 +1662122173405002496 +1662122173447003392 +1662122173492004352 +1662122173537005312 +1662122173582006272 +1662122173627007232 +1662122173672008192 +1662122173717009152 +1662122173759010048 +1662122173804011008 +1662122173849011968 +1662122173894012928 +1662122173939013888 +1662122173981014784 +1662122174023015680 +1662122174065016576 +1662122174107017472 +1662122174149018368 +1662122174194019328 +1662122174236020224 +1662122174284021248 +1662122174329022208 +1662122174371023104 +1662122174416024064 +1662122174461025024 +1662122174503025920 +1662122174545026816 +1662122174593027840 +1662122174638028800 +1662122174680029696 +1662122174722030592 +1662122174764031488 +1662122174800032256 +1662122174845033216 +1662122174887034112 +1662122174926034944 +1662122174968035840 +1662122175007036672 +1662122175049037568 +1662122175091038464 +1662122175136039424 +1662122175175040256 +1662122175220041216 +1662122175262042112 +1662122175307043072 +1662122175352044032 +1662122175394044928 +1662122175442045952 +1662122175484046848 +1662122175535047936 +1662122175577048832 +1662122175625049856 +1662122175667050752 +1662122175712051712 +1662122175754052608 +1662122175799053568 +1662122175841054464 +1662122175883055360 +1662122175925056256 +1662122175973057280 +1662122176015058176 +1662122176057059072 +1662122176102060032 +1662122176144060928 +1662122176189061888 +1662122176231062784 +1662122176273063680 +1662122176312064512 +1662122176354065408 +1662122176396066304 +1662122176432067072 +1662122176474067968 +1662122176516068864 +1662122176558069760 +1662122176600070656 +1662122176636071424 +1662122176681072384 +1662122176726073344 +1662122176768074240 +1662122176816075264 +1662122176858076160 +1662122176900077056 +1662122176948078080 +1662122176990078976 +1662122177032079872 +1662122177077080832 +1662122177119081728 +1662122177161082624 +1662122177203083520 +1662122177245084416 +1662122177287085312 +1662122177332086272 +1662122177374087168 +1662122177416088064 +1662122177461089024 +1662122177506089984 +1662122177554091008 +1662122177596091904 +1662122177635092736 +1662122177680093696 +1662122177725094656 +1662122177770095616 +1662122177815096576 +1662122177860097536 +1662122177905098496 +1662122177947099392 +1662122177986100224 +1662122178028101120 +1662122178070102016 +1662122178112102912 +1662122178154103808 +1662122178202104832 +1662122178241105664 +1662122178280106496 +1662122178325107456 +1662122178370108416 +1662122178415109376 +1662122178454110208 +1662122178502111232 +1662122178547112192 +1662122178589113088 +1662122178634114048 +1662122178679115008 +1662122178724115968 +1662122178766116864 +1662122178814117888 +1662122178859118848 +1662122178910119936 +1662122178955120896 +1662122179003121920 +1662122179051122944 +1662122179096123904 +1662122179138124800 +1662122179180125696 +1662122179228126720 +1662122179267127552 +1662122179312128512 +1662122179363129600 +1662122179405130496 +1662122179450131456 +1662122179498132480 +1662122179540133376 +1662122179579134208 +1662122179624135168 +1662122179666136064 +1662122179711137024 +1662122179753137920 +1662122179798138880 +1662122179840139776 +1662122179885140736 +1662122179930141696 +1662122179972142592 +1662122180014143488 +1662122180056144384 +1662122180098145280 +1662122180137146112 +1662122180176146944 +1662122180227148032 +1662122180269148928 +1662122180314149888 +1662122180356150784 +1662122180395151616 +1662122180437152512 +1662122180479153408 +1662122180521154304 +1662122180566155264 +1662122180608156160 +1662122180653157120 +1662122180695158016 +1662122180734158848 +1662122180776159744 +1662122180821160704 +1662122180863161600 +1662122180908162560 +1662122180956163584 +1662122181001164544 +1662122181049165568 +1662122181091166464 +1662122181133167360 +1662122181172168192 +1662122181217169152 +1662122181262170112 +1662122181310171136 +1662122181355172096 +1662122181400173056 +1662122181442173952 +1662122181484174848 +1662122181526175744 +1662122181571176704 +1662122181613177600 +1662122181652178432 +1662122181694179328 +1662122181736180224 +1662122181772180992 +1662122181817181952 +1662122181862182912 +1662122181907183872 +1662122181949184768 +1662122181994185728 +1662122182042186752 +1662122182081187584 +1662122182117188352 +1662122182159189248 +1662122182198190080 +1662122182243191040 +1662122182285191936 +1662122182327192832 +1662122182369193728 +1662122182411194624 +1662122182456195584 +1662122182498196480 +1662122182540197376 +1662122182582198272 +1662122182624199168 +1662122182666200064 +1662122182708200960 +1662122182750201856 +1662122182795202816 +1662122182837203712 +1662122182882204672 +1662122182927205632 +1662122182969206528 +1662122183011207424 +1662122183059208448 +1662122183098209280 +1662122183137210112 +1662122183182211072 +1662122183224211968 +1662122183269212928 +1662122183308213760 +1662122183353214720 +1662122183395215616 +1662122183437216512 +1662122183476217344 +1662122183515218176 +1662122183557219072 +1662122183599219968 +1662122183641220864 +1662122183689221888 +1662122183731222784 +1662122183776223744 +1662122183821224704 +1662122183863225600 +1662122183908226560 +1662122183947227392 +1662122183989228288 +1662122184034229248 +1662122184076230144 +1662122184121231104 +1662122184163232000 +1662122184202232832 +1662122184247233792 +1662122184292234752 +1662122184334235648 +1662122184376236544 +1662122184421237504 +1662122184463238400 +1662122184508239360 +1662122184553240320 +1662122184595241216 +1662122184637242112 +1662122184679243008 +1662122184721243904 +1662122184763244800 +1662122184808245760 +1662122184850246656 +1662122184892247552 +1662122184934248448 +1662122184976249344 +1662122185015250176 +1662122185057251072 +1662122185099251968 +1662122185144252928 +1662122185192253952 +1662122185234254848 +1662122185276255744 +1662122185321256704 +1662122185366257664 +1662122185411258624 +1662122185450259456 +1662122185492260352 +1662122185531261184 +1662122185579262208 +1662122185627263232 +1662122185672264192 +1662122185717265152 +1662122185759266048 +1662122185807267072 +1662122185849267968 +1662122185888268800 +1662122185930269696 +1662122185966270464 +1662122186011271424 +1662122186053272320 +1662122186095273216 +1662122186137274112 +1662122186173274880 +1662122186218275840 +1662122186260276736 +1662122186299277568 +1662122186341278464 +1662122186383279360 +1662122186428280320 +1662122186473281280 +1662122186515282176 +1662122186563283200 +1662122186614284288 +1662122186656285184 +1662122186701286144 +1662122186746287104 +1662122186788288000 +1662122186833288960 +1662122186878289920 +1662122186917290752 +1662122186962291712 +1662122187004292608 +1662122187049293568 +1662122187088294400 +1662122187130295296 +1662122187175296256 +1662122187220297216 +1662122187262298112 +1662122187301298944 +1662122187343299840 +1662122187382300672 +1662122187424301568 +1662122187463302400 +1662122187505303296 +1662122187544304128 +1662122187586305024 +1662122187631305984 +1662122187673306880 +1662122187715307776 +1662122187757308672 +1662122187802309632 +1662122187844310528 +1662122187889311488 +1662122187934312448 +1662122187979313408 +1662122188024314368 +1662122188063315200 +1662122188111316224 +1662122188153317120 +1662122188201318144 +1662122188243319040 +1662122188294320128 +1662122188336321024 +1662122188378321920 +1662122188423322880 +1662122188465323776 +1662122188504324608 +1662122188549325568 +1662122188591326464 +1662122188636327424 +1662122188681328384 +1662122188723329280 +1662122188768330240 +1662122188813331200 +1662122188858332160 +1662122188906333184 +1662122188951334144 +1662122188996335104 +1662122189041336064 +1662122189086337024 +1662122189128337920 +1662122189173338880 +1662122189221339904 +1662122189263340800 +1662122189305341696 +1662122189350342656 +1662122189395343616 +1662122189431344384 +1662122189476345344 +1662122189518346240 +1662122189560347136 +1662122189605348096 +1662122189647348992 +1662122189692349952 +1662122189737350912 +1662122189782351872 +1662122189827352832 +1662122189872353792 +1662122189917354752 +1662122189962355712 +1662122190007356672 +1662122190052357632 +1662122190097358592 +1662122190139359488 +1662122190181360384 +1662122190220361216 +1662122190265362176 +1662122190307363072 +1662122190352364032 +1662122190397364992 +1662122190436365824 +1662122190475366656 +1662122190520367616 +1662122190565368576 +1662122190613369600 +1662122190661370624 +1662122190700371456 +1662122190742372352 +1662122190787373312 +1662122190829374208 +1662122190874375168 +1662122190916376064 +1662122190964377088 +1662122191006377984 +1662122191048378880 +1662122191099379968 +1662122191141380864 +1662122191186381824 +1662122191228382720 +1662122191276383744 +1662122191318384640 +1662122191360385536 +1662122191405386496 +1662122191444387328 +1662122191489388288 +1662122191531389184 +1662122191570390016 +1662122191609390848 +1662122191651391744 +1662122191690392576 +1662122191732393472 +1662122191774394368 +1662122191813395200 +1662122191855396096 +1662122191897396992 +1662122191936397824 +1662122191978398720 +1662122192020399616 +1662122192062400512 +1662122192101401344 +1662122192143402240 +1662122192185403136 +1662122192227404032 +1662122192269404928 +1662122192311405824 +1662122192350406656 +1662122192395407616 +1662122192437408512 +1662122192476409344 +1662122192518410240 +1662122192563411200 +1662122192608412160 +1662122192650413056 +1662122192695414016 +1662122192740414976 +1662122192782415872 +1662122192824416768 +1662122192869417728 +1662122192914418688 +1662122192956419584 +1662122193001420544 +1662122193040421376 +1662122193082422272 +1662122193127423232 +1662122193166424064 +1662122193208424960 +1662122193247425792 +1662122193289426688 +1662122193331427584 +1662122193370428416 +1662122193415429376 +1662122193454430208 +1662122193499431168 +1662122193541432064 +1662122193589433088 +1662122193631433984 +1662122193676434944 +1662122193721435904 +1662122193763436800 +1662122193808437760 +1662122193850438656 +1662122193889439488 +1662122193934440448 +1662122193976441344 +1662122194018442240 +1662122194057443072 +1662122194093443840 +1662122194135444736 +1662122194186445824 +1662122194231446784 +1662122194270447616 +1662122194309448448 +1662122194348449280 +1662122194390450176 +1662122194432451072 +1662122194471451904 +1662122194513452800 +1662122194558453760 +1662122194603454720 +1662122194645455616 +1662122194690456576 +1662122194729457408 +1662122194777458432 +1662122194819459328 +1662122194864460288 +1662122194906461184 +1662122194954462208 +1662122194999463168 +1662122195044464128 +1662122195089465088 +1662122195131465984 +1662122195179467008 +1662122195224467968 +1662122195266468864 +1662122195308469760 +1662122195353470720 +1662122195395471616 +1662122195443472640 +1662122195488473600 +1662122195533474560 +1662122195572475392 +1662122195614476288 +1662122195656477184 +1662122195698478080 +1662122195740478976 +1662122195782479872 +1662122195821480704 +1662122195866481664 +1662122195908482560 +1662122195953483520 +1662122195992484352 +1662122196037485312 +1662122196082486272 +1662122196127487232 +1662122196169488128 +1662122196211489024 +1662122196253489920 +1662122196292490752 +1662122196334491648 +1662122196373492480 +1662122196415493376 +1662122196454494208 +1662122196496495104 +1662122196538496000 +1662122196580496896 +1662122196622497792 +1662122196667498752 +1662122196709499648 +1662122196748500480 +1662122196793501440 +1662122196838502400 +1662122196880503296 +1662122196922504192 +1662122196967505152 +1662122197015506176 +1662122197057507072 +1662122197099507968 +1662122197138508800 +1662122197180509696 +1662122197222510592 +1662122197264511488 +1662122197309512448 +1662122197351513344 +1662122197393514240 +1662122197441515264 +1662122197483516160 +1662122197528517120 +1662122197570518016 +1662122197621519104 +1662122197663520000 +1662122197705520896 +1662122197747521792 +1662122197789522688 +1662122197834523648 +1662122197879524608 +1662122197921525504 +1662122197963526400 +1662122198005527296 +1662122198044528128 +1662122198086529024 +1662122198131529984 +1662122198176530944 +1662122198218531840 +1662122198263532800 +1662122198302533632 +1662122198347534592 +1662122198395535616 +1662122198434536448 +1662122198482537472 +1662122198521538304 +1662122198563539200 +1662122198605540096 +1662122198644540928 +1662122198680541696 +1662122198722542592 +1662122198767543552 +1662122198806544384 +1662122198851545344 +1662122198890546176 +1662122198938547200 +1662122198986548224 +1662122199025549056 +1662122199064549888 +1662122199103550720 +1662122199145551616 +1662122199193552640 +1662122199241553664 +1662122199283554560 +1662122199331555584 +1662122199376556544 +1662122199415557376 +1662122199463558400 +1662122199508559360 +1662122199553560320 +1662122199601561344 +1662122199640562176 +1662122199682563072 +1662122199727564032 +1662122199769564928 +1662122199814565888 +1662122199862566912 +1662122199904567808 +1662122199943568640 +1662122199994569728 +1662122200033570560 +1662122200078571520 +1662122200120572416 +1662122200159573248 +1662122200204574208 +1662122200240574976 +1662122200285575936 +1662122200330576896 +1662122200369577728 +1662122200420578816 +1662122200459579648 +1662122200498580480 +1662122200540581376 +1662122200582582272 +1662122200621583104 +1662122200666584064 +1662122200708584960 +1662122200753585920 +1662122200795586816 +1662122200834587648 +1662122200876588544 +1662122200918589440 diff --git a/Examples/Monocular-Inertial/mono_inertial_euroc.cc b/Examples/Monocular-Inertial/mono_inertial_euroc.cc index fe29df96f8..bdccb3dad4 100644 --- a/Examples/Monocular-Inertial/mono_inertial_euroc.cc +++ b/Examples/Monocular-Inertial/mono_inertial_euroc.cc @@ -82,10 +82,10 @@ int main(int argc, char *argv[]) string pathSeq(argv[(2*seq) + 3]); string pathTimeStamps(argv[(2*seq) + 4]); - string pathCam0 = pathSeq + "/auv0/rgb/cam0/data"; + string pathcam2 = pathSeq + "/auv0/rgb/cam2/data"; string pathImu = pathSeq + "/auv0/imu0/data.csv"; - LoadImages(pathCam0, pathTimeStamps, vstrImageFilenames[seq], vTimestampsCam[seq]); + LoadImages(pathcam2, pathTimeStamps, vstrImageFilenames[seq], vTimestampsCam[seq]); cout << "LOADED!" << endl; cout << "Loading IMU for sequence " << seq << "..."; diff --git a/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_dark.txt b/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_dark.txt new file mode 100644 index 0000000000..e14794a331 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_dark.txt @@ -0,0 +1,2405 @@ +1662138209585822464 +1662138209624823296 +1662138209666824192 +1662138209705825024 +1662138209747825920 +1662138209789826816 +1662138209831827712 +1662138209873828608 +1662138209918829568 +1662138209972830720 +1662138210017831680 +1662138210065832704 +1662138210110833664 +1662138210155834624 +1662138210197835520 +1662138210242836480 +1662138210287837440 +1662138210329838336 +1662138210374839296 +1662138210416840192 +1662138210467841280 +1662138210515842304 +1662138210563843328 +1662138210605844224 +1662138210647845120 +1662138210698846208 +1662138210740847104 +1662138210782848000 +1662138210824848896 +1662138210869849856 +1662138210914850816 +1662138210959851776 +1662138211001852672 +1662138211046853632 +1662138211088854528 +1662138211130855424 +1662138211181856512 +1662138211223857408 +1662138211262858240 +1662138211304859136 +1662138211349860096 +1662138211391860992 +1662138211436861952 +1662138211475862784 +1662138211517863680 +1662138211562864640 +1662138211607865600 +1662138211652866560 +1662138211697867520 +1662138211745868544 +1662138211787869440 +1662138211829870336 +1662138211874871296 +1662138211925872384 +1662138211967873280 +1662138212012874240 +1662138212060875264 +1662138212102876160 +1662138212141876992 +1662138212180877824 +1662138212222878720 +1662138212270879744 +1662138212318880768 +1662138212363881728 +1662138212411882752 +1662138212465883904 +1662138212507884800 +1662138212552885760 +1662138212597886720 +1662138212639887616 +1662138212684888576 +1662138212732889600 +1662138212771890432 +1662138212813891328 +1662138212855892224 +1662138212897893120 +1662138212939894016 +1662138212981894912 +1662138213026895872 +1662138213068896768 +1662138213116897792 +1662138213161898752 +1662138213206899712 +1662138213248900608 +1662138213290901504 +1662138213332902400 +1662138213374903296 +1662138213416904192 +1662138213461905152 +1662138213509906176 +1662138213551907072 +1662138213599908096 +1662138213641908992 +1662138213695910144 +1662138213737911040 +1662138213788912128 +1662138213833913088 +1662138213881914112 +1662138213929915136 +1662138213971916032 +1662138214019917056 +1662138214061917952 +1662138214109918976 +1662138214157920000 +1662138214208921088 +1662138214250921984 +1662138214298923008 +1662138214337923840 +1662138214382924800 +1662138214430925824 +1662138214478926848 +1662138214520927744 +1662138214562928640 +1662138214604929536 +1662138214649930496 +1662138214691931392 +1662138214733932288 +1662138214775933184 +1662138214820934144 +1662138214859934976 +1662138214904935936 +1662138214955937024 +1662138214997937920 +1662138215042938880 +1662138215084939776 +1662138215132940800 +1662138215171941632 +1662138215210942464 +1662138215255943424 +1662138215300944384 +1662138215342945280 +1662138215387946240 +1662138215429947136 +1662138215468947968 +1662138215513948928 +1662138215561949952 +1662138215606950912 +1662138215648951808 +1662138215690952704 +1662138215738953728 +1662138215780954624 +1662138215828955648 +1662138215870956544 +1662138215909957376 +1662138215957958400 +1662138215999959296 +1662138216041960192 +1662138216083961088 +1662138216122961920 +1662138216164962816 +1662138216212963840 +1662138216257964800 +1662138216299965696 +1662138216341966592 +1662138216383967488 +1662138216431968512 +1662138216470969344 +1662138216512970240 +1662138216554971136 +1662138216596972032 +1662138216641972992 +1662138216689974016 +1662138216737975040 +1662138216782976000 +1662138216824976896 +1662138216866977792 +1662138216905978624 +1662138216947979520 +1662138216992980480 +1662138217034981376 +1662138217085982464 +1662138217133983488 +1662138217175984384 +1662138217214985216 +1662138217259986176 +1662138217301987072 +1662138217349988096 +1662138217391988992 +1662138217433989888 +1662138217475990784 +1662138217517991680 +1662138217559992576 +1662138217607993600 +1662138217652994560 +1662138217700995584 +1662138217742996480 +1662138217787997440 +1662138217829998336 +1662138217871999232 +1662138217914000128 +1662138217956001024 +1662138217998001920 +1662138218040002816 +1662138218085003776 +1662138218130004736 +1662138218175005696 +1662138218217006592 +1662138218256007424 +1662138218298008320 +1662138218343009280 +1662138218385010176 +1662138218427011072 +1662138218469011968 +1662138218517012992 +1662138218559013888 +1662138218601014784 +1662138218646015744 +1662138218694016768 +1662138218739017728 +1662138218781018624 +1662138218823019520 +1662138218865020416 +1662138218907021312 +1662138218949022208 +1662138218997023232 +1662138219036024064 +1662138219081025024 +1662138219123025920 +1662138219162026752 +1662138219207027712 +1662138219249028608 +1662138219294029568 +1662138219339030528 +1662138219381031424 +1662138219423032320 +1662138219474033408 +1662138219519034368 +1662138219567035392 +1662138219612036352 +1662138219660037376 +1662138219708038400 +1662138219756039424 +1662138219798040320 +1662138219846041344 +1662138219888042240 +1662138219933043200 +1662138219987044352 +1662138220035045376 +1662138220080046336 +1662138220128047360 +1662138220173048320 +1662138220218049280 +1662138220263050240 +1662138220305051136 +1662138220350052096 +1662138220395053056 +1662138220434053888 +1662138220479054848 +1662138220524055808 +1662138220569056768 +1662138220611057664 +1662138220650058496 +1662138220692059392 +1662138220734060288 +1662138220779061248 +1662138220824062208 +1662138220869063168 +1662138220917064192 +1662138220962065152 +1662138221007066112 +1662138221049067008 +1662138221091067904 +1662138221133068800 +1662138221178069760 +1662138221220070656 +1662138221265071616 +1662138221307072512 +1662138221349073408 +1662138221403074560 +1662138221445075456 +1662138221493076480 +1662138221535077376 +1662138221580078336 +1662138221628079360 +1662138221670080256 +1662138221712081152 +1662138221757082112 +1662138221799083008 +1662138221838083840 +1662138221880084736 +1662138221922085632 +1662138221961086464 +1662138222009087488 +1662138222051088384 +1662138222102089472 +1662138222150090496 +1662138222195091456 +1662138222240092416 +1662138222288093440 +1662138222336094464 +1662138222381095424 +1662138222429096448 +1662138222471097344 +1662138222513098240 +1662138222558099200 +1662138222600100096 +1662138222648101120 +1662138222687101952 +1662138222732102912 +1662138222777103872 +1662138222822104832 +1662138222870105856 +1662138222912106752 +1662138222960107776 +1662138223002108672 +1662138223044109568 +1662138223086110464 +1662138223131111424 +1662138223173112320 +1662138223221113344 +1662138223266114304 +1662138223311115264 +1662138223359116288 +1662138223401117184 +1662138223437117952 +1662138223479118848 +1662138223527119872 +1662138223569120768 +1662138223611121664 +1662138223656122624 +1662138223701123584 +1662138223749124608 +1662138223791125504 +1662138223839126528 +1662138223881127424 +1662138223926128384 +1662138223968129280 +1662138224019130368 +1662138224058131200 +1662138224112132352 +1662138224160133376 +1662138224208134400 +1662138224247135232 +1662138224289136128 +1662138224334137088 +1662138224376137984 +1662138224418138880 +1662138224463139840 +1662138224511140864 +1662138224553141760 +1662138224598142720 +1662138224643143680 +1662138224688144640 +1662138224733145600 +1662138224784146688 +1662138224826147584 +1662138224868148480 +1662138224910149376 +1662138224952150272 +1662138224994151168 +1662138225039152128 +1662138225084153088 +1662138225132154112 +1662138225174155008 +1662138225219155968 +1662138225267156992 +1662138225315158016 +1662138225360158976 +1662138225405159936 +1662138225450160896 +1662138225501161984 +1662138225546162944 +1662138225588163840 +1662138225633164800 +1662138225678165760 +1662138225723166720 +1662138225765167616 +1662138225810168576 +1662138225858169600 +1662138225900170496 +1662138225948171520 +1662138225993172480 +1662138226035173376 +1662138226077174272 +1662138226122175232 +1662138226167176192 +1662138226212177152 +1662138226254178048 +1662138226302179072 +1662138226344179968 +1662138226392180992 +1662138226431181824 +1662138226473182720 +1662138226521183744 +1662138226566184704 +1662138226608185600 +1662138226650186496 +1662138226689187328 +1662138226743188480 +1662138226794189568 +1662138226839190528 +1662138226881191424 +1662138226923192320 +1662138226971193344 +1662138227013194240 +1662138227058195200 +1662138227103196160 +1662138227148197120 +1662138227193198080 +1662138227241199104 +1662138227286200064 +1662138227337201152 +1662138227391202304 +1662138227433203200 +1662138227475204096 +1662138227517204992 +1662138227559205888 +1662138227604206848 +1662138227652207872 +1662138227694208768 +1662138227739209728 +1662138227784210688 +1662138227826211584 +1662138227868212480 +1662138227910213376 +1662138227955214336 +1662138227997215232 +1662138228039216128 +1662138228084217088 +1662138228126217984 +1662138228171218944 +1662138228225220096 +1662138228267220992 +1662138228318222080 +1662138228363223040 +1662138228405223936 +1662138228456225024 +1662138228504226048 +1662138228549227008 +1662138228594227968 +1662138228642228992 +1662138228684229888 +1662138228729230848 +1662138228783232000 +1662138228828232960 +1662138228870233856 +1662138228918234880 +1662138228966235904 +1662138229008236800 +1662138229056237824 +1662138229095238656 +1662138229143239680 +1662138229185240576 +1662138229227241472 +1662138229269242368 +1662138229317243392 +1662138229359244288 +1662138229401245184 +1662138229449246208 +1662138229503247360 +1662138229545248256 +1662138229590249216 +1662138229632250112 +1662138229674251008 +1662138229716251904 +1662138229764252928 +1662138229806253824 +1662138229851254784 +1662138229893255680 +1662138229941256704 +1662138229986257664 +1662138230028258560 +1662138230073259520 +1662138230127260672 +1662138230169261568 +1662138230217262592 +1662138230262263552 +1662138230304264448 +1662138230349265408 +1662138230394266368 +1662138230436267264 +1662138230481268224 +1662138230526269184 +1662138230574270208 +1662138230613271040 +1662138230658272000 +1662138230706273024 +1662138230748273920 +1662138230790274816 +1662138230835275776 +1662138230877276672 +1662138230919277568 +1662138230961278464 +1662138231006279424 +1662138231048280320 +1662138231099281408 +1662138231141282304 +1662138231186283264 +1662138231228284160 +1662138231279285248 +1662138231324286208 +1662138231372287232 +1662138231414288128 +1662138231468289280 +1662138231510290176 +1662138231552291072 +1662138231594291968 +1662138231633292800 +1662138231675293696 +1662138231714294528 +1662138231759295488 +1662138231810296576 +1662138231852297472 +1662138231894298368 +1662138231942299392 +1662138231984300288 +1662138232023301120 +1662138232068302080 +1662138232113303040 +1662138232155303936 +1662138232203304960 +1662138232248305920 +1662138232290306816 +1662138232338307840 +1662138232386308864 +1662138232428309760 +1662138232467310592 +1662138232515311616 +1662138232557312512 +1662138232614313728 +1662138232656314624 +1662138232695315456 +1662138232737316352 +1662138232782317312 +1662138232833318400 +1662138232875319296 +1662138232917320192 +1662138232959321088 +1662138233001321984 +1662138233046322944 +1662138233088323840 +1662138233136324864 +1662138233187325952 +1662138233232326912 +1662138233280327936 +1662138233322328832 +1662138233364329728 +1662138233409330688 +1662138233451331584 +1662138233493332480 +1662138233535333376 +1662138233580334336 +1662138233625335296 +1662138233667336192 +1662138233715337216 +1662138233757338112 +1662138233805339136 +1662138233856340224 +1662138233895341056 +1662138233940342016 +1662138233979342848 +1662138234021343744 +1662138234066344704 +1662138234108345600 +1662138234153346560 +1662138234192347392 +1662138234237348352 +1662138234282349312 +1662138234324350208 +1662138234366351104 +1662138234408352000 +1662138234453352960 +1662138234504354048 +1662138234549355008 +1662138234591355904 +1662138234645357056 +1662138234690358016 +1662138234735358976 +1662138234780359936 +1662138234828360960 +1662138234870361856 +1662138234912362752 +1662138234957363712 +1662138235002364672 +1662138235050365696 +1662138235095366656 +1662138235143367680 +1662138235194368768 +1662138235236369664 +1662138235275370496 +1662138235317371392 +1662138235359372288 +1662138235407373312 +1662138235452374272 +1662138235497375232 +1662138235545376256 +1662138235596377344 +1662138235644378368 +1662138235686379264 +1662138235728380160 +1662138235773381120 +1662138235812381952 +1662138235854382848 +1662138235905383936 +1662138235947384832 +1662138235989385728 +1662138236037386752 +1662138236079387648 +1662138236121388544 +1662138236163389440 +1662138236211390464 +1662138236256391424 +1662138236298392320 +1662138236340393216 +1662138236388394240 +1662138236430395136 +1662138236475396096 +1662138236520397056 +1662138236565398016 +1662138236607398912 +1662138236652399872 +1662138236706401024 +1662138236748401920 +1662138236796402944 +1662138236844403968 +1662138236886404864 +1662138236931405824 +1662138236976406784 +1662138237018407680 +1662138237066408704 +1662138237108409600 +1662138237150410496 +1662138237201411584 +1662138237246412544 +1662138237288413440 +1662138237336414464 +1662138237378415360 +1662138237423416320 +1662138237471417344 +1662138237513418240 +1662138237555419136 +1662138237597420032 +1662138237642420992 +1662138237687421952 +1662138237729422848 +1662138237771423744 +1662138237813424640 +1662138237852425472 +1662138237894426368 +1662138237939427328 +1662138237981428224 +1662138238023429120 +1662138238065430016 +1662138238110430976 +1662138238152431872 +1662138238197432832 +1662138238248433920 +1662138238299435008 +1662138238350436096 +1662138238392436992 +1662138238434437888 +1662138238476438784 +1662138238515439616 +1662138238563440640 +1662138238608441600 +1662138238653442560 +1662138238695443456 +1662138238737444352 +1662138238779445248 +1662138238821446144 +1662138238863447040 +1662138238905447936 +1662138238956449024 +1662138239001449984 +1662138239049451008 +1662138239091451904 +1662138239130452736 +1662138239169453568 +1662138239211454464 +1662138239259455488 +1662138239304456448 +1662138239349457408 +1662138239400458496 +1662138239451459584 +1662138239499460608 +1662138239541461504 +1662138239586462464 +1662138239640463616 +1662138239682464512 +1662138239733465600 +1662138239778466560 +1662138239823467520 +1662138239865468416 +1662138239910469376 +1662138239961470464 +1662138240006471424 +1662138240048472320 +1662138240096473344 +1662138240141474304 +1662138240183475200 +1662138240225476096 +1662138240270477056 +1662138240315478016 +1662138240357478912 +1662138240402479872 +1662138240447480832 +1662138240492481792 +1662138240534482688 +1662138240576483584 +1662138240618484480 +1662138240663485440 +1662138240717486592 +1662138240762487552 +1662138240810488576 +1662138240849489408 +1662138240897490432 +1662138240945491456 +1662138240987492352 +1662138241032493312 +1662138241077494272 +1662138241122495232 +1662138241167496192 +1662138241209497088 +1662138241257498112 +1662138241299499008 +1662138241344499968 +1662138241389500928 +1662138241434501888 +1662138241479502848 +1662138241527503872 +1662138241569504768 +1662138241608505600 +1662138241650506496 +1662138241695507456 +1662138241743508480 +1662138241785509376 +1662138241830510336 +1662138241878511360 +1662138241923512320 +1662138241974513408 +1662138242019514368 +1662138242061515264 +1662138242106516224 +1662138242151517184 +1662138242193518080 +1662138242235518976 +1662138242277519872 +1662138242319520768 +1662138242361521664 +1662138242406522624 +1662138242454523648 +1662138242499524608 +1662138242538525440 +1662138242580526336 +1662138242622527232 +1662138242667528192 +1662138242712529152 +1662138242754530048 +1662138242796530944 +1662138242844531968 +1662138242889532928 +1662138242931533824 +1662138242982534912 +1662138243030535936 +1662138243072536832 +1662138243114537728 +1662138243159538688 +1662138243204539648 +1662138243249540608 +1662138243294541568 +1662138243336542464 +1662138243381543424 +1662138243423544320 +1662138243465545216 +1662138243510546176 +1662138243552547072 +1662138243594547968 +1662138243639548928 +1662138243681549824 +1662138243723550720 +1662138243765551616 +1662138243810552576 +1662138243861553664 +1662138243900554496 +1662138243948555520 +1662138243996556544 +1662138244044557568 +1662138244086558464 +1662138244131559424 +1662138244173560320 +1662138244218561280 +1662138244260562176 +1662138244308563200 +1662138244350564096 +1662138244392564992 +1662138244431565824 +1662138244473566720 +1662138244515567616 +1662138244557568512 +1662138244599569408 +1662138244641570304 +1662138244689571328 +1662138244737572352 +1662138244782573312 +1662138244824574208 +1662138244866575104 +1662138244914576128 +1662138244965577216 +1662138245010578176 +1662138245058579200 +1662138245106580224 +1662138245151581184 +1662138245196582144 +1662138245244583168 +1662138245292584192 +1662138245337585152 +1662138245391586304 +1662138245442587392 +1662138245487588352 +1662138245535589376 +1662138245577590272 +1662138245619591168 +1662138245667592192 +1662138245706593024 +1662138245754594048 +1662138245796594944 +1662138245847596032 +1662138245895597056 +1662138245937597952 +1662138245982598912 +1662138246027599872 +1662138246078600960 +1662138246123601920 +1662138246174603008 +1662138246216603904 +1662138246258604800 +1662138246300605696 +1662138246345606656 +1662138246387607552 +1662138246435608576 +1662138246480609536 +1662138246522610432 +1662138246567611392 +1662138246609612288 +1662138246654613248 +1662138246699614208 +1662138246744615168 +1662138246786616064 +1662138246825616896 +1662138246876617984 +1662138246918618880 +1662138246960619776 +1662138247011620864 +1662138247053621760 +1662138247104622848 +1662138247149623808 +1662138247191624704 +1662138247233625600 +1662138247284626688 +1662138247329627648 +1662138247371628544 +1662138247419629568 +1662138247461630464 +1662138247509631488 +1662138247554632448 +1662138247599633408 +1662138247650634496 +1662138247692635392 +1662138247740636416 +1662138247782637312 +1662138247833638400 +1662138247875639296 +1662138247917640192 +1662138247959641088 +1662138248007642112 +1662138248049643008 +1662138248097644032 +1662138248139644928 +1662138248181645824 +1662138248229646848 +1662138248268647680 +1662138248313648640 +1662138248355649536 +1662138248400650496 +1662138248442651392 +1662138248487652352 +1662138248532653312 +1662138248571654144 +1662138248616655104 +1662138248655655936 +1662138248697656832 +1662138248739657728 +1662138248784658688 +1662138248832659712 +1662138248874660608 +1662138248919661568 +1662138248967662592 +1662138249015663616 +1662138249057664512 +1662138249105665536 +1662138249150666496 +1662138249198667520 +1662138249240668416 +1662138249282669312 +1662138249324670208 +1662138249366671104 +1662138249411672064 +1662138249456673024 +1662138249501673984 +1662138249546674944 +1662138249594675968 +1662138249636676864 +1662138249678677760 +1662138249726678784 +1662138249768679680 +1662138249810680576 +1662138249855681536 +1662138249897682432 +1662138249942683392 +1662138249990684416 +1662138250032685312 +1662138250080686336 +1662138250122687232 +1662138250170688256 +1662138250215689216 +1662138250257690112 +1662138250305691136 +1662138250347692032 +1662138250398693120 +1662138250440694016 +1662138250485694976 +1662138250527695872 +1662138250569696768 +1662138250614697728 +1662138250662698752 +1662138250707699712 +1662138250752700672 +1662138250800701696 +1662138250845702656 +1662138250887703552 +1662138250938704640 +1662138250980705536 +1662138251022706432 +1662138251067707392 +1662138251112708352 +1662138251154709248 +1662138251196710144 +1662138251238711040 +1662138251280711936 +1662138251322712832 +1662138251364713728 +1662138251409714688 +1662138251451715584 +1662138251493716480 +1662138251541717504 +1662138251583718400 +1662138251628719360 +1662138251676720384 +1662138251715721216 +1662138251757722112 +1662138251808723200 +1662138251853724160 +1662138251898725120 +1662138251937725952 +1662138251985726976 +1662138252027727872 +1662138252072728832 +1662138252114729728 +1662138252156730624 +1662138252198731520 +1662138252246732544 +1662138252285733376 +1662138252327734272 +1662138252372735232 +1662138252420736256 +1662138252459737088 +1662138252501737984 +1662138252546738944 +1662138252591739904 +1662138252633740800 +1662138252690742016 +1662138252735742976 +1662138252783744000 +1662138252831745024 +1662138252873745920 +1662138252915746816 +1662138252957747712 +1662138252996748544 +1662138253041749504 +1662138253083750400 +1662138253125751296 +1662138253167752192 +1662138253215753216 +1662138253263754240 +1662138253314755328 +1662138253353756160 +1662138253398757120 +1662138253443758080 +1662138253494759168 +1662138253536760064 +1662138253581761024 +1662138253629762048 +1662138253683763200 +1662138253725764096 +1662138253770765056 +1662138253818766080 +1662138253857766912 +1662138253899767808 +1662138253953768960 +1662138254001769984 +1662138254043770880 +1662138254088771840 +1662138254136772864 +1662138254181773824 +1662138254223774720 +1662138254265775616 +1662138254310776576 +1662138254361777664 +1662138254406778624 +1662138254451779584 +1662138254496780544 +1662138254532781312 +1662138254577782272 +1662138254622783232 +1662138254670784256 +1662138254709785088 +1662138254751785984 +1662138254799787008 +1662138254841787904 +1662138254883788800 +1662138254931789824 +1662138254979790848 +1662138255024791808 +1662138255069792768 +1662138255111793664 +1662138255153794560 +1662138255195795456 +1662138255237796352 +1662138255282797312 +1662138255333798400 +1662138255378799360 +1662138255423800320 +1662138255462801152 +1662138255507802112 +1662138255549803008 +1662138255588803840 +1662138255633804800 +1662138255675805696 +1662138255717806592 +1662138255759807488 +1662138255801808384 +1662138255846809344 +1662138255894810368 +1662138255936811264 +1662138255981812224 +1662138256023813120 +1662138256065814016 +1662138256113815040 +1662138256161816064 +1662138256206817024 +1662138256242817792 +1662138256281818624 +1662138256329819648 +1662138256371820544 +1662138256419821568 +1662138256464822528 +1662138256506823424 +1662138256554824448 +1662138256596825344 +1662138256638826240 +1662138256683827200 +1662138256725828096 +1662138256770829056 +1662138256812829952 +1662138256860830976 +1662138256911832064 +1662138256956833024 +1662138257001833984 +1662138257052835072 +1662138257094835968 +1662138257139836928 +1662138257184837888 +1662138257235838976 +1662138257277839872 +1662138257328840960 +1662138257370841856 +1662138257412842752 +1662138257454843648 +1662138257496844544 +1662138257544845568 +1662138257586846464 +1662138257628847360 +1662138257670848256 +1662138257724849408 +1662138257769850368 +1662138257811851264 +1662138257853852160 +1662138257895853056 +1662138257937853952 +1662138257979854848 +1662138258021855744 +1662138258069856768 +1662138258117857792 +1662138258156858624 +1662138258201859584 +1662138258246860544 +1662138258294861568 +1662138258342862592 +1662138258387863552 +1662138258429864448 +1662138258471865344 +1662138258516866304 +1662138258567867392 +1662138258609868288 +1662138258654869248 +1662138258696870144 +1662138258741871104 +1662138258786872064 +1662138258825872896 +1662138258867873792 +1662138258912874752 +1662138258957875712 +1662138259005876736 +1662138259047877632 +1662138259095878656 +1662138259149879808 +1662138259200880896 +1662138259242881792 +1662138259287882752 +1662138259335883776 +1662138259386884864 +1662138259428885760 +1662138259470886656 +1662138259512887552 +1662138259560888576 +1662138259602889472 +1662138259647890432 +1662138259689891328 +1662138259734892288 +1662138259776893184 +1662138259824894208 +1662138259866895104 +1662138259911896064 +1662138259956897024 +1662138259998897920 +1662138260040898816 +1662138260088899840 +1662138260133900800 +1662138260175901696 +1662138260226902784 +1662138260268903680 +1662138260316904704 +1662138260364905728 +1662138260406906624 +1662138260448907520 +1662138260490908416 +1662138260529909248 +1662138260574910208 +1662138260616911104 +1662138260667912192 +1662138260721913344 +1662138260769914368 +1662138260814915328 +1662138260856916224 +1662138260898917120 +1662138260937917952 +1662138260985918976 +1662138261036920064 +1662138261081921024 +1662138261120921856 +1662138261165922816 +1662138261207923712 +1662138261252924672 +1662138261300925696 +1662138261342926592 +1662138261384927488 +1662138261441928704 +1662138261483929600 +1662138261528930560 +1662138261573931520 +1662138261618932480 +1662138261666933504 +1662138261708934400 +1662138261753935360 +1662138261801936384 +1662138261849937408 +1662138261900938496 +1662138261945939456 +1662138261987940352 +1662138262026941184 +1662138262074942208 +1662138262116943104 +1662138262164944128 +1662138262209945088 +1662138262254946048 +1662138262296946944 +1662138262350948096 +1662138262395949056 +1662138262437949952 +1662138262482950912 +1662138262533952000 +1662138262575952896 +1662138262617953792 +1662138262668954880 +1662138262716955904 +1662138262767956992 +1662138262815958016 +1662138262857958912 +1662138262905959936 +1662138262950960896 +1662138262992961792 +1662138263043962880 +1662138263088963840 +1662138263130964736 +1662138263178965760 +1662138263220966656 +1662138263265967616 +1662138263304968448 +1662138263355969536 +1662138263400970496 +1662138263451971584 +1662138263493972480 +1662138263544973568 +1662138263592974592 +1662138263634975488 +1662138263673976320 +1662138263718977280 +1662138263763978240 +1662138263811979264 +1662138263859980288 +1662138263901981184 +1662138263949982208 +1662138263991983104 +1662138264036984064 +1662138264087985152 +1662138264129986048 +1662138264174987008 +1662138264219987968 +1662138264258988800 +1662138264303989760 +1662138264354990848 +1662138264399991808 +1662138264444992768 +1662138264483993600 +1662138264525994496 +1662138264573995520 +1662138264618996480 +1662138264660997376 +1662138264702998272 +1662138264762999552 +1662138264808000512 +1662138264850001408 +1662138264898002432 +1662138264943003392 +1662138264985004288 +1662138265030005248 +1662138265072006144 +1662138265114007040 +1662138265159008000 +1662138265207009024 +1662138265249009920 +1662138265300011008 +1662138265348012032 +1662138265390012928 +1662138265432013824 +1662138265477014784 +1662138265522015744 +1662138265564016640 +1662138265606017536 +1662138265651018496 +1662138265696019456 +1662138265744020480 +1662138265786021376 +1662138265831022336 +1662138265873023232 +1662138265918024192 +1662138265966025216 +1662138266008026112 +1662138266050027008 +1662138266095027968 +1662138266146029056 +1662138266188029952 +1662138266239031040 +1662138266284032000 +1662138266332033024 +1662138266371033856 +1662138266413034752 +1662138266455035648 +1662138266497036544 +1662138266542037504 +1662138266587038464 +1662138266629039360 +1662138266674040320 +1662138266725041408 +1662138266770042368 +1662138266821043456 +1662138266863044352 +1662138266908045312 +1662138266950046208 +1662138266992047104 +1662138267037048064 +1662138267079048960 +1662138267121049856 +1662138267166050816 +1662138267208051712 +1662138267253052672 +1662138267298053632 +1662138267343054592 +1662138267391055616 +1662138267433056512 +1662138267475057408 +1662138267520058368 +1662138267568059392 +1662138267610060288 +1662138267649061120 +1662138267694062080 +1662138267739063040 +1662138267778063872 +1662138267820064768 +1662138267862065664 +1662138267907066624 +1662138267952067584 +1662138267994068480 +1662138268039069440 +1662138268078070272 +1662138268117071104 +1662138268165072128 +1662138268210073088 +1662138268264074240 +1662138268306075136 +1662138268348076032 +1662138268387076864 +1662138268429077760 +1662138268471078656 +1662138268519079680 +1662138268564080640 +1662138268606081536 +1662138268657082624 +1662138268696083456 +1662138268744084480 +1662138268792085504 +1662138268831086336 +1662138268879087360 +1662138268924088320 +1662138268972089344 +1662138269017090304 +1662138269068091392 +1662138269107092224 +1662138269152093184 +1662138269194094080 +1662138269236094976 +1662138269290096128 +1662138269335097088 +1662138269377097984 +1662138269419098880 +1662138269464099840 +1662138269506100736 +1662138269548101632 +1662138269590102528 +1662138269632103424 +1662138269680104448 +1662138269731105536 +1662138269776106496 +1662138269818107392 +1662138269863108352 +1662138269905109248 +1662138269956110336 +1662138269998111232 +1662138270040112128 +1662138270085113088 +1662138270130114048 +1662138270172114944 +1662138270217115904 +1662138270262116864 +1662138270304117760 +1662138270352118784 +1662138270394119680 +1662138270442120704 +1662138270484121600 +1662138270529122560 +1662138270571123456 +1662138270613124352 +1662138270661125376 +1662138270703126272 +1662138270745127168 +1662138270790128128 +1662138270841129216 +1662138270886130176 +1662138270928131072 +1662138270973132032 +1662138271015132928 +1662138271063133952 +1662138271108134912 +1662138271156135936 +1662138271201136896 +1662138271243137792 +1662138271294138880 +1662138271336139776 +1662138271384140800 +1662138271426141696 +1662138271477142784 +1662138271519143680 +1662138271558144512 +1662138271600145408 +1662138271645146368 +1662138271690147328 +1662138271729148160 +1662138271777149184 +1662138271819150080 +1662138271864151040 +1662138271912152064 +1662138271954152960 +1662138271996153856 +1662138272038154752 +1662138272080155648 +1662138272125156608 +1662138272173157632 +1662138272215158528 +1662138272260159488 +1662138272305160448 +1662138272347161344 +1662138272389162240 +1662138272434163200 +1662138272485164288 +1662138272530165248 +1662138272572166144 +1662138272614167040 +1662138272659168000 +1662138272716169216 +1662138272758170112 +1662138272803171072 +1662138272848172032 +1662138272893172992 +1662138272935173888 +1662138272983174912 +1662138273028175872 +1662138273070176768 +1662138273118177792 +1662138273172178944 +1662138273217179904 +1662138273265180928 +1662138273313181952 +1662138273358182912 +1662138273406183936 +1662138273448184832 +1662138273490185728 +1662138273538186752 +1662138273583187712 +1662138273634188800 +1662138273676189696 +1662138273721190656 +1662138273766191616 +1662138273808192512 +1662138273850193408 +1662138273892194304 +1662138273931195136 +1662138273970195968 +1662138274012196864 +1662138274057197824 +1662138274099198720 +1662138274141199616 +1662138274183200512 +1662138274231201536 +1662138274279202560 +1662138274324203520 +1662138274372204544 +1662138274414205440 +1662138274459206400 +1662138274501207296 +1662138274549208320 +1662138274591209216 +1662138274633210112 +1662138274681211136 +1662138274729212160 +1662138274771213056 +1662138274813213952 +1662138274855214848 +1662138274897215744 +1662138274939216640 +1662138274981217536 +1662138275026218496 +1662138275071219456 +1662138275113220352 +1662138275155221248 +1662138275197222144 +1662138275242223104 +1662138275287224064 +1662138275332225024 +1662138275380226048 +1662138275425227008 +1662138275473228032 +1662138275518228992 +1662138275563229952 +1662138275602230784 +1662138275647231744 +1662138275689232640 +1662138275734233600 +1662138275776234496 +1662138275821235456 +1662138275863236352 +1662138275905237248 +1662138275953238272 +1662138275998239232 +1662138276040240128 +1662138276085241088 +1662138276133242112 +1662138276178243072 +1662138276220243968 +1662138276265244928 +1662138276307245824 +1662138276355246848 +1662138276394247680 +1662138276445248768 +1662138276487249664 +1662138276529250560 +1662138276577251584 +1662138276622252544 +1662138276673253632 +1662138276718254592 +1662138276760255488 +1662138276802256384 +1662138276850257408 +1662138276892258304 +1662138276940259328 +1662138276982260224 +1662138277030261248 +1662138277072262144 +1662138277120263168 +1662138277165264128 +1662138277210265088 +1662138277252265984 +1662138277303267072 +1662138277342267904 +1662138277384268800 +1662138277423269632 +1662138277465270528 +1662138277507271424 +1662138277555272448 +1662138277600273408 +1662138277645274368 +1662138277696275456 +1662138277741276416 +1662138277783277312 +1662138277825278208 +1662138277864279040 +1662138277906279936 +1662138277951280896 +1662138277999281920 +1662138278044282880 +1662138278086283776 +1662138278125284608 +1662138278179285760 +1662138278224286720 +1662138278266287616 +1662138278308288512 +1662138278350289408 +1662138278398290432 +1662138278443291392 +1662138278485292288 +1662138278524293120 +1662138278566294016 +1662138278608294912 +1662138278662296064 +1662138278710297088 +1662138278752297984 +1662138278800299008 +1662138278845299968 +1662138278887300864 +1662138278929301760 +1662138278971302656 +1662138279016303616 +1662138279058304512 +1662138279100305408 +1662138279151306496 +1662138279196307456 +1662138279244308480 +1662138279295309568 +1662138279343310592 +1662138279385311488 +1662138279430312448 +1662138279475313408 +1662138279526314496 +1662138279571315456 +1662138279634316800 +1662138279673317632 +1662138279721318656 +1662138279766319616 +1662138279820320768 +1662138279862321664 +1662138279907322624 +1662138279952323584 +1662138279994324480 +1662138280039325440 +1662138280081326336 +1662138280126327296 +1662138280174328320 +1662138280222329344 +1662138280264330240 +1662138280306331136 +1662138280348332032 +1662138280390332928 +1662138280438333952 +1662138280483334912 +1662138280525335808 +1662138280567336704 +1662138280615337728 +1662138280663338752 +1662138280705339648 +1662138280747340544 +1662138280792341504 +1662138280834342400 +1662138280879343360 +1662138280921344256 +1662138280966345216 +1662138281011346176 +1662138281056347136 +1662138281104348160 +1662138281152349184 +1662138281194350080 +1662138281242351104 +1662138281287352064 +1662138281338353152 +1662138281380354048 +1662138281419354880 +1662138281461355776 +1662138281503356672 +1662138281557357824 +1662138281599358720 +1662138281644359680 +1662138281689360640 +1662138281731361536 +1662138281782362624 +1662138281824363520 +1662138281878364672 +1662138281926365696 +1662138281971366656 +1662138282022367744 +1662138282064368640 +1662138282106369536 +1662138282148370432 +1662138282190371328 +1662138282232372224 +1662138282271373056 +1662138282313373952 +1662138282352374784 +1662138282397375744 +1662138282442376704 +1662138282484377600 +1662138282532378624 +1662138282574379520 +1662138282619380480 +1662138282661381376 +1662138282703382272 +1662138282745383168 +1662138282787384064 +1662138282829384960 +1662138282889386240 +1662138282934387200 +1662138282976388096 +1662138283024389120 +1662138283066390016 +1662138283108390912 +1662138283153391872 +1662138283195392768 +1662138283237393664 +1662138283279394560 +1662138283330395648 +1662138283375396608 +1662138283426397696 +1662138283477398784 +1662138283519399680 +1662138283561400576 +1662138283603401472 +1662138283645402368 +1662138283687403264 +1662138283729404160 +1662138283768404992 +1662138283810405888 +1662138283855406848 +1662138283900407808 +1662138283942408704 +1662138283987409664 +1662138284032410624 +1662138284077411584 +1662138284122412544 +1662138284167413504 +1662138284212414464 +1662138284254415360 +1662138284302416384 +1662138284350417408 +1662138284404418560 +1662138284446419456 +1662138284488420352 +1662138284536421376 +1662138284584422400 +1662138284626423296 +1662138284668424192 +1662138284728425472 +1662138284770426368 +1662138284812427264 +1662138284854428160 +1662138284896429056 +1662138284941430016 +1662138284992431104 +1662138285037432064 +1662138285082433024 +1662138285130434048 +1662138285178435072 +1662138285229436160 +1662138285271437056 +1662138285319438080 +1662138285370439168 +1662138285418440192 +1662138285460441088 +1662138285502441984 +1662138285550443008 +1662138285601444096 +1662138285655445248 +1662138285694446080 +1662138285742447104 +1662138285784448000 +1662138285826448896 +1662138285880450048 +1662138285928451072 +1662138285970451968 +1662138286012452864 +1662138286057453824 +1662138286108454912 +1662138286165456128 +1662138286207457024 +1662138286249457920 +1662138286297458944 +1662138286342459904 +1662138286390460928 +1662138286435461888 +1662138286480462848 +1662138286519463680 +1662138286564464640 +1662138286609465600 +1662138286660466688 +1662138286711467776 +1662138286756468736 +1662138286804469760 +1662138286852470784 +1662138286891471616 +1662138286933472512 +1662138286975473408 +1662138287020474368 +1662138287071475456 +1662138287113476352 +1662138287152477184 +1662138287197478144 +1662138287239479040 +1662138287281479936 +1662138287320480768 +1662138287362481664 +1662138287416482816 +1662138287458483712 +1662138287500484608 +1662138287545485568 +1662138287587486464 +1662138287629487360 +1662138287677488384 +1662138287719489280 +1662138287761490176 +1662138287806491136 +1662138287851492096 +1662138287893492992 +1662138287938493952 +1662138287983494912 +1662138288025495808 +1662138288067496704 +1662138288118497792 +1662138288157498624 +1662138288199499520 +1662138288238500352 +1662138288283501312 +1662138288325502208 +1662138288373503232 +1662138288418504192 +1662138288460505088 +1662138288502505984 +1662138288547506944 +1662138288592507904 +1662138288634508800 +1662138288676509696 +1662138288718510592 +1662138288763511552 +1662138288814512640 +1662138288856513536 +1662138288898514432 +1662138288940515328 +1662138288985516288 +1662138289027517184 +1662138289075518208 +1662138289117519104 +1662138289159520000 +1662138289201520896 +1662138289246521856 +1662138289291522816 +1662138289336523776 +1662138289384524800 +1662138289435525888 +1662138289480526848 +1662138289528527872 +1662138289576528896 +1662138289621529856 +1662138289663530752 +1662138289711531776 +1662138289759532800 +1662138289810533888 +1662138289852534784 +1662138289897535744 +1662138289942536704 +1662138289981537536 +1662138290026538496 +1662138290068539392 +1662138290122540544 +1662138290167541504 +1662138290215542528 +1662138290260543488 +1662138290302544384 +1662138290350545408 +1662138290392546304 +1662138290446547456 +1662138290494548480 +1662138290539549440 +1662138290584550400 +1662138290626551296 +1662138290674552320 +1662138290725553408 +1662138290767554304 +1662138290815555328 +1662138290857556224 +1662138290899557120 +1662138290944558080 +1662138290995559168 +1662138291037560064 +1662138291082561024 +1662138291124561920 +1662138291166562816 +1662138291208563712 +1662138291253564672 +1662138291304565760 +1662138291352566784 +1662138291394567680 +1662138291439568640 +1662138291484569600 +1662138291532570624 +1662138291574571520 +1662138291622572544 +1662138291667573504 +1662138291712574464 +1662138291760575488 +1662138291802576384 +1662138291844577280 +1662138291889578240 +1662138291931579136 +1662138291979580160 +1662138292021581056 +1662138292063581952 +1662138292105582848 +1662138292147583744 +1662138292198584832 +1662138292243585792 +1662138292288586752 +1662138292333587712 +1662138292378588672 +1662138292429589760 +1662138292471590656 +1662138292510591488 +1662138292552592384 +1662138292597593344 +1662138292645594368 +1662138292687595264 +1662138292726596096 +1662138292768596992 +1662138292813597952 +1662138292861598976 +1662138292903599872 +1662138292948600832 +1662138292990601728 +1662138293032602624 +1662138293077603584 +1662138293125604608 +1662138293170605568 +1662138293218606592 +1662138293266607616 +1662138293311608576 +1662138293359609600 +1662138293404610560 +1662138293446611456 +1662138293488612352 +1662138293533613312 +1662138293581614336 +1662138293623615232 +1662138293665616128 +1662138293710617088 +1662138293755618048 +1662138293800619008 +1662138293845619968 +1662138293887620864 +1662138293929621760 +1662138293989623040 +1662138294037624064 +1662138294085625088 +1662138294127625984 +1662138294172626944 +1662138294214627840 +1662138294265628928 +1662138294307629824 +1662138294349630720 +1662138294394631680 +1662138294436632576 +1662138294481633536 +1662138294526634496 +1662138294574635520 +1662138294619636480 +1662138294661637376 +1662138294706638336 +1662138294751639296 +1662138294796640256 +1662138294841641216 +1662138294886642176 +1662138294931643136 +1662138294973644032 +1662138295018644992 +1662138295063645952 +1662138295105646848 +1662138295153647872 +1662138295195648768 +1662138295246649856 +1662138295288650752 +1662138295339651840 +1662138295384652800 +1662138295426653696 +1662138295480654848 +1662138295531655936 +1662138295573656832 +1662138295618657792 +1662138295663658752 +1662138295708659712 +1662138295765660928 +1662138295810661888 +1662138295852662784 +1662138295897663744 +1662138295936664576 +1662138295975665408 +1662138296026666496 +1662138296068667392 +1662138296110668288 +1662138296155669248 +1662138296200670208 +1662138296242671104 +1662138296284672000 +1662138296329672960 +1662138296380674048 +1662138296419674880 +1662138296470675968 +1662138296512676864 +1662138296554677760 +1662138296602678784 +1662138296644679680 +1662138296686680576 +1662138296737681664 +1662138296779682560 +1662138296821683456 +1662138296872684544 +1662138296917685504 +1662138296959686400 +1662138297016687616 +1662138297061688576 +1662138297109689600 +1662138297154690560 +1662138297193691392 +1662138297235692288 +1662138297289693440 +1662138297337694464 +1662138297382695424 +1662138297424696320 +1662138297466697216 +1662138297508698112 +1662138297559699200 +1662138297601700096 +1662138297646701056 +1662138297697702144 +1662138297742703104 +1662138297784704000 +1662138297823704832 +1662138297862705664 +1662138297901706496 +1662138297952707584 +1662138298000708608 +1662138298045709568 +1662138298090710528 +1662138298141711616 +1662138298183712512 +1662138298225713408 +1662138298270714368 +1662138298315715328 +1662138298360716288 +1662138298405717248 +1662138298447718144 +1662138298492719104 +1662138298534720000 +1662138298576720896 +1662138298618721792 +1662138298660722688 +1662138298702723584 +1662138298744724480 +1662138298798725632 +1662138298840726528 +1662138298888727552 +1662138298936728576 +1662138298981729536 +1662138299023730432 +1662138299065731328 +1662138299107732224 +1662138299155733248 +1662138299197734144 +1662138299239735040 +1662138299287736064 +1662138299329736960 +1662138299374737920 +1662138299428739072 +1662138299479740160 +1662138299527741184 +1662138299578742272 +1662138299620743168 +1662138299662744064 +1662138299707745024 +1662138299749745920 +1662138299803747072 +1662138299848748032 +1662138299902749184 +1662138299944750080 +1662138299986750976 +1662138300028751872 +1662138300073752832 +1662138300118753792 +1662138300160754688 +1662138300199755520 +1662138300241756416 +1662138300286757376 +1662138300331758336 +1662138300373759232 +1662138300421760256 +1662138300463761152 +1662138300505762048 +1662138300559763200 +1662138300601764096 +1662138300643764992 +1662138300691766016 +1662138300730766848 +1662138300781767936 +1662138300823768832 +1662138300865769728 +1662138300904770560 +1662138300949771520 +1662138300997772544 +1662138301039773440 +1662138301087774464 +1662138301129775360 +1662138301174776320 +1662138301222777344 +1662138301264778240 +1662138301306779136 +1662138301351780096 +1662138301399781120 +1662138301441782016 +1662138301489783040 +1662138301531783936 +1662138301573784832 +1662138301621785856 +1662138301666786816 +1662138301708787712 +1662138301753788672 +1662138301795789568 +1662138301837790464 +1662138301879791360 +1662138301927792384 +1662138301978793472 +1662138302023794432 +1662138302065795328 +1662138302116796416 +1662138302167797504 +1662138302215798528 +1662138302266799616 +1662138302308800512 +1662138302356801536 +1662138302398802432 +1662138302446803456 +1662138302488804352 +1662138302533805312 +1662138302587806464 +1662138302629807360 +1662138302671808256 +1662138302713809152 +1662138302758810112 +1662138302803811072 +1662138302851812096 +1662138302896813056 +1662138302938813952 +1662138302983814912 +1662138303025815808 +1662138303073816832 +1662138303118817792 +1662138303163818752 +1662138303208819712 +1662138303256820736 +1662138303298821632 +1662138303340822528 +1662138303391823616 +1662138303439824640 +1662138303487825664 +1662138303532826624 +1662138303577827584 +1662138303625828608 +1662138303667829504 +1662138303709830400 +1662138303754831360 +1662138303799832320 +1662138303844833280 +1662138303886834176 +1662138303937835264 +1662138303982836224 +1662138304024837120 +1662138304066838016 +1662138304114839040 +1662138304171840256 +1662138304213841152 +1662138304264842240 +1662138304309843200 +1662138304357844224 +1662138304405845248 +1662138304450846208 +1662138304492847104 +1662138304540848128 +1662138304585849088 +1662138304627849984 +1662138304675851008 +1662138304720851968 +1662138304765852928 +1662138304813853952 +1662138304855854848 +1662138304903855872 +1662138304948856832 +1662138304999857920 +1662138305047858944 +1662138305089859840 +1662138305140860928 +1662138305194862080 +1662138305239863040 +1662138305278863872 +1662138305326864896 +1662138305374865920 +1662138305419866880 +1662138305461867776 +1662138305509868800 +1662138305557869824 +1662138305599870720 +1662138305647871744 +1662138305689872640 +1662138305734873600 +1662138305776874496 +1662138305830875648 +1662138305878876672 +1662138305929877760 +1662138305974878720 +1662138306019879680 +1662138306073880832 +1662138306115881728 +1662138306160882688 +1662138306202883584 +1662138306250884608 +1662138306292885504 +1662138306334886400 +1662138306376887296 +1662138306421888256 +1662138306463889152 +1662138306505890048 +1662138306565891328 +1662138306610892288 +1662138306652893184 +1662138306694894080 +1662138306742895104 +1662138306787896064 +1662138306838897152 +1662138306880898048 +1662138306925899008 +1662138306970899968 +1662138307021901056 +1662138307060901888 +1662138307105902848 +1662138307147903744 +1662138307192904704 +1662138307237905664 +1662138307288906752 +1662138307327907584 +1662138307375908608 +1662138307420909568 +1662138307468910592 +1662138307516911616 +1662138307561912576 +1662138307612913664 +1662138307654914560 +1662138307705915648 +1662138307753916672 +1662138307801917696 +1662138307852918784 +1662138307900919808 +1662138307948920832 +1662138307990921728 +1662138308032922624 +1662138308080923648 +1662138308125924608 +1662138308176925696 +1662138308221926656 +1662138308266927616 +1662138308308928512 +1662138308356929536 +1662138308401930496 +1662138308446931456 +1662138308494932480 +1662138308545933568 +1662138308584934400 +1662138308623935232 +1662138308668936192 +1662138308713937152 +1662138308758938112 +1662138308800939008 +1662138308845939968 +1662138308887940864 +1662138308929941760 +1662138308980942848 +1662138309022943744 +1662138309064944640 +1662138309109945600 +1662138309157946624 +1662138309205947648 +1662138309256948736 +1662138309301949696 +1662138309352950784 +1662138309397951744 +1662138309442952704 +1662138309493953792 +1662138309535954688 +1662138309583955712 +1662138309634956800 +1662138309676957696 +1662138309718958592 +1662138309763959552 +1662138309805960448 +1662138309859961600 +1662138309907962624 +1662138309949963520 +1662138310006964736 +1662138310048965632 +1662138310090966528 +1662138310138967552 +1662138310183968512 +1662138310225969408 +1662138310282970624 +1662138310321971456 +1662138310363972352 +1662138310411973376 +1662138310456974336 +1662138310501975296 +1662138310552976384 +1662138310594977280 +1662138310639978240 +1662138310684979200 +1662138310729980160 +1662138310771981056 +1662138310819982080 +1662138310861982976 +1662138310909984000 +1662138310960985088 +1662138311011986176 +1662138311065987328 +1662138311110988288 +1662138311152989184 +1662138311194990080 +1662138311239991040 +1662138311284992000 +1662138311332993024 +1662138311380994048 +1662138311428995072 +1662138311479996160 +1662138311530997248 +1662138311578998272 +1662138311623999232 +1662138311675000320 +1662138311717001216 +1662138311759002112 +1662138311804003072 +1662138311855004160 +1662138311906005248 +1662138311951006208 +1662138311993007104 +1662138312044008192 +1662138312089009152 +1662138312134010112 +1662138312179011072 +1662138312224012032 +1662138312266012928 +1662138312314013952 +1662138312362014976 +1662138312407015936 +1662138312449016832 +1662138312497017856 +1662138312536018688 +1662138312593019904 +1662138312638020864 +1662138312686021888 +1662138312731022848 +1662138312782023936 +1662138312830024960 +1662138312878025984 +1662138312920026880 +1662138312962027776 +1662138313010028800 +1662138313064029952 +1662138313112030976 +1662138313163032064 +1662138313208033024 +1662138313253033984 +1662138313301035008 +1662138313343035904 +1662138313388036864 +1662138313427037696 +1662138313472038656 +1662138313517039616 +1662138313565040640 +1662138313610041600 +1662138313658042624 +1662138313703043584 +1662138313748044544 +1662138313787045376 +1662138313841046528 +1662138313886047488 +1662138313931048448 +1662138313976049408 +1662138314021050368 +1662138314063051264 +1662138314111052288 +1662138314156053248 +1662138314201054208 +1662138314258055424 +1662138314303056384 +1662138314345057280 +1662138314387058176 +1662138314432059136 +1662138314474060032 +1662138314516060928 +1662138314564061952 +1662138314612062976 +1662138314657063936 +1662138314696064768 +1662138314738065664 +1662138314783066624 +1662138314783066624 +1662138314828067584 +1662138314873068544 +1662138314915069440 +1662138314957070336 +1662138314999071232 +1662138315041072128 +1662138315080072960 +1662138315128073984 +1662138315176075008 +1662138315224076032 +1662138315269076992 +1662138315317078016 +1662138315362078976 +1662138315410080000 +1662138315461081088 +1662138315509082112 +1662138315551083008 +1662138315599084032 +1662138315641084928 +1662138315683085824 +1662138315728086784 +1662138315770087680 +1662138315815088640 +1662138315854089472 +1662138315905090560 +1662138315947091456 +1662138315992092416 +1662138316037093376 +1662138316082094336 +1662138316133095424 +1662138316178096384 +1662138316223097344 +1662138316265098240 +1662138316310099200 +1662138316358100224 +1662138316397101056 +1662138316442102016 +1662138316493103104 +1662138316538104064 +1662138316583105024 +1662138316625105920 +1662138316676107008 +1662138316727108096 +1662138316772109056 +1662138316814109952 +1662138316859110912 +1662138316901111808 +1662138316946112768 +1662138316994113792 +1662138317036114688 +1662138317081115648 +1662138317123116544 +1662138317165117440 diff --git a/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_light.txt b/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_light.txt new file mode 100644 index 0000000000..cca6f70bc4 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_light.txt @@ -0,0 +1,2421 @@ +1662135911410189568 +1662135911452190464 +1662135911491191296 +1662135911539192320 +1662135911584193280 +1662135911638194432 +1662135911683195392 +1662135911731196416 +1662135911776197376 +1662135911824198400 +1662135911866199296 +1662135911908200192 +1662135911953201152 +1662135912001202176 +1662135912052203264 +1662135912094204160 +1662135912136205056 +1662135912181206016 +1662135912232207104 +1662135912280208128 +1662135912322209024 +1662135912370210048 +1662135912412210944 +1662135912454211840 +1662135912496212736 +1662135912538213632 +1662135912583214592 +1662135912625215488 +1662135912667216384 +1662135912712217344 +1662135912754218240 +1662135912796219136 +1662135912844220160 +1662135912889221120 +1662135912928221952 +1662135912970222848 +1662135913015223808 +1662135913057224704 +1662135913108225792 +1662135913159226880 +1662135913210227968 +1662135913249228800 +1662135913306230016 +1662135913351230976 +1662135913396231936 +1662135913441232896 +1662135913492233984 +1662135913540235008 +1662135913585235968 +1662135913639237120 +1662135913681238016 +1662135913729239040 +1662135913774240000 +1662135913825241088 +1662135913867241984 +1662135913909242880 +1662135913951243776 +1662135913993244672 +1662135914041245696 +1662135914086246656 +1662135914131247616 +1662135914173248512 +1662135914218249472 +1662135914260250368 +1662135914302251264 +1662135914350252288 +1662135914392253184 +1662135914437254144 +1662135914491255296 +1662135914530256128 +1662135914569256960 +1662135914611257856 +1662135914653258752 +1662135914698259712 +1662135914740260608 +1662135914782261504 +1662135914824262400 +1662135914866263296 +1662135914908264192 +1662135914953265152 +1662135914998266112 +1662135915046267136 +1662135915091268096 +1662135915136269056 +1662135915181270016 +1662135915223270912 +1662135915277272064 +1662135915325273088 +1662135915364273920 +1662135915415275008 +1662135915457275904 +1662135915499276800 +1662135915544277760 +1662135915586278656 +1662135915628279552 +1662135915676280576 +1662135915718281472 +1662135915772282624 +1662135915811283456 +1662135915853284352 +1662135915907285504 +1662135915949286400 +1662135915994287360 +1662135916039288320 +1662135916093289472 +1662135916135290368 +1662135916177291264 +1662135916222292224 +1662135916267293184 +1662135916309294080 +1662135916351294976 +1662135916393295872 +1662135916438296832 +1662135916486297856 +1662135916531298816 +1662135916573299712 +1662135916621300736 +1662135916669301760 +1662135916714302720 +1662135916759303680 +1662135916807304704 +1662135916849305600 +1662135916891306496 +1662135916933307392 +1662135916984308480 +1662135917035309568 +1662135917080310528 +1662135917125311488 +1662135917167312384 +1662135917212313344 +1662135917257314304 +1662135917311315456 +1662135917356316416 +1662135917395317248 +1662135917437318144 +1662135917482319104 +1662135917524320000 +1662135917569320960 +1662135917623322112 +1662135917668323072 +1662135917716324096 +1662135917758324992 +1662135917800325888 +1662135917839326720 +1662135917887327744 +1662135917929328640 +1662135917971329536 +1662135918013330432 +1662135918052331264 +1662135918094332160 +1662135918136333056 +1662135918178333952 +1662135918220334848 +1662135918262335744 +1662135918307336704 +1662135918361337856 +1662135918406338816 +1662135918448339712 +1662135918508340992 +1662135918550341888 +1662135918592342784 +1662135918643343872 +1662135918685344768 +1662135918733345792 +1662135918775346688 +1662135918817347584 +1662135918856348416 +1662135918898349312 +1662135918946350336 +1662135918994351360 +1662135919036352256 +1662135919078353152 +1662135919120354048 +1662135919159354880 +1662135919201355776 +1662135919246356736 +1662135919294357760 +1662135919342358784 +1662135919387359744 +1662135919429360640 +1662135919474361600 +1662135919513362432 +1662135919555363328 +1662135919597364224 +1662135919645365248 +1662135919690366208 +1662135919732367104 +1662135919774368000 +1662135919816368896 +1662135919861369856 +1662135919906370816 +1662135919951371776 +1662135920005372928 +1662135920047373824 +1662135920095374848 +1662135920140375808 +1662135920185376768 +1662135920230377728 +1662135920272378624 +1662135920314379520 +1662135920356380416 +1662135920398381312 +1662135920440382208 +1662135920488383232 +1662135920536384256 +1662135920578385152 +1662135920617385984 +1662135920659386880 +1662135920704387840 +1662135920749388800 +1662135920797389824 +1662135920851390976 +1662135920896391936 +1662135920941392896 +1662135920983393792 +1662135921025394688 +1662135921070395648 +1662135921115396608 +1662135921154397440 +1662135921196398336 +1662135921250399488 +1662135921292400384 +1662135921358401792 +1662135921406402816 +1662135921448403712 +1662135921496404736 +1662135921544405760 +1662135921595406848 +1662135921640407808 +1662135921685408768 +1662135921724409600 +1662135921775410688 +1662135921823411712 +1662135921865412608 +1662135921907413504 +1662135921952414464 +1662135921997415424 +1662135922039416320 +1662135922081417216 +1662135922123418112 +1662135922165419008 +1662135922207419904 +1662135922249420800 +1662135922300421888 +1662135922345422848 +1662135922390423808 +1662135922435424768 +1662135922480425728 +1662135922522426624 +1662135922567427584 +1662135922609428480 +1662135922654429440 +1662135922705430528 +1662135922750431488 +1662135922792432384 +1662135922840433408 +1662135922897434624 +1662135922942435584 +1662135922987436544 +1662135923029437440 +1662135923071438336 +1662135923113439232 +1662135923155440128 +1662135923203441152 +1662135923245442048 +1662135923284442880 +1662135923326443776 +1662135923365444608 +1662135923407445504 +1662135923449446400 +1662135923491447296 +1662135923533448192 +1662135923578449152 +1662135923620450048 +1662135923674451200 +1662135923716452096 +1662135923758452992 +1662135923800453888 +1662135923848454912 +1662135923890455808 +1662135923932456704 +1662135923983457792 +1662135924025458688 +1662135924079459840 +1662135924121460736 +1662135924163461632 +1662135924208462592 +1662135924268463872 +1662135924310464768 +1662135924355465728 +1662135924394466560 +1662135924436467456 +1662135924481468416 +1662135924532469504 +1662135924577470464 +1662135924616471296 +1662135924667472384 +1662135924709473280 +1662135924751474176 +1662135924793475072 +1662135924835475968 +1662135924883476992 +1662135924925477888 +1662135924973478912 +1662135925015479808 +1662135925057480704 +1662135925099481600 +1662135925147482624 +1662135925186483456 +1662135925228484352 +1662135925273485312 +1662135925315486208 +1662135925360487168 +1662135925408488192 +1662135925453489152 +1662135925495490048 +1662135925540491008 +1662135925582491904 +1662135925624492800 +1662135925663493632 +1662135925708494592 +1662135925750495488 +1662135925798496512 +1662135925846497536 +1662135925888498432 +1662135925930499328 +1662135925987500544 +1662135926035501568 +1662135926077502464 +1662135926122503424 +1662135926164504320 +1662135926209505280 +1662135926263506432 +1662135926311507456 +1662135926353508352 +1662135926401509376 +1662135926449510400 +1662135926488511232 +1662135926530512128 +1662135926578513152 +1662135926620514048 +1662135926665515008 +1662135926707515904 +1662135926749516800 +1662135926791517696 +1662135926833518592 +1662135926875519488 +1662135926914520320 +1662135926959521280 +1662135927001522176 +1662135927055523328 +1662135927097524224 +1662135927148525312 +1662135927199526400 +1662135927238527232 +1662135927280528128 +1662135927322529024 +1662135927367529984 +1662135927406530816 +1662135927445531648 +1662135927487532544 +1662135927538533632 +1662135927580534528 +1662135927622535424 +1662135927664536320 +1662135927709537280 +1662135927760538368 +1662135927802539264 +1662135927850540288 +1662135927892541184 +1662135927937542144 +1662135927988543232 +1662135928030544128 +1662135928075545088 +1662135928120546048 +1662135928162546944 +1662135928207547904 +1662135928255548928 +1662135928303549952 +1662135928345550848 +1662135928393551872 +1662135928435552768 +1662135928477553664 +1662135928519554560 +1662135928561555456 +1662135928603556352 +1662135928645557248 +1662135928687558144 +1662135928729559040 +1662135928774560000 +1662135928822561024 +1662135928864561920 +1662135928912562944 +1662135928954563840 +1662135929002564864 +1662135929041565696 +1662135929083566592 +1662135929125567488 +1662135929167568384 +1662135929212569344 +1662135929257570304 +1662135929299571200 +1662135929341572096 +1662135929386573056 +1662135929428573952 +1662135929467574784 +1662135929512575744 +1662135929566576896 +1662135929608577792 +1662135929659578880 +1662135929707579904 +1662135929749580800 +1662135929800581888 +1662135929842582784 +1662135929884583680 +1662135929926584576 +1662135929968585472 +1662135930010586368 +1662135930061587456 +1662135930103588352 +1662135930154589440 +1662135930199590400 +1662135930241591296 +1662135930283592192 +1662135930328593152 +1662135930367593984 +1662135930415595008 +1662135930460595968 +1662135930511597056 +1662135930553597952 +1662135930598598912 +1662135930640599808 +1662135930685600768 +1662135930730601728 +1662135930778602752 +1662135930820603648 +1662135930865604608 +1662135930907605504 +1662135930952606464 +1662135930997607424 +1662135931039608320 +1662135931081609216 +1662135931135610368 +1662135931180611328 +1662135931222612224 +1662135931270613248 +1662135931321614336 +1662135931372615424 +1662135931420616448 +1662135931465617408 +1662135931507618304 +1662135931549619200 +1662135931591620096 +1662135931639621120 +1662135931684622080 +1662135931726622976 +1662135931774624000 +1662135931819624960 +1662135931870626048 +1662135931912626944 +1662135931960627968 +1662135932002628864 +1662135932065630208 +1662135932107631104 +1662135932149632000 +1662135932209633280 +1662135932254634240 +1662135932299635200 +1662135932350636288 +1662135932392637184 +1662135932434638080 +1662135932482639104 +1662135932524640000 +1662135932566640896 +1662135932608641792 +1662135932650642688 +1662135932695643648 +1662135932743644672 +1662135932785645568 +1662135932830646528 +1662135932875647488 +1662135932917648384 +1662135932959649280 +1662135933004650240 +1662135933049651200 +1662135933091652096 +1662135933133652992 +1662135933178653952 +1662135933223654912 +1662135933268655872 +1662135933310656768 +1662135933358657792 +1662135933403658752 +1662135933454659840 +1662135933499660800 +1662135933541661696 +1662135933589662720 +1662135933631663616 +1662135933679664640 +1662135933718665472 +1662135933757666304 +1662135933802667264 +1662135933853668352 +1662135933898669312 +1662135933940670208 +1662135933979671040 +1662135934024672000 +1662135934066672896 +1662135934111673856 +1662135934156674816 +1662135934210675968 +1662135934255676928 +1662135934297677824 +1662135934345678848 +1662135934387679744 +1662135934429680640 +1662135934468681472 +1662135934513682432 +1662135934555683328 +1662135934600684288 +1662135934642685184 +1662135934684686080 +1662135934729687040 +1662135934771687936 +1662135934816688896 +1662135934858689792 +1662135934900690688 +1662135934942691584 +1662135934990692608 +1662135935032693504 +1662135935077694464 +1662135935119695360 +1662135935158696192 +1662135935209697280 +1662135935251698176 +1662135935293699072 +1662135935344700160 +1662135935389701120 +1662135935431702016 +1662135935482703104 +1662135935524704000 +1662135935572705024 +1662135935620706048 +1662135935668707072 +1662135935713708032 +1662135935758708992 +1662135935803709952 +1662135935845710848 +1662135935887711744 +1662135935932712704 +1662135935974713600 +1662135936019714560 +1662135936067715584 +1662135936106716416 +1662135936154717440 +1662135936196718336 +1662135936235719168 +1662135936277720064 +1662135936325721088 +1662135936367721984 +1662135936415723008 +1662135936457723904 +1662135936499724800 +1662135936544725760 +1662135936592726784 +1662135936631727616 +1662135936679728640 +1662135936727729664 +1662135936772730624 +1662135936814731520 +1662135936856732416 +1662135936907733504 +1662135936949734400 +1662135936997735424 +1662135937045736448 +1662135937093737472 +1662135937135738368 +1662135937180739328 +1662135937222740224 +1662135937267741184 +1662135937306742016 +1662135937351742976 +1662135937396743936 +1662135937435744768 +1662135937477745664 +1662135937522746624 +1662135937567747584 +1662135937609748480 +1662135937660749568 +1662135937705750528 +1662135937756751616 +1662135937804752640 +1662135937846753536 +1662135937903754752 +1662135937942755584 +1662135937984756480 +1662135938032757504 +1662135938071758336 +1662135938119759360 +1662135938161760256 +1662135938212761344 +1662135938254762240 +1662135938308763392 +1662135938350764288 +1662135938395765248 +1662135938452766464 +1662135938500767488 +1662135938539768320 +1662135938584769280 +1662135938629770240 +1662135938671771136 +1662135938716772096 +1662135938764773120 +1662135938815774208 +1662135938863775232 +1662135938905776128 +1662135938953777152 +1662135939001778176 +1662135939043779072 +1662135939094780160 +1662135939142781184 +1662135939187782144 +1662135939235783168 +1662135939274784000 +1662135939322785024 +1662135939367785984 +1662135939409786880 +1662135939460787968 +1662135939502788864 +1662135939541789696 +1662135939592790784 +1662135939637791744 +1662135939688792832 +1662135939736793856 +1662135939778794752 +1662135939820795648 +1662135939865796608 +1662135939919797760 +1662135939961798656 +1662135940006799616 +1662135940045800448 +1662135940093801472 +1662135940135802368 +1662135940180803328 +1662135940228804352 +1662135940282805504 +1662135940327806464 +1662135940372807424 +1662135940426808576 +1662135940468809472 +1662135940510810368 +1662135940552811264 +1662135940603812352 +1662135940642813184 +1662135940681814016 +1662135940723814912 +1662135940765815808 +1662135940807816704 +1662135940849817600 +1662135940888818432 +1662135940930819328 +1662135940978820352 +1662135941023821312 +1662135941065822208 +1662135941107823104 +1662135941149824000 +1662135941188824832 +1662135941233825792 +1662135941281826816 +1662135941323827712 +1662135941365828608 +1662135941413829632 +1662135941455830528 +1662135941500831488 +1662135941542832384 +1662135941581833216 +1662135941623834112 +1662135941665835008 +1662135941707835904 +1662135941746836736 +1662135941791837696 +1662135941833838592 +1662135941878839552 +1662135941929840640 +1662135941977841664 +1662135942025842688 +1662135942061843456 +1662135942103844352 +1662135942145845248 +1662135942199846400 +1662135942247847424 +1662135942292848384 +1662135942334849280 +1662135942388850432 +1662135942433851392 +1662135942478852352 +1662135942520853248 +1662135942562854144 +1662135942613855232 +1662135942658856192 +1662135942700857088 +1662135942751858176 +1662135942793859072 +1662135942835859968 +1662135942883860992 +1662135942925861888 +1662135942967862784 +1662135943006863616 +1662135943048864512 +1662135943093865472 +1662135943138866432 +1662135943186867456 +1662135943234868480 +1662135943276869376 +1662135943321870336 +1662135943369871360 +1662135943408872192 +1662135943456873216 +1662135943501874176 +1662135943543875072 +1662135943582875904 +1662135943627876864 +1662135943669877760 +1662135943720878848 +1662135943762879744 +1662135943804880640 +1662135943849881600 +1662135943894882560 +1662135943945883648 +1662135943996884736 +1662135944038885632 +1662135944083886592 +1662135944134887680 +1662135944182888704 +1662135944224889600 +1662135944275890688 +1662135944317891584 +1662135944362892544 +1662135944410893568 +1662135944452894464 +1662135944497895424 +1662135944551896576 +1662135944593897472 +1662135944635898368 +1662135944680899328 +1662135944731900416 +1662135944776901376 +1662135944824902400 +1662135944878903552 +1662135944923904512 +1662135944965905408 +1662135945010906368 +1662135945058907392 +1662135945100908288 +1662135945142909184 +1662135945190910208 +1662135945235911168 +1662135945289912320 +1662135945331913216 +1662135945376914176 +1662135945421915136 +1662135945466916096 +1662135945508916992 +1662135945550917888 +1662135945595918848 +1662135945634919680 +1662135945679920640 +1662135945727921664 +1662135945775922688 +1662135945817923584 +1662135945862924544 +1662135945904925440 +1662135945949926400 +1662135945991927296 +1662135946036928256 +1662135946081929216 +1662135946123930112 +1662135946165931008 +1662135946216932096 +1662135946261933056 +1662135946306934016 +1662135946351934976 +1662135946393935872 +1662135946438936832 +1662135946477937664 +1662135946519938560 +1662135946564939520 +1662135946609940480 +1662135946651941376 +1662135946690942208 +1662135946735943168 +1662135946783944192 +1662135946825945088 +1662135946867945984 +1662135946918947072 +1662135946963948032 +1662135947005948928 +1662135947047949824 +1662135947095950848 +1662135947134951680 +1662135947188952832 +1662135947236953856 +1662135947278954752 +1662135947320955648 +1662135947368956672 +1662135947410957568 +1662135947452958464 +1662135947494959360 +1662135947539960320 +1662135947578961152 +1662135947623962112 +1662135947665963008 +1662135947716964096 +1662135947758964992 +1662135947800965888 +1662135947842966784 +1662135947890967808 +1662135947941968896 +1662135947989969920 +1662135948031970816 +1662135948079971840 +1662135948121972736 +1662135948163973632 +1662135948211974656 +1662135948253975552 +1662135948292976384 +1662135948337977344 +1662135948382978304 +1662135948430979328 +1662135948472980224 +1662135948514981120 +1662135948553981952 +1662135948595982848 +1662135948637983744 +1662135948685984768 +1662135948730985728 +1662135948772986624 +1662135948814987520 +1662135948856988416 +1662135948895989248 +1662135948937990144 +1662135948982991104 +1662135949033992192 +1662135949078993152 +1662135949120994048 +1662135949174995200 +1662135949216996096 +1662135949261997056 +1662135949306998016 +1662135949348998912 +1662135949393999872 +1662135949439000832 +1662135949481001728 +1662135949529002752 +1662135949568003584 +1662135949616004608 +1662135949667005696 +1662135949709006592 +1662135949754007552 +1662135949796008448 +1662135949838009344 +1662135949886010368 +1662135949928011264 +1662135949970012160 +1662135950012013056 +1662135950057014016 +1662135950099014912 +1662135950144015872 +1662135950186016768 +1662135950240017920 +1662135950285018880 +1662135950327019776 +1662135950375020800 +1662135950417021696 +1662135950468022784 +1662135950510023680 +1662135950558024704 +1662135950600025600 +1662135950642026496 +1662135950690027520 +1662135950735028480 +1662135950777029376 +1662135950822030336 +1662135950870031360 +1662135950918032384 +1662135950960033280 +1662135951002034176 +1662135951047035136 +1662135951089036032 +1662135951146037248 +1662135951188038144 +1662135951230039040 +1662135951272039936 +1662135951317040896 +1662135951368041984 +1662135951413042944 +1662135951455043840 +1662135951494044672 +1662135951545045760 +1662135951587046656 +1662135951632047616 +1662135951674048512 +1662135951722049536 +1662135951770050560 +1662135951815051520 +1662135951860052480 +1662135951902053376 +1662135951944054272 +1662135951986055168 +1662135952028056064 +1662135952067056896 +1662135952112057856 +1662135952154058752 +1662135952196059648 +1662135952238060544 +1662135952280061440 +1662135952337062656 +1662135952379063552 +1662135952424064512 +1662135952466065408 +1662135952517066496 +1662135952559067392 +1662135952616068608 +1662135952661069568 +1662135952709070592 +1662135952763071744 +1662135952808072704 +1662135952850073600 +1662135952895074560 +1662135952937075456 +1662135952982076416 +1662135953033077504 +1662135953075078400 +1662135953117079296 +1662135953159080192 +1662135953201081088 +1662135953243081984 +1662135953291083008 +1662135953333083904 +1662135953384084992 +1662135953426085888 +1662135953471086848 +1662135953513087744 +1662135953555088640 +1662135953603089664 +1662135953651090688 +1662135953693091584 +1662135953741092608 +1662135953786093568 +1662135953828094464 +1662135953870095360 +1662135953912096256 +1662135953957097216 +1662135953999098112 +1662135954044099072 +1662135954092100096 +1662135954134100992 +1662135954176101888 +1662135954218102784 +1662135954260103680 +1662135954308104704 +1662135954353105664 +1662135954392106496 +1662135954431107328 +1662135954479108352 +1662135954518109184 +1662135954566110208 +1662135954611111168 +1662135954656112128 +1662135954704113152 +1662135954746114048 +1662135954791115008 +1662135954833115904 +1662135954878116864 +1662135954923117824 +1662135954965118720 +1662135955016119808 +1662135955058120704 +1662135955097121536 +1662135955136122368 +1662135955178123264 +1662135955217124096 +1662135955259124992 +1662135955304125952 +1662135955346126848 +1662135955391127808 +1662135955436128768 +1662135955487129856 +1662135955526130688 +1662135955568131584 +1662135955610132480 +1662135955655133440 +1662135955697134336 +1662135955739135232 +1662135955781136128 +1662135955826137088 +1662135955868137984 +1662135955913138944 +1662135955964140032 +1662135956009140992 +1662135956057142016 +1662135956105143040 +1662135956153144064 +1662135956195144960 +1662135956240145920 +1662135956288146944 +1662135956336147968 +1662135956381148928 +1662135956426149888 +1662135956468150784 +1662135956513151744 +1662135956555152640 +1662135956600153600 +1662135956648154624 +1662135956690155520 +1662135956732156416 +1662135956774157312 +1662135956828158464 +1662135956876159488 +1662135956921160448 +1662135956963161344 +1662135957008162304 +1662135957056163328 +1662135957104164352 +1662135957146165248 +1662135957188166144 +1662135957230167040 +1662135957266167808 +1662135957308168704 +1662135957350169600 +1662135957392170496 +1662135957437171456 +1662135957479172352 +1662135957521173248 +1662135957566174208 +1662135957608175104 +1662135957650176000 +1662135957695176960 +1662135957734177792 +1662135957785178880 +1662135957827179776 +1662135957869180672 +1662135957911181568 +1662135957956182528 +1662135958001183488 +1662135958046184448 +1662135958088185344 +1662135958130186240 +1662135958175187200 +1662135958226188288 +1662135958268189184 +1662135958310190080 +1662135958352190976 +1662135958394191872 +1662135958445192960 +1662135958487193856 +1662135958529194752 +1662135958565195520 +1662135958610196480 +1662135958652197376 +1662135958694198272 +1662135958739199232 +1662135958781200128 +1662135958826201088 +1662135958868201984 +1662135958910202880 +1662135958952203776 +1662135958994204672 +1662135959039205632 +1662135959084206592 +1662135959129207552 +1662135959174208512 +1662135959216209408 +1662135959261210368 +1662135959306211328 +1662135959351212288 +1662135959396213248 +1662135959438214144 +1662135959483215104 +1662135959531216128 +1662135959573217024 +1662135959615217920 +1662135959654218752 +1662135959696219648 +1662135959738220544 +1662135959780221440 +1662135959825222400 +1662135959870223360 +1662135959909224192 +1662135959951225088 +1662135959999226112 +1662135960041227008 +1662135960083227904 +1662135960125228800 +1662135960167229696 +1662135960218230784 +1662135960260231680 +1662135960299232512 +1662135960347233536 +1662135960392234496 +1662135960440235520 +1662135960485236480 +1662135960539237632 +1662135960584238592 +1662135960635239680 +1662135960680240640 +1662135960725241600 +1662135960776242688 +1662135960818243584 +1662135960863244544 +1662135960908245504 +1662135960950246400 +1662135961001247488 +1662135961043248384 +1662135961085249280 +1662135961127250176 +1662135961178251264 +1662135961220252160 +1662135961265253120 +1662135961307254016 +1662135961352254976 +1662135961400256000 +1662135961448257024 +1662135961490257920 +1662135961535258880 +1662135961580259840 +1662135961619260672 +1662135961658261504 +1662135961700262400 +1662135961742263296 +1662135961784264192 +1662135961826265088 +1662135961868265984 +1662135961907266816 +1662135961949267712 +1662135961991268608 +1662135962039269632 +1662135962081270528 +1662135962123271424 +1662135962165272320 +1662135962210273280 +1662135962252274176 +1662135962303275264 +1662135962345276160 +1662135962387277056 +1662135962432278016 +1662135962477278976 +1662135962528280064 +1662135962570280960 +1662135962615281920 +1662135962657282816 +1662135962699283712 +1662135962741284608 +1662135962792285696 +1662135962837286656 +1662135962882287616 +1662135962924288512 +1662135962972289536 +1662135963014290432 +1662135963065291520 +1662135963113292544 +1662135963164293632 +1662135963212294656 +1662135963254295552 +1662135963299296512 +1662135963341297408 +1662135963386298368 +1662135963425299200 +1662135963467300096 +1662135963512301056 +1662135963554301952 +1662135963596302848 +1662135963644303872 +1662135963686304768 +1662135963728305664 +1662135963773306624 +1662135963815307520 +1662135963857308416 +1662135963902309376 +1662135963947310336 +1662135963995311360 +1662135964040312320 +1662135964088313344 +1662135964139314432 +1662135964181315328 +1662135964223316224 +1662135964271317248 +1662135964313318144 +1662135964358319104 +1662135964406320128 +1662135964445320960 +1662135964487321856 +1662135964532322816 +1662135964574323712 +1662135964619324672 +1662135964667325696 +1662135964709326592 +1662135964754327552 +1662135964796328448 +1662135964835329280 +1662135964883330304 +1662135964928331264 +1662135964970332160 +1662135965012333056 +1662135965057334016 +1662135965108335104 +1662135965144335872 +1662135965186336768 +1662135965234337792 +1662135965276338688 +1662135965327339776 +1662135965369340672 +1662135965414341632 +1662135965459342592 +1662135965507343616 +1662135965549344512 +1662135965591345408 +1662135965633346304 +1662135965678347264 +1662135965720348160 +1662135965765349120 +1662135965810350080 +1662135965852350976 +1662135965894351872 +1662135965933352704 +1662135965972353536 +1662135966017354496 +1662135966065355520 +1662135966107356416 +1662135966152357376 +1662135966191358208 +1662135966239359232 +1662135966284360192 +1662135966329361152 +1662135966371362048 +1662135966419363072 +1662135966464364032 +1662135966512365056 +1662135966551365888 +1662135966596366848 +1662135966638367744 +1662135966680368640 +1662135966719369472 +1662135966761370368 +1662135966803371264 +1662135966848372224 +1662135966890373120 +1662135966932374016 +1662135966974374912 +1662135967025376000 +1662135967067376896 +1662135967115377920 +1662135967160378880 +1662135967202379776 +1662135967250380800 +1662135967295381760 +1662135967340382720 +1662135967382383616 +1662135967424384512 +1662135967466385408 +1662135967505386240 +1662135967550387200 +1662135967592388096 +1662135967646389248 +1662135967685390080 +1662135967733391104 +1662135967775392000 +1662135967817392896 +1662135967874394112 +1662135967919395072 +1662135967961395968 +1662135968012397056 +1662135968054397952 +1662135968096398848 +1662135968141399808 +1662135968186400768 +1662135968225401600 +1662135968264402432 +1662135968312403456 +1662135968360404480 +1662135968402405376 +1662135968447406336 +1662135968492407296 +1662135968534408192 +1662135968582409216 +1662135968624410112 +1662135968666411008 +1662135968708411904 +1662135968747412736 +1662135968789413632 +1662135968834414592 +1662135968879415552 +1662135968921416448 +1662135968963417344 +1662135969008418304 +1662135969050419200 +1662135969092420096 +1662135969137421056 +1662135969182422016 +1662135969227422976 +1662135969269423872 +1662135969311424768 +1662135969356425728 +1662135969404426752 +1662135969452427776 +1662135969497428736 +1662135969548429824 +1662135969596430848 +1662135969641431808 +1662135969695432960 +1662135969740433920 +1662135969779434752 +1662135969821435648 +1662135969863436544 +1662135969908437504 +1662135969953438464 +1662135970004439552 +1662135970043440384 +1662135970088441344 +1662135970130442240 +1662135970178443264 +1662135970223444224 +1662135970265445120 +1662135970307446016 +1662135970358447104 +1662135970400448000 +1662135970445448960 +1662135970487449856 +1662135970526450688 +1662135970565451520 +1662135970607452416 +1662135970649453312 +1662135970691454208 +1662135970736455168 +1662135970781456128 +1662135970829457152 +1662135970871458048 +1662135970913458944 +1662135970958459904 +1662135971006460928 +1662135971063462144 +1662135971105463040 +1662135971150464000 +1662135971198465024 +1662135971240465920 +1662135971285466880 +1662135971336467968 +1662135971381468928 +1662135971426469888 +1662135971468470784 +1662135971510471680 +1662135971552472576 +1662135971600473600 +1662135971642474496 +1662135971690475520 +1662135971741476608 +1662135971786477568 +1662135971831478528 +1662135971876479488 +1662135971918480384 +1662135971960481280 +1662135972014482432 +1662135972068483584 +1662135972116484608 +1662135972164485632 +1662135972209486592 +1662135972254487552 +1662135972296488448 +1662135972344489472 +1662135972395490560 +1662135972443491584 +1662135972488492544 +1662135972533493504 +1662135972575494400 +1662135972620495360 +1662135972662496256 +1662135972704497152 +1662135972749498112 +1662135972797499136 +1662135972842500096 +1662135972887501056 +1662135972926501888 +1662135972974502912 +1662135973016503808 +1662135973070504960 +1662135973115505920 +1662135973160506880 +1662135973205507840 +1662135973262509056 +1662135973304509952 +1662135973346510848 +1662135973391511808 +1662135973433512704 +1662135973472513536 +1662135973514514432 +1662135973556515328 +1662135973598516224 +1662135973649517312 +1662135973700518400 +1662135973748519424 +1662135973793520384 +1662135973835521280 +1662135973883522304 +1662135973928523264 +1662135973976524288 +1662135974018525184 +1662135974060526080 +1662135974108527104 +1662135974150528000 +1662135974192528896 +1662135974237529856 +1662135974282530816 +1662135974324531712 +1662135974369532672 +1662135974411533568 +1662135974456534528 +1662135974501535488 +1662135974543536384 +1662135974585537280 +1662135974627538176 +1662135974681539328 +1662135974729540352 +1662135974771541248 +1662135974813542144 +1662135974858543104 +1662135974906544128 +1662135974945544960 +1662135974987545856 +1662135975035546880 +1662135975083547904 +1662135975134548992 +1662135975176549888 +1662135975218550784 +1662135975263551744 +1662135975311552768 +1662135975359553792 +1662135975401554688 +1662135975452555776 +1662135975494556672 +1662135975542557696 +1662135975587558656 +1662135975632559616 +1662135975677560576 +1662135975725561600 +1662135975767562496 +1662135975818563584 +1662135975866564608 +1662135975908565504 +1662135975950566400 +1662135975995567360 +1662135976040568320 +1662135976085569280 +1662135976127570176 +1662135976169571072 +1662135976211571968 +1662135976256572928 +1662135976295573760 +1662135976340574720 +1662135976385575680 +1662135976430576640 +1662135976472577536 +1662135976520578560 +1662135976559579392 +1662135976607580416 +1662135976649581312 +1662135976697582336 +1662135976745583360 +1662135976787584256 +1662135976829585152 +1662135976871586048 +1662135976913586944 +1662135976955587840 +1662135977006588928 +1662135977048589824 +1662135977093590784 +1662135977138591744 +1662135977183592704 +1662135977228593664 +1662135977276594688 +1662135977318595584 +1662135977360596480 +1662135977405597440 +1662135977453598464 +1662135977495599360 +1662135977540600320 +1662135977582601216 +1662135977624602112 +1662135977681603328 +1662135977723604224 +1662135977765605120 +1662135977810606080 +1662135977858607104 +1662135977900608000 +1662135977945608960 +1662135977996610048 +1662135978041611008 +1662135978086611968 +1662135978131612928 +1662135978173613824 +1662135978212614656 +1662135978257615616 +1662135978299616512 +1662135978341617408 +1662135978383618304 +1662135978425619200 +1662135978470620160 +1662135978509620992 +1662135978563622144 +1662135978608623104 +1662135978650624000 +1662135978698625024 +1662135978737625856 +1662135978785626880 +1662135978824627712 +1662135978869628672 +1662135978911629568 +1662135978956630528 +1662135978998631424 +1662135979043632384 +1662135979091633408 +1662135979133634304 +1662135979175635200 +1662135979220636160 +1662135979262637056 +1662135979304637952 +1662135979346638848 +1662135979388639744 +1662135979439640832 +1662135979484641792 +1662135979529642752 +1662135979571643648 +1662135979613644544 +1662135979658645504 +1662135979700646400 +1662135979742647296 +1662135979784648192 +1662135979829649152 +1662135979877650176 +1662135979919651072 +1662135979964652032 +1662135980009652992 +1662135980054653952 +1662135980105655040 +1662135980147655936 +1662135980189656832 +1662135980234657792 +1662135980276658688 +1662135980318659584 +1662135980363660544 +1662135980408661504 +1662135980465662720 +1662135980507663616 +1662135980549664512 +1662135980606665728 +1662135980651666688 +1662135980696667648 +1662135980738668544 +1662135980780669440 +1662135980822670336 +1662135980867671296 +1662135980909672192 +1662135980954673152 +1662135980996674048 +1662135981041675008 +1662135981083675904 +1662135981131676928 +1662135981179677952 +1662135981221678848 +1662135981293680384 +1662135981335681280 +1662135981383682304 +1662135981425683200 +1662135981470684160 +1662135981515685120 +1662135981560686080 +1662135981608687104 +1662135981659688192 +1662135981701689088 +1662135981740689920 +1662135981782690816 +1662135981824691712 +1662135981869692672 +1662135981920693760 +1662135981965694720 +1662135982016695808 +1662135982058696704 +1662135982100697600 +1662135982142698496 +1662135982184699392 +1662135982226700288 +1662135982271701248 +1662135982319702272 +1662135982361703168 +1662135982400704000 +1662135982442704896 +1662135982490705920 +1662135982541707008 +1662135982583707904 +1662135982625708800 +1662135982667709696 +1662135982715710720 +1662135982757711616 +1662135982796712448 +1662135982841713408 +1662135982883714304 +1662135982922715136 +1662135982967716096 +1662135983009716992 +1662135983048717824 +1662135983093718784 +1662135983135719680 +1662135983183720704 +1662135983228721664 +1662135983270722560 +1662135983321723648 +1662135983366724608 +1662135983408725504 +1662135983456726528 +1662135983501727488 +1662135983549728512 +1662135983594729472 +1662135983642730496 +1662135983687731456 +1662135983729732352 +1662135983771733248 +1662135983819734272 +1662135983864735232 +1662135983909736192 +1662135983954737152 +1662135983999738112 +1662135984041739008 +1662135984083739904 +1662135984125740800 +1662135984179741952 +1662135984224742912 +1662135984269743872 +1662135984317744896 +1662135984362745856 +1662135984404746752 +1662135984446747648 +1662135984491748608 +1662135984533749504 +1662135984572750336 +1662135984614751232 +1662135984656752128 +1662135984701753088 +1662135984743753984 +1662135984782754816 +1662135984833755904 +1662135984884756992 +1662135984929757952 +1662135984980759040 +1662135985031760128 +1662135985076761088 +1662135985115761920 +1662135985166763008 +1662135985217764096 +1662135985265765120 +1662135985304765952 +1662135985346766848 +1662135985388767744 +1662135985427768576 +1662135985469769472 +1662135985508770304 +1662135985547771136 +1662135985589772032 +1662135985634772992 +1662135985676773888 +1662135985721774848 +1662135985769775872 +1662135985817776896 +1662135985865777920 +1662135985907778816 +1662135985955779840 +1662135986003780864 +1662135986051781888 +1662135986096782848 +1662135986141783808 +1662135986186784768 +1662135986234785792 +1662135986279786752 +1662135986321787648 +1662135986363788544 +1662135986414789632 +1662135986462790656 +1662135986501791488 +1662135986546792448 +1662135986591793408 +1662135986636794368 +1662135986687795456 +1662135986729796352 +1662135986780797440 +1662135986828798464 +1662135986876799488 +1662135986918800384 +1662135986963801344 +1662135987014802432 +1662135987059803392 +1662135987107804416 +1662135987152805376 +1662135987197806336 +1662135987245807360 +1662135987290808320 +1662135987332809216 +1662135987374810112 +1662135987416811008 +1662135987461811968 +1662135987500812800 +1662135987542813696 +1662135987584814592 +1662135987632815616 +1662135987674816512 +1662135987716817408 +1662135987758818304 +1662135987803819264 +1662135987845820160 +1662135987890821120 +1662135987935822080 +1662135987980823040 +1662135988022823936 +1662135988067824896 +1662135988112825856 +1662135988154826752 +1662135988196827648 +1662135988235828480 +1662135988277829376 +1662135988319830272 +1662135988361831168 +1662135988406832128 +1662135988448833024 +1662135988493833984 +1662135988535834880 +1662135988583835904 +1662135988625836800 +1662135988670837760 +1662135988715838720 +1662135988760839680 +1662135988799840512 +1662135988838841344 +1662135988880842240 +1662135988919843072 +1662135988961843968 +1662135989003844864 +1662135989042845696 +1662135989084846592 +1662135989129847552 +1662135989171848448 +1662135989210849280 +1662135989258850304 +1662135989300851200 +1662135989342852096 +1662135989384852992 +1662135989429853952 +1662135989468854784 +1662135989510855680 +1662135989552856576 +1662135989594857472 +1662135989639858432 +1662135989681859328 +1662135989723860224 +1662135989765861120 +1662135989807862016 +1662135989852862976 +1662135989897863936 +1662135989942864896 +1662135989984865792 +1662135990029866752 +1662135990065867520 +1662135990113868544 +1662135990161869568 +1662135990203870464 +1662135990245871360 +1662135990287872256 +1662135990329873152 +1662135990374874112 +1662135990422875136 +1662135990464876032 +1662135990509876992 +1662135990551877888 +1662135990605879040 +1662135990650880000 +1662135990695880960 +1662135990743881984 +1662135990785882880 +1662135990836883968 +1662135990884884992 +1662135990935886080 +1662135990980887040 +1662135991025888000 +1662135991067888896 +1662135991109889792 +1662135991151890688 +1662135991199891712 +1662135991238892544 +1662135991283893504 +1662135991328894464 +1662135991370895360 +1662135991415896320 +1662135991457897216 +1662135991502898176 +1662135991544899072 +1662135991586899968 +1662135991628900864 +1662135991670901760 +1662135991712902656 +1662135991760903680 +1662135991802904576 +1662135991844905472 +1662135991889906432 +1662135991931907328 +1662135991979908352 +1662135992021909248 +1662135992075910400 +1662135992114911232 +1662135992156912128 +1662135992195912960 +1662135992240913920 +1662135992282914816 +1662135992330915840 +1662135992378916864 +1662135992417917696 +1662135992462918656 +1662135992510919680 +1662135992552920576 +1662135992603921664 +1662135992645922560 +1662135992687923456 +1662135992729924352 +1662135992771925248 +1662135992813926144 +1662135992855927040 +1662135992909928192 +1662135992951929088 +1662135992990929920 +1662135993032930816 +1662135993083931904 +1662135993128932864 +1662135993182934016 +1662135993224934912 +1662135993281936128 +1662135993329937152 +1662135993371938048 +1662135993413938944 +1662135993458939904 +1662135993503940864 +1662135993545941760 +1662135993590942720 +1662135993632943616 +1662135993677944576 +1662135993722945536 +1662135993761946368 +1662135993806947328 +1662135993851948288 +1662135993893949184 +1662135993935950080 +1662135993980951040 +1662135994025952000 +1662135994070952960 +1662135994112953856 +1662135994157954816 +1662135994202955776 +1662135994253956864 +1662135994298957824 +1662135994340958720 +1662135994382959616 +1662135994427960576 +1662135994469961472 +1662135994514962432 +1662135994565963520 +1662135994610964480 +1662135994655965440 +1662135994694966272 +1662135994739967232 +1662135994781968128 +1662135994838969344 +1662135994883970304 +1662135994931971328 +1662135994976972288 +1662135995018973184 +1662135995060974080 +1662135995111975168 +1662135995156976128 +1662135995201977088 +1662135995243977984 +1662135995291979008 +1662135995333979904 +1662135995381980928 +1662135995429981952 +1662135995480983040 +1662135995525984000 +1662135995573985024 +1662135995615985920 +1662135995672987136 +1662135995717988096 +1662135995777989376 +1662135995822990336 +1662135995864991232 +1662135995918992384 +1662135995960993280 +1662135995999994112 +1662135996044995072 +1662135996086995968 +1662135996128996864 +1662135996179997952 +1662135996224998912 +1662135996266999808 +1662135996315000832 +1662135996357001728 +1662135996402002688 +1662135996444003584 +1662135996489004544 +1662135996528005376 +1662135996579006464 +1662135996621007360 +1662135996666008320 +1662135996705009152 +1662135996747010048 +1662135996789010944 +1662135996837011968 +1662135996888013056 +1662135996939014144 +1662135996990015232 +1662135997038016256 +1662135997086017280 +1662135997128018176 +1662135997176019200 +1662135997218020096 +1662135997260020992 +1662135997305021952 +1662135997350022912 +1662135997398023936 +1662135997437024768 +1662135997479025664 +1662135997521026560 +1662135997572027648 +1662135997620028672 +1662135997659029504 +1662135997710030592 +1662135997752031488 +1662135997794032384 +1662135997836033280 +1662135997878034176 +1662135997920035072 +1662135997965036032 +1662135998007036928 +1662135998052037888 +1662135998097038848 +1662135998139039744 +1662135998184040704 +1662135998226041600 +1662135998271042560 +1662135998316043520 +1662135998361044480 +1662135998412045568 +1662135998457046528 +1662135998499047424 +1662135998550048512 +1662135998595049472 +1662135998640050432 +1662135998682051328 +1662135998727052288 +1662135998772053248 +1662135998820054272 +1662135998865055232 +1662135998907056128 +1662135998949057024 +1662135998997058048 +1662135999039058944 +1662135999081059840 +1662135999123060736 +1662135999168061696 +1662135999216062720 +1662135999264063744 +1662135999309064704 +1662135999360065792 +1662135999402066688 +1662135999447067648 +1662135999489068544 +1662135999528069376 +1662135999579070464 +1662135999630071552 +1662135999678072576 +1662135999720073472 +1662135999759074304 +1662135999804075264 +1662135999846076160 +1662135999894077184 +1662135999939078144 +1662135999981079040 +1662136000029080064 +1662136000077081088 +1662136000125082112 +1662136000173083136 +1662136000215084032 +1662136000257084928 +1662136000299085824 +1662136000341086720 +1662136000383087616 +1662136000425088512 +1662136000473089536 +1662136000518090496 +1662136000557091328 +1662136000605092352 +1662136000650093312 +1662136000701094400 +1662136000740095232 +1662136000782096128 +1662136000827097088 +1662136000869097984 +1662136000911098880 +1662136000953099776 +1662136000992100608 +1662136001034101504 +1662136001088102656 +1662136001130103552 +1662136001172104448 +1662136001217105408 +1662136001256106240 +1662136001307107328 +1662136001352108288 +1662136001400109312 +1662136001442110208 +1662136001490111232 +1662136001535112192 +1662136001580113152 +1662136001622114048 +1662136001670115072 +1662136001709115904 +1662136001751116800 +1662136001796117760 +1662136001841118720 +1662136001895119872 +1662136001946120960 +1662136001991121920 +1662136002042123008 +1662136002084123904 +1662136002132124928 +1662136002180125952 +1662136002222126848 +1662136002267127808 +1662136002306128640 +1662136002348129536 +1662136002396130560 +1662136002441131520 +1662136002495132672 +1662136002540133632 +1662136002585134592 +1662136002633135616 +1662136002678136576 +1662136002723137536 +1662136002768138496 +1662136002813139456 +1662136002852140288 +1662136002894141184 +1662136002939142144 +1662136002990143232 +1662136003041144320 +1662136003083145216 +1662136003128146176 +1662136003179147264 +1662136003239148544 +1662136003284149504 +1662136003323150336 +1662136003371151360 +1662136003416152320 +1662136003458153216 +1662136003503154176 +1662136003545155072 +1662136003590156032 +1662136003638157056 +1662136003680157952 +1662136003722158848 +1662136003761159680 +1662136003803160576 +1662136003848161536 +1662136003899162624 +1662136003941163520 +1662136003992164608 +1662136004034165504 +1662136004088166656 +1662136004139167744 +1662136004184168704 +1662136004229169664 +1662136004268170496 +1662136004313171456 +1662136004352172288 +1662136004400173312 +1662136004439174144 +1662136004484175104 +1662136004529176064 +1662136004571176960 +1662136004619177984 +1662136004658178816 +1662136004703179776 +1662136004748180736 +1662136004793181696 +1662136004835182592 +1662136004880183552 +1662136004928184576 +1662136004985185792 +1662136005030186752 +1662136005072187648 +1662136005120188672 +1662136005168189696 +1662136005213190656 +1662136005255191552 +1662136005297192448 +1662136005339193344 +1662136005381194240 +1662136005426195200 +1662136005465196032 +1662136005507196928 +1662136005552197888 +1662136005594198784 +1662136005639199744 +1662136005681200640 +1662136005729201664 +1662136005774202624 +1662136005816203520 +1662136005861204480 +1662136005903205376 +1662136005945206272 +1662136005984207104 +1662136006029208064 +1662136006080209152 +1662136006131210240 +1662136006185211392 +1662136006230212352 +1662136006272213248 +1662136006317214208 +1662136006359215104 +1662136006401216000 +1662136006452217088 +1662136006494217984 +1662136006539218944 +1662136006581219840 +1662136006632220928 +1662136006668221696 +1662136006713222656 +1662136006755223552 +1662136006800224512 +1662136006845225472 +1662136006887226368 +1662136006929227264 +1662136006971228160 +1662136007016229120 +1662136007067230208 +1662136007118231296 +1662136007160232192 +1662136007202233088 +1662136007244233984 +1662136007286234880 +1662136007328235776 +1662136007373236736 +1662136007421237760 +1662136007466238720 +1662136007517239808 +1662136007562240768 +1662136007604241664 +1662136007652242688 +1662136007697243648 +1662136007739244544 +1662136007781245440 +1662136007826246400 +1662136007868247296 +1662136007910248192 +1662136007952249088 +1662136008000250112 +1662136008042251008 +1662136008084251904 +1662136008126252800 +1662136008174253824 +1662136008216254720 +1662136008261255680 +1662136008303256576 +1662136008342257408 +1662136008384258304 +1662136008426259200 +1662136008468260096 +1662136008513261056 +1662136008561262080 +1662136008603262976 +1662136008648263936 +1662136008696264960 +1662136008741265920 +1662136008783266816 +1662136008831267840 +1662136008873268736 +1662136008918269696 +1662136008960270592 +1662136008999271424 +1662136009041272320 +1662136009089273344 +1662136009140274432 +1662136009182275328 +1662136009224276224 +1662136009266277120 +1662136009311278080 +1662136009356279040 +1662136009395279872 +1662136009440280832 +1662136009482281728 +1662136009527282688 +1662136009578283776 +1662136009617284608 +1662136009662285568 +1662136009704286464 +1662136009752287488 +1662136009797288448 +1662136009842289408 +1662136009884290304 +1662136009926291200 +1662136009974292224 +1662136010016293120 +1662136010061294080 +1662136010109295104 +1662136010154296064 +1662136010196296960 +1662136010235297792 +1662136010280298752 +1662136010322299648 +1662136010364300544 +1662136010409301504 +1662136010451302400 +1662136010499303424 +1662136010547304448 +1662136010592305408 +1662136010637306368 +1662136010676307200 +1662136010718308096 +1662136010760308992 +1662136010808310016 +1662136010850310912 +1662136010892311808 +1662136010934312704 +1662136010982313728 +1662136011027314688 +1662136011072315648 +1662136011114316544 +1662136011159317504 +1662136011201318400 +1662136011243319296 +1662136011285320192 +1662136011327321088 +1662136011372322048 +1662136011420323072 +1662136011462323968 +1662136011507324928 +1662136011549325824 +1662136011591326720 +1662136011633327616 +1662136011687328768 +1662136011732329728 +1662136011780330752 +1662136011822331648 +1662136011870332672 +1662136011918333696 +1662136011960334592 +1662136012002335488 +1662136012047336448 +1662136012092337408 +1662136012134338304 +1662136012176339200 +1662136012218340096 +1662136012260340992 +1662136012302341888 +1662136012350342912 +1662136012395343872 +1662136012437344768 +1662136012482345728 +1662136012527346688 +1662136012575347712 +1662136012614348544 +1662136012656349440 +1662136012701350400 +1662136012740351232 +1662136012782352128 +1662136012824353024 +1662136012866353920 +1662136012914354944 +1662136012959355904 +1662136013004356864 +1662136013046357760 +1662136013091358720 +1662136013136359680 +1662136013178360576 +1662136013223361536 +1662136013262362368 +1662136013307363328 +1662136013352364288 +1662136013394365184 +1662136013436366080 +1662136013481367040 +1662136013523367936 +1662136013565368832 +1662136013607369728 +1662136013652370688 +1662136013694371584 +1662136013736372480 +1662136013790373632 +1662136013832374528 +1662136013874375424 +1662136013916376320 +1662136013961377280 +1662136014006378240 +1662136014051379200 +1662136014096380160 +1662136014144381184 +1662136014189382144 +1662136014231383040 +1662136014276384000 +1662136014321384960 +1662136014369385984 +1662136014411386880 +1662136014453387776 +1662136014501388800 +1662136014543389696 +1662136014591390720 +1662136014630391552 +1662136014672392448 +1662136014717393408 +1662136014765394432 +1662136014807395328 +1662136014858396416 +1662136014903397376 +1662136014948398336 +1662136014996399360 +1662136015041400320 +1662136015086401280 +1662136015128402176 +1662136015170403072 +1662136015218404096 +1662136015263405056 +1662136015305405952 +1662136015347406848 +1662136015404408064 +1662136015449409024 +1662136015500410112 +1662136015545411072 +1662136015584411904 +1662136015629412864 +1662136015671413760 +1662136015716414720 +1662136015761415680 +1662136015806416640 +1662136015848417536 +1662136015893418496 +1662136015938419456 +1662136015986420480 +1662136016028421376 +1662136016076422400 +1662136016121423360 +1662136016163424256 +1662136016208425216 +1662136016253426176 +1662136016295427072 +1662136016340428032 +1662136016382428928 +1662136016427429888 +1662136016484431104 +1662136016529432064 +1662136016574433024 +1662136016625434112 +1662136016667435008 +1662136016715436032 +1662136016760436992 +1662136016808438016 +1662136016850438912 +1662136016892439808 +1662136016937440768 +1662136016985441792 +1662136017027442688 +1662136017075443712 +1662136017129444864 +1662136017174445824 +1662136017222446848 +1662136017264447744 +1662136017309448704 +1662136017351449600 +1662136017402450688 +1662136017441451520 +1662136017486452480 +1662136017534453504 +1662136017579454464 +1662136017624455424 +1662136017663456256 +1662136017708457216 +1662136017750458112 +1662136017792459008 +1662136017843460096 +1662136017882460928 +1662136017924461824 +1662136017966462720 +1662136018011463680 +1662136018056464640 +1662136018107465728 +1662136018152466688 +1662136018200467712 +1662136018248468736 +1662136018290469632 +1662136018332470528 +1662136018377471488 +1662136018425472512 +1662136018467473408 +1662136018509474304 +1662136018557475328 +1662136018605476352 +1662136018647477248 +1662136018689478144 +1662136018737479168 +1662136018791480320 +1662136018833481216 +1662136018878482176 +1662136018920483072 +1662136018962483968 +1662136019010484992 +1662136019052485888 +1662136019097486848 +1662136019136487680 +1662136019190488832 +1662136019232489728 diff --git a/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track1_light.txt b/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track1_light.txt new file mode 100644 index 0000000000..fc436ed12e --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track1_light.txt @@ -0,0 +1,6263 @@ +1662129779504666880 +1662129779546667776 +1662129779588668672 +1662129779630669568 +1662129779675670528 +1662129779717671424 +1662129779762672384 +1662129779804673280 +1662129779849674240 +1662129779894675200 +1662129779936676096 +1662129779984677120 +1662129780026678016 +1662129780068678912 +1662129780110679808 +1662129780152680704 +1662129780194681600 +1662129780236682496 +1662129780278683392 +1662129780326684416 +1662129780368685312 +1662129780413686272 +1662129780455687168 +1662129780506688256 +1662129780548689152 +1662129780596690176 +1662129780641691136 +1662129780683692032 +1662129780728692992 +1662129780773693952 +1662129780815694848 +1662129780857695744 +1662129780911696896 +1662129780956697856 +1662129781001698816 +1662129781052699904 +1662129781097700864 +1662129781139701760 +1662129781181702656 +1662129781223703552 +1662129781268704512 +1662129781310705408 +1662129781358706432 +1662129781400707328 +1662129781442708224 +1662129781490709248 +1662129781532710144 +1662129781574711040 +1662129781616711936 +1662129781661712896 +1662129781703713792 +1662129781751714816 +1662129781796715776 +1662129781838716672 +1662129781883717632 +1662129781922718464 +1662129781970719488 +1662129782012720384 +1662129782054721280 +1662129782099722240 +1662129782141723136 +1662129782192724224 +1662129782234725120 +1662129782279726080 +1662129782324727040 +1662129782378728192 +1662129782423729152 +1662129782471730176 +1662129782513731072 +1662129782558732032 +1662129782600732928 +1662129782642733824 +1662129782687734784 +1662129782729735680 +1662129782777736704 +1662129782834737920 +1662129782876738816 +1662129782918739712 +1662129782966740736 +1662129783008741632 +1662129783053742592 +1662129783101743616 +1662129783143744512 +1662129783188745472 +1662129783233746432 +1662129783275747328 +1662129783323748352 +1662129783371749376 +1662129783410750208 +1662129783452751104 +1662129783497752064 +1662129783539752960 +1662129783584753920 +1662129783626754816 +1662129783668755712 +1662129783713756672 +1662129783761757696 +1662129783803758592 +1662129783845759488 +1662129783887760384 +1662129783932761344 +1662129783977762304 +1662129784019763200 +1662129784064764160 +1662129784106765056 +1662129784154766080 +1662129784199767040 +1662129784241767936 +1662129784292769024 +1662129784334769920 +1662129784382770944 +1662129784430771968 +1662129784472772864 +1662129784514773760 +1662129784562774784 +1662129784613775872 +1662129784655776768 +1662129784706777856 +1662129784751778816 +1662129784793779712 +1662129784838780672 +1662129784883781632 +1662129784931782656 +1662129784976783616 +1662129785018784512 +1662129785063785472 +1662129785111786496 +1662129785162787584 +1662129785210788608 +1662129785255789568 +1662129785300790528 +1662129785342791424 +1662129785387792384 +1662129785432793344 +1662129785483794432 +1662129785528795392 +1662129785576796416 +1662129785621797376 +1662129785666798336 +1662129785717799424 +1662129785762800384 +1662129785810801408 +1662129785852802304 +1662129785894803200 +1662129785936804096 +1662129785978804992 +1662129786026806016 +1662129786068806912 +1662129786113807872 +1662129786161808896 +1662129786209809920 +1662129786251810816 +1662129786296811776 +1662129786341812736 +1662129786386813696 +1662129786437814784 +1662129786485815808 +1662129786530816768 +1662129786584817920 +1662129786629818880 +1662129786671819776 +1662129786719820800 +1662129786761821696 +1662129786803822592 +1662129786845823488 +1662129786890824448 +1662129786929825280 +1662129786977826304 +1662129787025827328 +1662129787070828288 +1662129787115829248 +1662129787157830144 +1662129787205831168 +1662129787250832128 +1662129787295833088 +1662129787340834048 +1662129787388835072 +1662129787436836096 +1662129787481837056 +1662129787529838080 +1662129787574839040 +1662129787619840000 +1662129787658840832 +1662129787703841792 +1662129787748842752 +1662129787793843712 +1662129787841844736 +1662129787886845696 +1662129787931846656 +1662129787976847616 +1662129788021848576 +1662129788069849600 +1662129788111850496 +1662129788159851520 +1662129788201852416 +1662129788243853312 +1662129788288854272 +1662129788342855424 +1662129788390856448 +1662129788432857344 +1662129788480858368 +1662129788522859264 +1662129788567860224 +1662129788615861248 +1662129788660862208 +1662129788705863168 +1662129788747864064 +1662129788786864896 +1662129788831865856 +1662129788885867008 +1662129788933868032 +1662129788972868864 +1662129789020869888 +1662129789068870912 +1662129789110871808 +1662129789152872704 +1662129789197873664 +1662129789239874560 +1662129789287875584 +1662129789335876608 +1662129789377877504 +1662129789425878528 +1662129789467879424 +1662129789512880384 +1662129789563881472 +1662129789605882368 +1662129789647883264 +1662129789692884224 +1662129789737885184 +1662129789779886080 +1662129789821886976 +1662129789863887872 +1662129789908888832 +1662129789956889856 +1662129790001890816 +1662129790046891776 +1662129790085892608 +1662129790130893568 +1662129790175894528 +1662129790217895424 +1662129790259896320 +1662129790304897280 +1662129790352898304 +1662129790397899264 +1662129790442900224 +1662129790484901120 +1662129790526902016 +1662129790568902912 +1662129790610903808 +1662129790649904640 +1662129790691905536 +1662129790733906432 +1662129790775907328 +1662129790820908288 +1662129790862909184 +1662129790910910208 +1662129790949911040 +1662129790994912000 +1662129791033912832 +1662129791075913728 +1662129791120914688 +1662129791162915584 +1662129791207916544 +1662129791252917504 +1662129791294918400 +1662129791336919296 +1662129791378920192 +1662129791420921088 +1662129791465922048 +1662129791504922880 +1662129791549923840 +1662129791594924800 +1662129791636925696 +1662129791678926592 +1662129791720927488 +1662129791762928384 +1662129791804929280 +1662129791843930112 +1662129791888931072 +1662129791936932096 +1662129791981933056 +1662129792029934080 +1662129792077935104 +1662129792119936000 +1662129792155936768 +1662129792197937664 +1662129792245938688 +1662129792287939584 +1662129792338940672 +1662129792380941568 +1662129792425942528 +1662129792470943488 +1662129792512944384 +1662129792557945344 +1662129792599946240 +1662129792644947200 +1662129792683948032 +1662129792728948992 +1662129792773949952 +1662129792821950976 +1662129792866951936 +1662129792908952832 +1662129792959953920 +1662129793004954880 +1662129793049955840 +1662129793088956672 +1662129793133957632 +1662129793181958656 +1662129793223959552 +1662129793265960448 +1662129793313961472 +1662129793358962432 +1662129793409963520 +1662129793451964416 +1662129793496965376 +1662129793544966400 +1662129793586967296 +1662129793628968192 +1662129793670969088 +1662129793712969984 +1662129793754970880 +1662129793796971776 +1662129793841972736 +1662129793895973888 +1662129793937974784 +1662129793979975680 +1662129794027976704 +1662129794075977728 +1662129794117978624 +1662129794162979584 +1662129794207980544 +1662129794249981440 +1662129794291982336 +1662129794333983232 +1662129794375984128 +1662129794417985024 +1662129794459985920 +1662129794513987072 +1662129794555987968 +1662129794597988864 +1662129794639989760 +1662129794684990720 +1662129794732991744 +1662129794777992704 +1662129794822993664 +1662129794873994752 +1662129794915995648 +1662129794957996544 +1662129795002997504 +1662129795044998400 +1662129795083999232 +1662129795135000320 +1662129795177001216 +1662129795225002240 +1662129795267003136 +1662129795315004160 +1662129795366005248 +1662129795408006144 +1662129795456007168 +1662129795501008128 +1662129795543009024 +1662129795585009920 +1662129795624010752 +1662129795672011776 +1662129795717012736 +1662129795762013696 +1662129795804014592 +1662129795855015680 +1662129795903016704 +1662129795957017856 +1662129796008018944 +1662129796050019840 +1662129796098020864 +1662129796146021888 +1662129796191022848 +1662129796239023872 +1662129796284024832 +1662129796335025920 +1662129796380026880 +1662129796428027904 +1662129796470028800 +1662129796512029696 +1662129796557030656 +1662129796599031552 +1662129796641032448 +1662129796683033344 +1662129796725034240 +1662129796767035136 +1662129796812036096 +1662129796851036928 +1662129796896037888 +1662129796941038848 +1662129796992039936 +1662129797034040832 +1662129797076041728 +1662129797118042624 +1662129797163043584 +1662129797208044544 +1662129797253045504 +1662129797295046400 +1662129797337047296 +1662129797388048384 +1662129797430049280 +1662129797475050240 +1662129797526051328 +1662129797580052480 +1662129797628053504 +1662129797679054592 +1662129797718055424 +1662129797766056448 +1662129797814057472 +1662129797862058496 +1662129797907059456 +1662129797949060352 +1662129797991061248 +1662129798033062144 +1662129798075063040 +1662129798117063936 +1662129798162064896 +1662129798204065792 +1662129798246066688 +1662129798288067584 +1662129798333068544 +1662129798372069376 +1662129798420070400 +1662129798462071296 +1662129798504072192 +1662129798561073408 +1662129798609074432 +1662129798651075328 +1662129798690076160 +1662129798735077120 +1662129798777078016 +1662129798819078912 +1662129798870080000 +1662129798921081088 +1662129798966082048 +1662129799008082944 +1662129799053083904 +1662129799098084864 +1662129799140085760 +1662129799182086656 +1662129799230087680 +1662129799284088832 +1662129799329089792 +1662129799371090688 +1662129799428091904 +1662129799473092864 +1662129799515093760 +1662129799560094720 +1662129799605095680 +1662129799650096640 +1662129799692097536 +1662129799734098432 +1662129799776099328 +1662129799818100224 +1662129799863101184 +1662129799911102208 +1662129799956103168 +1662129800004104192 +1662129800046105088 +1662129800088105984 +1662129800133106944 +1662129800175107840 +1662129800223108864 +1662129800268109824 +1662129800319110912 +1662129800358111744 +1662129800400112640 +1662129800442113536 +1662129800493114624 +1662129800541115648 +1662129800589116672 +1662129800631117568 +1662129800676118528 +1662129800718119424 +1662129800772120576 +1662129800820121600 +1662129800862122496 +1662129800910123520 +1662129800955124480 +1662129801000125440 +1662129801048126464 +1662129801090127360 +1662129801150128640 +1662129801192129536 +1662129801234130432 +1662129801276131328 +1662129801321132288 +1662129801363133184 +1662129801405134080 +1662129801447134976 +1662129801495136000 +1662129801543137024 +1662129801588137984 +1662129801636139008 +1662129801681139968 +1662129801723140864 +1662129801765141760 +1662129801807142656 +1662129801855143680 +1662129801900144640 +1662129801948145664 +1662129801993146624 +1662129802044147712 +1662129802083148544 +1662129802131149568 +1662129802176150528 +1662129802224151552 +1662129802272152576 +1662129802311153408 +1662129802353154304 +1662129802398155264 +1662129802443156224 +1662129802488157184 +1662129802533158144 +1662129802584159232 +1662129802635160320 +1662129802677161216 +1662129802728162304 +1662129802773163264 +1662129802818164224 +1662129802860165120 +1662129802911166208 +1662129802950167040 +1662129802992167936 +1662129803040168960 +1662129803085169920 +1662129803136171008 +1662129803178171904 +1662129803220172800 +1662129803274173952 +1662129803316174848 +1662129803364175872 +1662129803415176960 +1662129803460177920 +1662129803499178752 +1662129803547179776 +1662129803592180736 +1662129803634181632 +1662129803676182528 +1662129803721183488 +1662129803760184320 +1662129803814185472 +1662129803856186368 +1662129803898187264 +1662129803943188224 +1662129803997189376 +1662129804039190272 +1662129804084191232 +1662129804126192128 +1662129804171193088 +1662129804216194048 +1662129804258194944 +1662129804312196096 +1662129804354196992 +1662129804402198016 +1662129804444198912 +1662129804495200000 +1662129804540200960 +1662129804582201856 +1662129804636203008 +1662129804678203904 +1662129804726204928 +1662129804768205824 +1662129804813206784 +1662129804855207680 +1662129804900208640 +1662129804951209728 +1662129804996210688 +1662129805041211648 +1662129805089212672 +1662129805140213760 +1662129805182214656 +1662129805227215616 +1662129805272216576 +1662129805314217472 +1662129805356218368 +1662129805398219264 +1662129805449220352 +1662129805494221312 +1662129805533222144 +1662129805575223040 +1662129805620224000 +1662129805662224896 +1662129805707225856 +1662129805764227072 +1662129805803227904 +1662129805842228736 +1662129805893229824 +1662129805938230784 +1662129805989231872 +1662129806031232768 +1662129806076233728 +1662129806124234752 +1662129806166235648 +1662129806205236480 +1662129806256237568 +1662129806295238400 +1662129806337239296 +1662129806379240192 +1662129806433241344 +1662129806475242240 +1662129806520243200 +1662129806565244160 +1662129806610245120 +1662129806652246016 +1662129806691246848 +1662129806736247808 +1662129806787248896 +1662129806826249728 +1662129806871250688 +1662129806916251648 +1662129806970252800 +1662129807012253696 +1662129807054254592 +1662129807096255488 +1662129807144256512 +1662129807189257472 +1662129807234258432 +1662129807282259456 +1662129807336260608 +1662129807378261504 +1662129807432262656 +1662129807480263680 +1662129807528264704 +1662129807576265728 +1662129807618266624 +1662129807657267456 +1662129807702268416 +1662129807753269504 +1662129807798270464 +1662129807840271360 +1662129807885272320 +1662129807927273216 +1662129807978274304 +1662129808017275136 +1662129808059276032 +1662129808104276992 +1662129808146277888 +1662129808197278976 +1662129808239279872 +1662129808278280704 +1662129808323281664 +1662129808374282752 +1662129808419283712 +1662129808470284800 +1662129808515285760 +1662129808557286656 +1662129808602287616 +1662129808644288512 +1662129808689289472 +1662129808734290432 +1662129808779291392 +1662129808824292352 +1662129808878293504 +1662129808920294400 +1662129808965295360 +1662129809007296256 +1662129809052297216 +1662129809094298112 +1662129809142299136 +1662129809190300160 +1662129809232301056 +1662129809277302016 +1662129809322302976 +1662129809367303936 +1662129809418305024 +1662129809460305920 +1662129809508306944 +1662129809553307904 +1662129809598308864 +1662129809646309888 +1662129809688310784 +1662129809733311744 +1662129809784312832 +1662129809832313856 +1662129809877314816 +1662129809925315840 +1662129809967316736 +1662129810012317696 +1662129810057318656 +1662129810099319552 +1662129810144320512 +1662129810186321408 +1662129810231322368 +1662129810276323328 +1662129810318324224 +1662129810360325120 +1662129810405326080 +1662129810447326976 +1662129810489327872 +1662129810543329024 +1662129810588329984 +1662129810639331072 +1662129810687332096 +1662129810732333056 +1662129810780334080 +1662129810819334912 +1662129810864335872 +1662129810909336832 +1662129810954337792 +1662129810999338752 +1662129811041339648 +1662129811086340608 +1662129811128341504 +1662129811170342400 +1662129811209343232 +1662129811263344384 +1662129811308345344 +1662129811359346432 +1662129811401347328 +1662129811446348288 +1662129811491349248 +1662129811533350144 +1662129811578351104 +1662129811626352128 +1662129811668353024 +1662129811710353920 +1662129811752354816 +1662129811794355712 +1662129811839356672 +1662129811881357568 +1662129811923358464 +1662129811974359552 +1662129812019360512 +1662129812067361536 +1662129812109362432 +1662129812151363328 +1662129812193364224 +1662129812235365120 +1662129812277366016 +1662129812322366976 +1662129812364367872 +1662129812409368832 +1662129812451369728 +1662129812499370752 +1662129812547371776 +1662129812589372672 +1662129812634373632 +1662129812679374592 +1662129812724375552 +1662129812778376704 +1662129812829377792 +1662129812874378752 +1662129812922379776 +1662129812967380736 +1662129813009381632 +1662129813057382656 +1662129813099383552 +1662129813147384576 +1662129813189385472 +1662129813231386368 +1662129813273387264 +1662129813318388224 +1662129813357389056 +1662129813402390016 +1662129813444390912 +1662129813489391872 +1662129813531392768 +1662129813579393792 +1662129813624394752 +1662129813666395648 +1662129813705396480 +1662129813747397376 +1662129813792398336 +1662129813834399232 +1662129813876400128 +1662129813918401024 +1662129813966402048 +1662129814011403008 +1662129814059404032 +1662129814104404992 +1662129814146405888 +1662129814191406848 +1662129814242407936 +1662129814284408832 +1662129814332409856 +1662129814371410688 +1662129814416411648 +1662129814467412736 +1662129814509413632 +1662129814551414528 +1662129814593415424 +1662129814635416320 +1662129814674417152 +1662129814722418176 +1662129814764419072 +1662129814818420224 +1662129814863421184 +1662129814908422144 +1662129814953423104 +1662129815001424128 +1662129815046425088 +1662129815091426048 +1662129815136427008 +1662129815181427968 +1662129815223428864 +1662129815265429760 +1662129815310430720 +1662129815352431616 +1662129815394432512 +1662129815436433408 +1662129815481434368 +1662129815526435328 +1662129815574436352 +1662129815625437440 +1662129815676438528 +1662129815721439488 +1662129815769440512 +1662129815814441472 +1662129815856442368 +1662129815910443520 +1662129815952444416 +1662129815997445376 +1662129816039446272 +1662129816087447296 +1662129816129448192 +1662129816171449088 +1662129816216450048 +1662129816264451072 +1662129816315452160 +1662129816360453120 +1662129816411454208 +1662129816456455168 +1662129816498456064 +1662129816540456960 +1662129816582457856 +1662129816627458816 +1662129816669459712 +1662129816717460736 +1662129816759461632 +1662129816813462784 +1662129816858463744 +1662129816900464640 +1662129816945465600 +1662129816996466688 +1662129817041467648 +1662129817083468544 +1662129817125469440 +1662129817179470592 +1662129817218471424 +1662129817266472448 +1662129817311473408 +1662129817359474432 +1662129817401475328 +1662129817443476224 +1662129817485477120 +1662129817527478016 +1662129817569478912 +1662129817611479808 +1662129817668481024 +1662129817713481984 +1662129817764483072 +1662129817812484096 +1662129817866485248 +1662129817908486144 +1662129817950487040 +1662129817992487936 +1662129818043489024 +1662129818094490112 +1662129818139491072 +1662129818181491968 +1662129818223492864 +1662129818268493824 +1662129818313494784 +1662129818367495936 +1662129818412496896 +1662129818454497792 +1662129818499498752 +1662129818544499712 +1662129818586500608 +1662129818631501568 +1662129818673502464 +1662129818718503424 +1662129818760504320 +1662129818802505216 +1662129818850506240 +1662129818892507136 +1662129818934508032 +1662129818982509056 +1662129819030510080 +1662129819075511040 +1662129819120512000 +1662129819162512896 +1662129819207513856 +1662129819261515008 +1662129819306515968 +1662129819354516992 +1662129819399517952 +1662129819447518976 +1662129819495520000 +1662129819534520832 +1662129819579521792 +1662129819621522688 +1662129819669523712 +1662129819714524672 +1662129819756525568 +1662129819801526528 +1662129819846527488 +1662129819888528384 +1662129819933529344 +1662129819978530304 +1662129820020531200 +1662129820062532096 +1662129820104532992 +1662129820152534016 +1662129820197534976 +1662129820239535872 +1662129820281536768 +1662129820323537664 +1662129820365538560 +1662129820410539520 +1662129820458540544 +1662129820500541440 +1662129820542542336 +1662129820587543296 +1662129820638544384 +1662129820689545472 +1662129820737546496 +1662129820782547456 +1662129820830548480 +1662129820881549568 +1662129820932550656 +1662129820983551744 +1662129821028552704 +1662129821070553600 +1662129821112554496 +1662129821157555456 +1662129821205556480 +1662129821256557568 +1662129821301558528 +1662129821343559424 +1662129821394560512 +1662129821451561728 +1662129821493562624 +1662129821535563520 +1662129821589564672 +1662129821634565632 +1662129821682566656 +1662129821724567552 +1662129821778568704 +1662129821826569728 +1662129821871570688 +1662129821913571584 +1662129821955572480 +1662129821997573376 +1662129822039574272 +1662129822084575232 +1662129822144576512 +1662129822192577536 +1662129822234578432 +1662129822276579328 +1662129822318580224 +1662129822363581184 +1662129822411582208 +1662129822453583104 +1662129822498584064 +1662129822540584960 +1662129822582585856 +1662129822624586752 +1662129822669587712 +1662129822708588544 +1662129822750589440 +1662129822792590336 +1662129822843591424 +1662129822885592320 +1662129822939593472 +1662129822981594368 +1662129823023595264 +1662129823062596096 +1662129823101596928 +1662129823143597824 +1662129823185598720 +1662129823233599744 +1662129823278600704 +1662129823332601856 +1662129823380602880 +1662129823425603840 +1662129823473604864 +1662129823521605888 +1662129823560606720 +1662129823605607680 +1662129823650608640 +1662129823698609664 +1662129823740610560 +1662129823791611648 +1662129823836612608 +1662129823878613504 +1662129823923614464 +1662129823971615488 +1662129824016616448 +1662129824067617536 +1662129824112618496 +1662129824154619392 +1662129824208620544 +1662129824253621504 +1662129824298622464 +1662129824340623360 +1662129824388624384 +1662129824430625280 +1662129824475626240 +1662129824514627072 +1662129824556627968 +1662129824607629056 +1662129824655630080 +1662129824703631104 +1662129824745632000 +1662129824790632960 +1662129824832633856 +1662129824880634880 +1662129824925635840 +1662129824970636800 +1662129825018637824 +1662129825063638784 +1662129825108639744 +1662129825153640704 +1662129825195641600 +1662129825249642752 +1662129825300643840 +1662129825345644800 +1662129825387645696 +1662129825435646720 +1662129825477647616 +1662129825522648576 +1662129825570649600 +1662129825615650560 +1662129825660651520 +1662129825702652416 +1662129825747653376 +1662129825792654336 +1662129825837655296 +1662129825876656128 +1662129825918657024 +1662129825960657920 +1662129826005658880 +1662129826047659776 +1662129826104660992 +1662129826152662016 +1662129826197662976 +1662129826236663808 +1662129826278664704 +1662129826323665664 +1662129826365666560 +1662129826416667648 +1662129826458668544 +1662129826506669568 +1662129826551670528 +1662129826599671552 +1662129826644672512 +1662129826695673600 +1662129826743674624 +1662129826785675520 +1662129826836676608 +1662129826887677696 +1662129826941678848 +1662129826992679936 +1662129827031680768 +1662129827079681792 +1662129827121682688 +1662129827166683648 +1662129827217684736 +1662129827262685696 +1662129827304686592 +1662129827349687552 +1662129827400688640 +1662129827451689728 +1662129827490690560 +1662129827544691712 +1662129827589692672 +1662129827631693568 +1662129827676694528 +1662129827730695680 +1662129827769696512 +1662129827811697408 +1662129827856698368 +1662129827901699328 +1662129827943700224 +1662129827985701120 +1662129828027702016 +1662129828072702976 +1662129828114703872 +1662129828162704896 +1662129828204705792 +1662129828246706688 +1662129828303707904 +1662129828345708800 +1662129828387709696 +1662129828432710656 +1662129828471711488 +1662129828513712384 +1662129828558713344 +1662129828612714496 +1662129828657715456 +1662129828699716352 +1662129828738717184 +1662129828780718080 +1662129828831719168 +1662129828876720128 +1662129828918721024 +1662129828963721984 +1662129829008722944 +1662129829050723840 +1662129829095724800 +1662129829134725632 +1662129829176726528 +1662129829224727552 +1662129829266728448 +1662129829311729408 +1662129829350730240 +1662129829392731136 +1662129829437732096 +1662129829479732992 +1662129829533734144 +1662129829578735104 +1662129829620736000 +1662129829671737088 +1662129829719738112 +1662129829761739008 +1662129829806739968 +1662129829854740992 +1662129829899741952 +1662129829947742976 +1662129829989743872 +1662129830034744832 +1662129830079745792 +1662129830121746688 +1662129830163747584 +1662129830205748480 +1662129830247749376 +1662129830289750272 +1662129830328751104 +1662129830376752128 +1662129830427753216 +1662129830469754112 +1662129830514755072 +1662129830565756160 +1662129830610757120 +1662129830652758016 +1662129830703759104 +1662129830745760000 +1662129830793761024 +1662129830844762112 +1662129830886763008 +1662129830928763904 +1662129830973764864 +1662129831015765760 +1662129831057766656 +1662129831099767552 +1662129831144768512 +1662129831186769408 +1662129831231770368 +1662129831276771328 +1662129831318772224 +1662129831357773056 +1662129831405774080 +1662129831447774976 +1662129831495776000 +1662129831537776896 +1662129831591778048 +1662129831636779008 +1662129831681779968 +1662129831729780992 +1662129831786782208 +1662129831834783232 +1662129831882784256 +1662129831921785088 +1662129831963785984 +1662129832005786880 +1662129832050787840 +1662129832101788928 +1662129832149789952 +1662129832188790784 +1662129832233791744 +1662129832275792640 +1662129832323793664 +1662129832368794624 +1662129832410795520 +1662129832452796416 +1662129832494797312 +1662129832536798208 +1662129832581799168 +1662129832626800128 +1662129832668801024 +1662129832710801920 +1662129832758802944 +1662129832800803840 +1662129832854804992 +1662129832896805888 +1662129832941806848 +1662129832989807872 +1662129833034808832 +1662129833076809728 +1662129833124810752 +1662129833166811648 +1662129833223812864 +1662129833265813760 +1662129833310814720 +1662129833355815680 +1662129833406816768 +1662129833448817664 +1662129833493818624 +1662129833541819648 +1662129833583820544 +1662129833628821504 +1662129833673822464 +1662129833715823360 +1662129833760824320 +1662129833799825152 +1662129833841826048 +1662129833889827072 +1662129833937828096 +1662129833985829120 +1662129834030830080 +1662129834069830912 +1662129834117831936 +1662129834162832896 +1662129834210833920 +1662129834255834880 +1662129834303835904 +1662129834348836864 +1662129834387837696 +1662129834432838656 +1662129834480839680 +1662129834528840704 +1662129834570841600 +1662129834609842432 +1662129834651843328 +1662129834693844224 +1662129834735845120 +1662129834786846208 +1662129834834847232 +1662129834876848128 +1662129834924849152 +1662129834966850048 +1662129835011851008 +1662129835056851968 +1662129835101852928 +1662129835158854144 +1662129835200855040 +1662129835245856000 +1662129835287856896 +1662129835341858048 +1662129835383858944 +1662129835428859904 +1662129835476860928 +1662129835521861888 +1662129835566862848 +1662129835605863680 +1662129835647864576 +1662129835698865664 +1662129835746866688 +1662129835788867584 +1662129835836868608 +1662129835878869504 +1662129835920870400 +1662129835965871360 +1662129836013872384 +1662129836052873216 +1662129836094874112 +1662129836142875136 +1662129836190876160 +1662129836238877184 +1662129836280878080 +1662129836328879104 +1662129836367879936 +1662129836415880960 +1662129836457881856 +1662129836499882752 +1662129836544883712 +1662129836586884608 +1662129836628885504 +1662129836679886592 +1662129836730887680 +1662129836772888576 +1662129836817889536 +1662129836862890496 +1662129836913891584 +1662129836958892544 +1662129837006893568 +1662129837057894656 +1662129837096895488 +1662129837135896320 +1662129837177897216 +1662129837219898112 +1662129837264899072 +1662129837309900032 +1662129837351900928 +1662129837393901824 +1662129837444902912 +1662129837483903744 +1662129837528904704 +1662129837573905664 +1662129837615906560 +1662129837657907456 +1662129837702908416 +1662129837747909376 +1662129837792910336 +1662129837843911424 +1662129837885912320 +1662129837930913280 +1662129837975914240 +1662129838020915200 +1662129838062916096 +1662129838104916992 +1662129838149917952 +1662129838191918848 +1662129838236919808 +1662129838278920704 +1662129838320921600 +1662129838374922752 +1662129838419923712 +1662129838464924672 +1662129838512925696 +1662129838554926592 +1662129838596927488 +1662129838638928384 +1662129838686929408 +1662129838728930304 +1662129838770931200 +1662129838812932096 +1662129838854932992 +1662129838896933888 +1662129838941934848 +1662129838983935744 +1662129839028936704 +1662129839070937600 +1662129839112938496 +1662129839154939392 +1662129839199940352 +1662129839244941312 +1662129839286942208 +1662129839328943104 +1662129839370944000 +1662129839421945088 +1662129839463945984 +1662129839508946944 +1662129839550947840 +1662129839589948672 +1662129839631949568 +1662129839673950464 +1662129839715951360 +1662129839757952256 +1662129839802953216 +1662129839844954112 +1662129839895955200 +1662129839940956160 +1662129839982957056 +1662129840024957952 +1662129840075959040 +1662129840126960128 +1662129840171961088 +1662129840213961984 +1662129840255962880 +1662129840297963776 +1662129840339964672 +1662129840381965568 +1662129840426966528 +1662129840468967424 +1662129840513968384 +1662129840564969472 +1662129840609970432 +1662129840660971520 +1662129840708972544 +1662129840759973632 +1662129840801974528 +1662129840843975424 +1662129840888976384 +1662129840933977344 +1662129840975978240 +1662129841020979200 +1662129841071980288 +1662129841116981248 +1662129841164982272 +1662129841203983104 +1662129841248984064 +1662129841302985216 +1662129841344986112 +1662129841392987136 +1662129841434988032 +1662129841479988992 +1662129841527990016 +1662129841569990912 +1662129841617991936 +1662129841662992896 +1662129841707993856 +1662129841749994752 +1662129841791995648 +1662129841833996544 +1662129841875997440 +1662129841914998272 +1662129841956999168 +1662129841999000064 +1662129842041000960 +1662129842086001920 +1662129842131002880 +1662129842188004096 +1662129842233005056 +1662129842278006016 +1662129842326007040 +1662129842368007936 +1662129842419009024 +1662129842458009856 +1662129842500010752 +1662129842542011648 +1662129842584012544 +1662129842626013440 +1662129842680014592 +1662129842719015424 +1662129842773016576 +1662129842818017536 +1662129842860018432 +1662129842905019392 +1662129842947020288 +1662129842992021248 +1662129843040022272 +1662129843079023104 +1662129843121024000 +1662129843166024960 +1662129843208025856 +1662129843250026752 +1662129843292027648 +1662129843337028608 +1662129843382029568 +1662129843433030656 +1662129843481031680 +1662129843526032640 +1662129843574033664 +1662129843625034752 +1662129843667035648 +1662129843709036544 +1662129843751037440 +1662129843793038336 +1662129843835039232 +1662129843880040192 +1662129843922041088 +1662129843973042176 +1662129844018043136 +1662129844066044160 +1662129844108045056 +1662129844150045952 +1662129844204047104 +1662129844255048192 +1662129844297049088 +1662129844339049984 +1662129844381050880 +1662129844423051776 +1662129844462052608 +1662129844504053504 +1662129844552054528 +1662129844597055488 +1662129844642056448 +1662129844687057408 +1662129844732058368 +1662129844771059200 +1662129844813060096 +1662129844855060992 +1662129844906062080 +1662129844948062976 +1662129844996064000 +1662129845035064832 +1662129845083065856 +1662129845137067008 +1662129845179067904 +1662129845227068928 +1662129845272069888 +1662129845314070784 +1662129845356071680 +1662129845401072640 +1662129845443073536 +1662129845485074432 +1662129845527075328 +1662129845572076288 +1662129845617077248 +1662129845662078208 +1662129845704079104 +1662129845746080000 +1662129845788080896 +1662129845836081920 +1662129845878082816 +1662129845926083840 +1662129845974084864 +1662129846019085824 +1662129846067086848 +1662129846112087808 +1662129846157088768 +1662129846202089728 +1662129846244090624 +1662129846286091520 +1662129846328092416 +1662129846385093632 +1662129846424094464 +1662129846469095424 +1662129846508096256 +1662129846553097216 +1662129846598098176 +1662129846649099264 +1662129846697100288 +1662129846739101184 +1662129846787102208 +1662129846832103168 +1662129846874104064 +1662129846919105024 +1662129846964105984 +1662129847006106880 +1662129847051107840 +1662129847105108992 +1662129847156110080 +1662129847201111040 +1662129847246112000 +1662129847288112896 +1662129847336113920 +1662129847384114944 +1662129847423115776 +1662129847468116736 +1662129847519117824 +1662129847567118848 +1662129847612119808 +1662129847654120704 +1662129847702121728 +1662129847744122624 +1662129847783123456 +1662129847831124480 +1662129847873125376 +1662129847921126400 +1662129847963127296 +1662129848005128192 +1662129848053129216 +1662129848107130368 +1662129848152131328 +1662129848197132288 +1662129848242133248 +1662129848284134144 +1662129848332135168 +1662129848380136192 +1662129848422137088 +1662129848467138048 +1662129848509138944 +1662129848551139840 +1662129848593140736 +1662129848632141568 +1662129848674142464 +1662129848719143424 +1662129848764144384 +1662129848812145408 +1662129848857146368 +1662129848896147200 +1662129848941148160 +1662129848992149248 +1662129849034150144 +1662129849076151040 +1662129849127152128 +1662129849169153024 +1662129849223154176 +1662129849277155328 +1662129849325156352 +1662129849367157248 +1662129849418158336 +1662129849466159360 +1662129849514160384 +1662129849556161280 +1662129849604162304 +1662129849652163328 +1662129849694164224 +1662129849736165120 +1662129849781166080 +1662129849832167168 +1662129849877168128 +1662129849922169088 +1662129849964169984 +1662129850009170944 +1662129850051171840 +1662129850093172736 +1662129850138173696 +1662129850180174592 +1662129850222175488 +1662129850264176384 +1662129850315177472 +1662129850360178432 +1662129850399179264 +1662129850444180224 +1662129850489181184 +1662129850531182080 +1662129850576183040 +1662129850621184000 +1662129850669185024 +1662129850714185984 +1662129850759186944 +1662129850804187904 +1662129850846188800 +1662129850894189824 +1662129850936190720 +1662129850987191808 +1662129851029192704 +1662129851074193664 +1662129851119194624 +1662129851164195584 +1662129851209196544 +1662129851254197504 +1662129851299198464 +1662129851338199296 +1662129851380200192 +1662129851422201088 +1662129851470202112 +1662129851515203072 +1662129851554203904 +1662129851596204800 +1662129851647205888 +1662129851695206912 +1662129851737207808 +1662129851785208832 +1662129851830209792 +1662129851872210688 +1662129851917211648 +1662129851959212544 +1662129852001213440 +1662129852049214464 +1662129852100215552 +1662129852148216576 +1662129852190217472 +1662129852229218304 +1662129852271219200 +1662129852313220096 +1662129852355220992 +1662129852409222144 +1662129852451223040 +1662129852496224000 +1662129852538224896 +1662129852583225856 +1662129852625226752 +1662129852676227840 +1662129852724228864 +1662129852766229760 +1662129852811230720 +1662129852859231744 +1662129852907232768 +1662129852955233792 +1662129852997234688 +1662129853042235648 +1662129853090236672 +1662129853138237696 +1662129853189238784 +1662129853237239808 +1662129853279240704 +1662129853324241664 +1662129853366242560 +1662129853408243456 +1662129853453244416 +1662129853501245440 +1662129853543246336 +1662129853591247360 +1662129853636248320 +1662129853678249216 +1662129853723250176 +1662129853771251200 +1662129853816252160 +1662129853873253376 +1662129853924254464 +1662129853969255424 +1662129854011256320 +1662129854056257280 +1662129854098258176 +1662129854140259072 +1662129854185260032 +1662129854233261056 +1662129854284262144 +1662129854329263104 +1662129854374264064 +1662129854422265088 +1662129854473266176 +1662129854521267200 +1662129854560268032 +1662129854605268992 +1662129854644269824 +1662129854686270720 +1662129854728271616 +1662129854782272768 +1662129854827273728 +1662129854869274624 +1662129854911275520 +1662129854962276608 +1662129855010277632 +1662129855055278592 +1662129855100279552 +1662129855142280448 +1662129855187281408 +1662129855235282432 +1662129855283283456 +1662129855328284416 +1662129855370285312 +1662129855409286144 +1662129855454287104 +1662129855499288064 +1662129855541288960 +1662129855580289792 +1662129855625290752 +1662129855670291712 +1662129855712292608 +1662129855754293504 +1662129855799294464 +1662129855841295360 +1662129855886296320 +1662129855937297408 +1662129855976298240 +1662129856018299136 +1662129856066300160 +1662129856111301120 +1662129856156302080 +1662129856204303104 +1662129856255304192 +1662129856297305088 +1662129856339305984 +1662129856381306880 +1662129856426307840 +1662129856465308672 +1662129856507309568 +1662129856549310464 +1662129856594311424 +1662129856636312320 +1662129856678313216 +1662129856720314112 +1662129856768315136 +1662129856813316096 +1662129856855316992 +1662129856897317888 +1662129856939318784 +1662129856984319744 +1662129857029320704 +1662129857074321664 +1662129857122322688 +1662129857167323648 +1662129857215324672 +1662129857260325632 +1662129857302326528 +1662129857350327552 +1662129857395328512 +1662129857437329408 +1662129857479330304 +1662129857521331200 +1662129857566332160 +1662129857614333184 +1662129857656334080 +1662129857698334976 +1662129857743335936 +1662129857785336832 +1662129857827337728 +1662129857875338752 +1662129857917339648 +1662129857959340544 +1662129858001341440 +1662129858049342464 +1662129858088343296 +1662129858127344128 +1662129858169345024 +1662129858211345920 +1662129858259346944 +1662129858301347840 +1662129858352348928 +1662129858403350016 +1662129858448350976 +1662129858496352000 +1662129858541352960 +1662129858589353984 +1662129858637355008 +1662129858688356096 +1662129858727356928 +1662129858769357824 +1662129858814358784 +1662129858856359680 +1662129858898360576 +1662129858943361536 +1662129858985362432 +1662129859042363648 +1662129859087364608 +1662129859126365440 +1662129859171366400 +1662129859213367296 +1662129859255368192 +1662129859300369152 +1662129859342370048 +1662129859390371072 +1662129859432371968 +1662129859477372928 +1662129859528374016 +1662129859570374912 +1662129859615375872 +1662129859657376768 +1662129859699377664 +1662129859750378752 +1662129859792379648 +1662129859834380544 +1662129859879381504 +1662129859921382400 +1662129859963383296 +1662129860008384256 +1662129860053385216 +1662129860095386112 +1662129860140387072 +1662129860182387968 +1662129860233389056 +1662129860275389952 +1662129860320390912 +1662129860368391936 +1662129860419393024 +1662129860464393984 +1662129860506394880 +1662129860548395776 +1662129860590396672 +1662129860641397760 +1662129860683398656 +1662129860731399680 +1662129860776400640 +1662129860818401536 +1662129860869402624 +1662129860917403648 +1662129860959404544 +1662129861007405568 +1662129861055406592 +1662129861097407488 +1662129861142408448 +1662129861184409344 +1662129861229410304 +1662129861274411264 +1662129861319412224 +1662129861364413184 +1662129861415414272 +1662129861457415168 +1662129861496416000 +1662129861538416896 +1662129861586417920 +1662129861625418752 +1662129861667419648 +1662129861712420608 +1662129861754421504 +1662129861796422400 +1662129861838423296 +1662129861886424320 +1662129861937425408 +1662129861982426368 +1662129862024427264 +1662129862066428160 +1662129862114429184 +1662129862159430144 +1662129862201431040 +1662129862243431936 +1662129862291432960 +1662129862336433920 +1662129862378434816 +1662129862423435776 +1662129862465436672 +1662129862516437760 +1662129862561438720 +1662129862603439616 +1662129862648440576 +1662129862687441408 +1662129862729442304 +1662129862777443328 +1662129862825444352 +1662129862867445248 +1662129862912446208 +1662129862960447232 +1662129863005448192 +1662129863056449280 +1662129863101450240 +1662129863140451072 +1662129863182451968 +1662129863224452864 +1662129863266453760 +1662129863317454848 +1662129863359455744 +1662129863407456768 +1662129863455457792 +1662129863497458688 +1662129863542459648 +1662129863584460544 +1662129863626461440 +1662129863674462464 +1662129863722463488 +1662129863764464384 +1662129863806465280 +1662129863845466112 +1662129863890467072 +1662129863932467968 +1662129863977468928 +1662129864019469824 +1662129864061470720 +1662129864106471680 +1662129864154472704 +1662129864202473728 +1662129864244474624 +1662129864286475520 +1662129864331476480 +1662129864382477568 +1662129864427478528 +1662129864472479488 +1662129864517480448 +1662129864559481344 +1662129864601482240 +1662129864646483200 +1662129864694484224 +1662129864733485056 +1662129864778486016 +1662129864829487104 +1662129864880488192 +1662129864922489088 +1662129864964489984 +1662129865006490880 +1662129865054491904 +1662129865099492864 +1662129865141493760 +1662129865183494656 +1662129865222495488 +1662129865270496512 +1662129865312497408 +1662129865351498240 +1662129865393499136 +1662129865438500096 +1662129865489501184 +1662129865534502144 +1662129865579503104 +1662129865624504064 +1662129865666504960 +1662129865708505856 +1662129865753506816 +1662129865804507904 +1662129865846508800 +1662129865894509824 +1662129865939510784 +1662129865981511680 +1662129866023512576 +1662129866077513728 +1662129866125514752 +1662129866167515648 +1662129866212516608 +1662129866257517568 +1662129866308518656 +1662129866353519616 +1662129866398520576 +1662129866440521472 +1662129866485522432 +1662129866530523392 +1662129866578524416 +1662129866620525312 +1662129866662526208 +1662129866707527168 +1662129866752528128 +1662129866794529024 +1662129866836529920 +1662129866875530752 +1662129866920531712 +1662129866974532864 +1662129867022533888 +1662129867064534784 +1662129867106535680 +1662129867151536640 +1662129867190537472 +1662129867244538624 +1662129867289539584 +1662129867331540480 +1662129867385541632 +1662129867427542528 +1662129867472543488 +1662129867517544448 +1662129867562545408 +1662129867607546368 +1662129867649547264 +1662129867697548288 +1662129867742549248 +1662129867787550208 +1662129867829551104 +1662129867868551936 +1662129867916552960 +1662129867961553920 +1662129868009554944 +1662129868054555904 +1662129868096556800 +1662129868150557952 +1662129868192558848 +1662129868234559744 +1662129868279560704 +1662129868327561728 +1662129868378562816 +1662129868423563776 +1662129868465564672 +1662129868507565568 +1662129868549566464 +1662129868591567360 +1662129868633568256 +1662129868675569152 +1662129868723570176 +1662129868768571136 +1662129868822572288 +1662129868867573248 +1662129868909574144 +1662129868957575168 +1662129869002576128 +1662129869050577152 +1662129869092578048 +1662129869137579008 +1662129869182579968 +1662129869224580864 +1662129869266581760 +1662129869314582784 +1662129869356583680 +1662129869401584640 +1662129869449585664 +1662129869491586560 +1662129869533587456 +1662129869575588352 +1662129869614589184 +1662129869659590144 +1662129869701591040 +1662129869749592064 +1662129869788592896 +1662129869830593792 +1662129869875594752 +1662129869917595648 +1662129869962596608 +1662129870010597632 +1662129870055598592 +1662129870097599488 +1662129870142600448 +1662129870184601344 +1662129870226602240 +1662129870271603200 +1662129870316604160 +1662129870355604992 +1662129870409606144 +1662129870451607040 +1662129870502608128 +1662129870541608960 +1662129870586609920 +1662129870628610816 +1662129870673611776 +1662129870718612736 +1662129870763613696 +1662129870808614656 +1662129870850615552 +1662129870892616448 +1662129870943617536 +1662129870985618432 +1662129871033619456 +1662129871078620416 +1662129871129621504 +1662129871171622400 +1662129871216623360 +1662129871258624256 +1662129871306625280 +1662129871348626176 +1662129871390627072 +1662129871432627968 +1662129871474628864 +1662129871525629952 +1662129871573630976 +1662129871615631872 +1662129871657632768 +1662129871702633728 +1662129871744634624 +1662129871789635584 +1662129871837636608 +1662129871885637632 +1662129871930638592 +1662129871972639488 +1662129872020640512 +1662129872065641472 +1662129872107642368 +1662129872149643264 +1662129872191644160 +1662129872239645184 +1662129872287646208 +1662129872332647168 +1662129872374648064 +1662129872419649024 +1662129872464649984 +1662129872509650944 +1662129872557651968 +1662129872602652928 +1662129872644653824 +1662129872689654784 +1662129872731655680 +1662129872773656576 +1662129872827657728 +1662129872875658752 +1662129872926659840 +1662129872977660928 +1662129873025661952 +1662129873070662912 +1662129873124664064 +1662129873178665216 +1662129873223666176 +1662129873271667200 +1662129873328668416 +1662129873370669312 +1662129873415670272 +1662129873460671232 +1662129873505672192 +1662129873547673088 +1662129873592674048 +1662129873634674944 +1662129873679675904 +1662129873721676800 +1662129873763677696 +1662129873808678656 +1662129873853679616 +1662129873898680576 +1662129873940681472 +1662129873982682368 +1662129874024683264 +1662129874072684288 +1662129874123685376 +1662129874168686336 +1662129874210687232 +1662129874255688192 +1662129874297689088 +1662129874348690176 +1662129874393691136 +1662129874435692032 +1662129874477692928 +1662129874522693888 +1662129874567694848 +1662129874609695744 +1662129874651696640 +1662129874693697536 +1662129874735698432 +1662129874780699392 +1662129874822700288 +1662129874867701248 +1662129874921702400 +1662129874966703360 +1662129875011704320 +1662129875053705216 +1662129875095706112 +1662129875137707008 +1662129875179707904 +1662129875221708800 +1662129875266709760 +1662129875311710720 +1662129875356711680 +1662129875395712512 +1662129875437713408 +1662129875482714368 +1662129875524715264 +1662129875569716224 +1662129875611717120 +1662129875650717952 +1662129875692718848 +1662129875743719936 +1662129875788720896 +1662129875830721792 +1662129875872722688 +1662129875917723648 +1662129875959724544 +1662129876001725440 +1662129876052726528 +1662129876103727616 +1662129876148728576 +1662129876190729472 +1662129876238730496 +1662129876286731520 +1662129876328732416 +1662129876373733376 +1662129876415734272 +1662129876463735296 +1662129876508736256 +1662129876550737152 +1662129876592738048 +1662129876634738944 +1662129876679739904 +1662129876727740928 +1662129876775741952 +1662129876817742848 +1662129876859743744 +1662129876904744704 +1662129876943745536 +1662129876985746432 +1662129877030747392 +1662129877075748352 +1662129877120749312 +1662129877165750272 +1662129877222751488 +1662129877270752512 +1662129877312753408 +1662129877357754368 +1662129877399755264 +1662129877441756160 +1662129877483757056 +1662129877528758016 +1662129877567758848 +1662129877609759744 +1662129877651760640 +1662129877696761600 +1662129877735762432 +1662129877783763456 +1662129877831764480 +1662129877873765376 +1662129877924766464 +1662129877969767424 +1662129878014768384 +1662129878053769216 +1662129878095770112 +1662129878140771072 +1662129878185772032 +1662129878227772928 +1662129878266773760 +1662129878311774720 +1662129878353775616 +1662129878401776640 +1662129878446777600 +1662129878488778496 +1662129878530779392 +1662129878578780416 +1662129878617781248 +1662129878665782272 +1662129878707783168 +1662129878752784128 +1662129878794785024 +1662129878845786112 +1662129878890787072 +1662129878932787968 +1662129878974788864 +1662129879025789952 +1662129879073790976 +1662129879115791872 +1662129879166792960 +1662129879214793984 +1662129879256794880 +1662129879295795712 +1662129879337796608 +1662129879382797568 +1662129879427798528 +1662129879469799424 +1662129879514800384 +1662129879559801344 +1662129879604802304 +1662129879652803328 +1662129879700804352 +1662129879742805248 +1662129879784806144 +1662129879832807168 +1662129879877808128 +1662129879925809152 +1662129879967810048 +1662129880009810944 +1662129880060812032 +1662129880105812992 +1662129880144813824 +1662129880189814784 +1662129880231815680 +1662129880279816704 +1662129880321817600 +1662129880366818560 +1662129880408819456 +1662129880456820480 +1662129880498821376 +1662129880540822272 +1662129880585823232 +1662129880624824064 +1662129880669825024 +1662129880711825920 +1662129880756826880 +1662129880801827840 +1662129880843828736 +1662129880885829632 +1662129880933830656 +1662129880981831680 +1662129881029832704 +1662129881074833664 +1662129881116834560 +1662129881158835456 +1662129881203836416 +1662129881245837312 +1662129881293838336 +1662129881335839232 +1662129881383840256 +1662129881425841152 +1662129881470842112 +1662129881524843264 +1662129881569844224 +1662129881611845120 +1662129881656846080 +1662129881704847104 +1662129881749848064 +1662129881794849024 +1662129881836849920 +1662129881887851008 +1662129881929851904 +1662129881977852928 +1662129882019853824 +1662129882064854784 +1662129882118855936 +1662129882163856896 +1662129882211857920 +1662129882253858816 +1662129882298859776 +1662129882340860672 +1662129882382861568 +1662129882421862400 +1662129882463863296 +1662129882508864256 +1662129882553865216 +1662129882601866240 +1662129882643867136 +1662129882685868032 +1662129882733869056 +1662129882781870080 +1662129882826871040 +1662129882871872000 +1662129882913872896 +1662129882955873792 +1662129882997874688 +1662129883036875520 +1662129883078876416 +1662129883132877568 +1662129883174878464 +1662129883216879360 +1662129883267880448 +1662129883309881344 +1662129883351882240 +1662129883399883264 +1662129883444884224 +1662129883483885056 +1662129883525885952 +1662129883576887040 +1662129883624888064 +1662129883675889152 +1662129883723890176 +1662129883762891008 +1662129883810892032 +1662129883861893120 +1662129883903894016 +1662129883948894976 +1662129883996896000 +1662129884038896896 +1662129884092898048 +1662129884137899008 +1662129884185900032 +1662129884230900992 +1662129884281902080 +1662129884320902912 +1662129884368903936 +1662129884407904768 +1662129884452905728 +1662129884497906688 +1662129884548907776 +1662129884593908736 +1662129884635909632 +1662129884686910720 +1662129884737911808 +1662129884782912768 +1662129884827913728 +1662129884872914688 +1662129884923915776 +1662129884968916736 +1662129885010917632 +1662129885049918464 +1662129885091919360 +1662129885142920448 +1662129885187921408 +1662129885229922304 +1662129885277923328 +1662129885322924288 +1662129885367925248 +1662129885409926144 +1662129885454927104 +1662129885505928192 +1662129885550929152 +1662129885595930112 +1662129885643931136 +1662129885685932032 +1662129885730932992 +1662129885772933888 +1662129885826935040 +1662129885877936128 +1662129885919937024 +1662129885961937920 +1662129886006938880 +1662129886060940032 +1662129886105940992 +1662129886147941888 +1662129886192942848 +1662129886234943744 +1662129886276944640 +1662129886318945536 +1662129886378946816 +1662129886423947776 +1662129886465948672 +1662129886510949632 +1662129886558950656 +1662129886603951616 +1662129886645952512 +1662129886687953408 +1662129886732954368 +1662129886777955328 +1662129886819956224 +1662129886861957120 +1662129886909958144 +1662129886951959040 +1662129886996960000 +1662129887038960896 +1662129887080961792 +1662129887134962944 +1662129887173963776 +1662129887218964736 +1662129887263965696 +1662129887308966656 +1662129887353967616 +1662129887398968576 +1662129887449969664 +1662129887491970560 +1662129887533971456 +1662129887578972416 +1662129887623973376 +1662129887665974272 +1662129887710975232 +1662129887758976256 +1662129887797977088 +1662129887839977984 +1662129887881978880 +1662129887929979904 +1662129887974980864 +1662129888019981824 +1662129888061982720 +1662129888112983808 +1662129888151984640 +1662129888199985664 +1662129888244986624 +1662129888286987520 +1662129888331988480 +1662129888376989440 +1662129888418990336 +1662129888460991232 +1662129888508992256 +1662129888553993216 +1662129888595994112 +1662129888637995008 +1662129888679995904 +1662129888721996800 +1662129888763997696 +1662129888808998656 +1662129888850999552 +1662129888893000448 +1662129888935001344 +1662129888980002304 +1662129889025003264 +1662129889064004096 +1662129889112005120 +1662129889157006080 +1662129889202007040 +1662129889241007872 +1662129889289008896 +1662129889331009792 +1662129889376010752 +1662129889424011776 +1662129889466012672 +1662129889508013568 +1662129889559014656 +1662129889604015616 +1662129889643016448 +1662129889685017344 +1662129889730018304 +1662129889772019200 +1662129889826020352 +1662129889865021184 +1662129889904022016 +1662129889952023040 +1662129889997024000 +1662129890039024896 +1662129890081025792 +1662129890123026688 +1662129890171027712 +1662129890213028608 +1662129890255029504 +1662129890297030400 +1662129890339031296 +1662129890381032192 +1662129890423033088 +1662129890471034112 +1662129890513035008 +1662129890558035968 +1662129890603036928 +1662129890648037888 +1662129890702039040 +1662129890750040064 +1662129890789040896 +1662129890840041984 +1662129890882042880 +1662129890927043840 +1662129890972044800 +1662129891020045824 +1662129891062046720 +1662129891116047872 +1662129891164048896 +1662129891209049856 +1662129891257050880 +1662129891299051776 +1662129891344052736 +1662129891386053632 +1662129891428054528 +1662129891467055360 +1662129891509056256 +1662129891554057216 +1662129891599058176 +1662129891644059136 +1662129891686060032 +1662129891743061248 +1662129891785062144 +1662129891824062976 +1662129891863063808 +1662129891911064832 +1662129891956065792 +1662129891998066688 +1662129892040067584 +1662129892088068608 +1662129892133069568 +1662129892175070464 +1662129892217071360 +1662129892259072256 +1662129892304073216 +1662129892346074112 +1662129892391075072 +1662129892436076032 +1662129892484077056 +1662129892523077888 +1662129892565078784 +1662129892610079744 +1662129892655080704 +1662129892697081600 +1662129892745082624 +1662129892787083520 +1662129892835084544 +1662129892880085504 +1662129892931086592 +1662129892973087488 +1662129893015088384 +1662129893057089280 +1662129893096090112 +1662129893138091008 +1662129893183091968 +1662129893228092928 +1662129893276093952 +1662129893327095040 +1662129893369095936 +1662129893414096896 +1662129893459097856 +1662129893501098752 +1662129893546099712 +1662129893600100864 +1662129893645101824 +1662129893687102720 +1662129893735103744 +1662129893774104576 +1662129893816105472 +1662129893858106368 +1662129893900107264 +1662129893948108288 +1662129893990109184 +1662129894035110144 +1662129894080111104 +1662129894128112128 +1662129894170113024 +1662129894215113984 +1662129894257114880 +1662129894299115776 +1662129894341116672 +1662129894386117632 +1662129894425118464 +1662129894467119360 +1662129894515120384 +1662129894560121344 +1662129894611122432 +1662129894650123264 +1662129894695124224 +1662129894737125120 +1662129894782126080 +1662129894833127168 +1662129894884128256 +1662129894929129216 +1662129894977130240 +1662129895034131456 +1662129895085132544 +1662129895130133504 +1662129895172134400 +1662129895214135296 +1662129895262136320 +1662129895304137216 +1662129895343138048 +1662129895385138944 +1662129895427139840 +1662129895466140672 +1662129895511141632 +1662129895568142848 +1662129895616143872 +1662129895661144832 +1662129895709145856 +1662129895760146944 +1662129895808147968 +1662129895850148864 +1662129895895149824 +1662129895934150656 +1662129895979151616 +1662129896033152768 +1662129896075153664 +1662129896126154752 +1662129896171155712 +1662129896216156672 +1662129896258157568 +1662129896303158528 +1662129896348159488 +1662129896390160384 +1662129896438161408 +1662129896486162432 +1662129896534163456 +1662129896582164480 +1662129896621165312 +1662129896669166336 +1662129896714167296 +1662129896756168192 +1662129896801169152 +1662129896849170176 +1662129896897171200 +1662129896945172224 +1662129896990173184 +1662129897032174080 +1662129897077175040 +1662129897122176000 +1662129897170177024 +1662129897212177920 +1662129897254178816 +1662129897299179776 +1662129897341180672 +1662129897380181504 +1662129897428182528 +1662129897479183616 +1662129897521184512 +1662129897566185472 +1662129897605186304 +1662129897647187200 +1662129897695188224 +1662129897734189056 +1662129897776189952 +1662129897821190912 +1662129897863191808 +1662129897908192768 +1662129897956193792 +1662129897998194688 +1662129898037195520 +1662129898085196544 +1662129898127197440 +1662129898169198336 +1662129898220199424 +1662129898262200320 +1662129898307201280 +1662129898349202176 +1662129898397203200 +1662129898448204288 +1662129898493205248 +1662129898538206208 +1662129898586207232 +1662129898646208512 +1662129898694209536 +1662129898736210432 +1662129898784211456 +1662129898829212416 +1662129898877213440 +1662129898919214336 +1662129898970215424 +1662129899015216384 +1662129899063217408 +1662129899111218432 +1662129899156219392 +1662129899204220416 +1662129899246221312 +1662129899291222272 +1662129899333223168 +1662129899378224128 +1662129899420225024 +1662129899462225920 +1662129899504226816 +1662129899549227776 +1662129899591228672 +1662129899636229632 +1662129899687230720 +1662129899732231680 +1662129899774232576 +1662129899816233472 +1662129899858234368 +1662129899900235264 +1662129899945236224 +1662129899993237248 +1662129900041238272 +1662129900083239168 +1662129900137240320 +1662129900188241408 +1662129900233242368 +1662129900284243456 +1662129900329244416 +1662129900371245312 +1662129900410246144 +1662129900449246976 +1662129900497248000 +1662129900539248896 +1662129900584249856 +1662129900635250944 +1662129900683251968 +1662129900725252864 +1662129900770253824 +1662129900821254912 +1662129900863255808 +1662129900905256704 +1662129900956257792 +1662129900998258688 +1662129901040259584 +1662129901082260480 +1662129901136261632 +1662129901178262528 +1662129901217263360 +1662129901262264320 +1662129901304265216 +1662129901352266240 +1662129901403267328 +1662129901448268288 +1662129901493269248 +1662129901535270144 +1662129901577271040 +1662129901631272192 +1662129901676273152 +1662129901715273984 +1662129901760274944 +1662129901799275776 +1662129901844276736 +1662129901886277632 +1662129901928278528 +1662129901973279488 +1662129902015280384 +1662129902057281280 +1662129902099282176 +1662129902141283072 +1662129902183283968 +1662129902225284864 +1662129902270285824 +1662129902318286848 +1662129902363287808 +1662129902408288768 +1662129902459289856 +1662129902507290880 +1662129902555291904 +1662129902597292800 +1662129902651293952 +1662129902696294912 +1662129902738295808 +1662129902789296896 +1662129902831297792 +1662129902882298880 +1662129902936300032 +1662129902978300928 +1662129903020301824 +1662129903062302720 +1662129903110303744 +1662129903155304704 +1662129903197305600 +1662129903239306496 +1662129903281307392 +1662129903323308288 +1662129903365309184 +1662129903410310144 +1662129903455311104 +1662129903494311936 +1662129903536312832 +1662129903578313728 +1662129903617314560 +1662129903662315520 +1662129903704316416 +1662129903749317376 +1662129903791318272 +1662129903833319168 +1662129903875320064 +1662129903920321024 +1662129903962321920 +1662129904019323136 +1662129904061324032 +1662129904106324992 +1662129904151325952 +1662129904199326976 +1662129904241327872 +1662129904289328896 +1662129904331329792 +1662129904379330816 +1662129904421331712 +1662129904463332608 +1662129904505333504 +1662129904547334400 +1662129904592335360 +1662129904634336256 +1662129904679337216 +1662129904721338112 +1662129904766339072 +1662129904805339904 +1662129904847340800 +1662129904889341696 +1662129904931342592 +1662129904976343552 +1662129905021344512 +1662129905063345408 +1662129905105346304 +1662129905156347392 +1662129905195348224 +1662129905231348992 +1662129905276349952 +1662129905318350848 +1662129905363351808 +1662129905405352704 +1662129905450353664 +1662129905492354560 +1662129905537355520 +1662129905591356672 +1662129905633357568 +1662129905687358720 +1662129905738359808 +1662129905780360704 +1662129905825361664 +1662129905867362560 +1662129905918363648 +1662129905960364544 +1662129906005365504 +1662129906047366400 +1662129906089367296 +1662129906131368192 +1662129906176369152 +1662129906224370176 +1662129906266371072 +1662129906311372032 +1662129906362373120 +1662129906404374016 +1662129906449374976 +1662129906494375936 +1662129906536376832 +1662129906578377728 +1662129906623378688 +1662129906668379648 +1662129906707380480 +1662129906749381376 +1662129906803382528 +1662129906845383424 +1662129906887384320 +1662129906932385280 +1662129906974386176 +1662129907019387136 +1662129907064388096 +1662129907106388992 +1662129907151389952 +1662129907196390912 +1662129907238391808 +1662129907286392832 +1662129907331393792 +1662129907370394624 +1662129907412395520 +1662129907454396416 +1662129907499397376 +1662129907541398272 +1662129907583399168 +1662129907625400064 +1662129907670401024 +1662129907712401920 +1662129907760402944 +1662129907811404032 +1662129907853404928 +1662129907898405888 +1662129907937406720 +1662129907982407680 +1662129908027408640 +1662129908072409600 +1662129908123410688 +1662129908168411648 +1662129908216412672 +1662129908258413568 +1662129908303414528 +1662129908345415424 +1662129908387416320 +1662129908441417472 +1662129908498418688 +1662129908549419776 +1662129908591420672 +1662129908639421696 +1662129908687422720 +1662129908729423616 +1662129908771424512 +1662129908816425472 +1662129908858426368 +1662129908915427584 +1662129908960428544 +1662129909005429504 +1662129909050430464 +1662129909095431424 +1662129909140432384 +1662129909179433216 +1662129909221434112 +1662129909266435072 +1662129909305435904 +1662129909347436800 +1662129909392437760 +1662129909434438656 +1662129909479439616 +1662129909521440512 +1662129909572441600 +1662129909611442432 +1662129909653443328 +1662129909698444288 +1662129909740445184 +1662129909782446080 +1662129909824446976 +1662129909866447872 +1662129909905448704 +1662129909959449856 +1662129910001450752 +1662129910049451776 +1662129910091452672 +1662129910136453632 +1662129910181454592 +1662129910223455488 +1662129910265456384 +1662129910313457408 +1662129910364458496 +1662129910409459456 +1662129910448460288 +1662129910496461312 +1662129910541462272 +1662129910589463296 +1662129910634464256 +1662129910679465216 +1662129910718466048 +1662129910760466944 +1662129910808467968 +1662129910850468864 +1662129910892469760 +1662129910934470656 +1662129910985471744 +1662129911030472704 +1662129911072473600 +1662129911114474496 +1662129911162475520 +1662129911204476416 +1662129911255477504 +1662129911306478592 +1662129911348479488 +1662129911390480384 +1662129911429481216 +1662129911474482176 +1662129911519483136 +1662129911561484032 +1662129911606484992 +1662129911651485952 +1662129911693486848 +1662129911732487680 +1662129911774488576 +1662129911828489728 +1662129911876490752 +1662129911924491776 +1662129911975492864 +1662129912020493824 +1662129912062494720 +1662129912107495680 +1662129912155496704 +1662129912197497600 +1662129912239498496 +1662129912281499392 +1662129912326500352 +1662129912368501248 +1662129912413502208 +1662129912452503040 +1662129912497504000 +1662129912539504896 +1662129912584505856 +1662129912626506752 +1662129912671507712 +1662129912710508544 +1662129912755509504 +1662129912797510400 +1662129912839511296 +1662129912881512192 +1662129912926513152 +1662129912974514176 +1662129913019515136 +1662129913067516160 +1662129913121517312 +1662129913169518336 +1662129913211519232 +1662129913253520128 +1662129913301521152 +1662129913349522176 +1662129913391523072 +1662129913436524032 +1662129913484525056 +1662129913529526016 +1662129913574526976 +1662129913616527872 +1662129913667528960 +1662129913709529856 +1662129913751530752 +1662129913793531648 +1662129913844532736 +1662129913889533696 +1662129913931534592 +1662129913979535616 +1662129914030536704 +1662129914078537728 +1662129914123538688 +1662129914168539648 +1662129914219540736 +1662129914267541760 +1662129914318542848 +1662129914363543808 +1662129914411544832 +1662129914453545728 +1662129914495546624 +1662129914540547584 +1662129914588548608 +1662129914633549568 +1662129914681550592 +1662129914729551616 +1662129914777552640 +1662129914825553664 +1662129914867554560 +1662129914909555456 +1662129914960556544 +1662129915002557440 +1662129915047558400 +1662129915089559296 +1662129915134560256 +1662129915176561152 +1662129915218562048 +1662129915260562944 +1662129915302563840 +1662129915353564928 +1662129915395565824 +1662129915440566784 +1662129915485567744 +1662129915533568768 +1662129915575569664 +1662129915617570560 +1662129915659571456 +1662129915704572416 +1662129915752573440 +1662129915797574400 +1662129915839575296 +1662129915881576192 +1662129915929577216 +1662129915971578112 +1662129916016579072 +1662129916067580160 +1662129916118581248 +1662129916160582144 +1662129916205583104 +1662129916244583936 +1662129916295585024 +1662129916349586176 +1662129916394587136 +1662129916442588160 +1662129916487589120 +1662129916535590144 +1662129916586591232 +1662129916631592192 +1662129916673593088 +1662129916721594112 +1662129916766595072 +1662129916811596032 +1662129916868597248 +1662129916913598208 +1662129916958599168 +1662129917000600064 +1662129917051601152 +1662129917096602112 +1662129917147603200 +1662129917192604160 +1662129917234605056 +1662129917276605952 +1662129917318606848 +1662129917360607744 +1662129917402608640 +1662129917450609664 +1662129917504610816 +1662129917549611776 +1662129917594612736 +1662129917639613696 +1662129917681614592 +1662129917732615680 +1662129917780616704 +1662129917825617664 +1662129917873618688 +1662129917921619712 +1662129917960620544 +1662129918005621504 +1662129918044622336 +1662129918089623296 +1662129918137624320 +1662129918182625280 +1662129918239626496 +1662129918278627328 +1662129918320628224 +1662129918362629120 +1662129918407630080 +1662129918455631104 +1662129918506632192 +1662129918554633216 +1662129918596634112 +1662129918641635072 +1662129918692636160 +1662129918740637184 +1662129918782638080 +1662129918824638976 +1662129918869639936 +1662129918917640960 +1662129918968642048 +1662129919013643008 +1662129919055643904 +1662129919100644864 +1662129919145645824 +1662129919187646720 +1662129919226647552 +1662129919280648704 +1662129919325649664 +1662129919367650560 +1662129919415651584 +1662129919463652608 +1662129919505653504 +1662129919556654592 +1662129919601655552 +1662129919649656576 +1662129919694657536 +1662129919736658432 +1662129919781659392 +1662129919823660288 +1662129919865661184 +1662129919910662144 +1662129919952663040 +1662129919991663872 +1662129920033664768 +1662129920081665792 +1662129920126666752 +1662129920168667648 +1662129920219668736 +1662129920261669632 +1662129920303670528 +1662129920348671488 +1662129920396672512 +1662129920444673536 +1662129920483674368 +1662129920534675456 +1662129920582676480 +1662129920627677440 +1662129920669678336 +1662129920711679232 +1662129920753680128 +1662129920798681088 +1662129920846682112 +1662129920891683072 +1662129920933683968 +1662129920975684864 +1662129921020685824 +1662129921062686720 +1662129921107687680 +1662129921149688576 +1662129921191689472 +1662129921233690368 +1662129921278691328 +1662129921329692416 +1662129921368693248 +1662129921410694144 +1662129921461695232 +1662129921506696192 +1662129921551697152 +1662129921593698048 +1662129921635698944 +1662129921677699840 +1662129921728700928 +1662129921773701888 +1662129921812702720 +1662129921854703616 +1662129921893704448 +1662129921941705472 +1662129921986706432 +1662129922028707328 +1662129922070708224 +1662129922115709184 +1662129922157710080 +1662129922202711040 +1662129922253712128 +1662129922298713088 +1662129922340713984 +1662129922391715072 +1662129922442716160 +1662129922490717184 +1662129922541718272 +1662129922583719168 +1662129922625720064 +1662129922670721024 +1662129922715721984 +1662129922757722880 +1662129922808723968 +1662129922850724864 +1662129922892725760 +1662129922937726720 +1662129922982727680 +1662129923027728640 +1662129923069729536 +1662129923111730432 +1662129923153731328 +1662129923201732352 +1662129923252733440 +1662129923297734400 +1662129923345735424 +1662129923396736512 +1662129923441737472 +1662129923483738368 +1662129923528739328 +1662129923570740224 +1662129923612741120 +1662129923657742080 +1662129923696742912 +1662129923738743808 +1662129923786744832 +1662129923834745856 +1662129923879746816 +1662129923930747904 +1662129923981748992 +1662129924020749824 +1662129924062750720 +1662129924101751552 +1662129924146752512 +1662129924200753664 +1662129924239754496 +1662129924287755520 +1662129924329756416 +1662129924368757248 +1662129924413758208 +1662129924461759232 +1662129924503760128 +1662129924545761024 +1662129924593762048 +1662129924641763072 +1662129924683763968 +1662129924725764864 +1662129924776765952 +1662129924827767040 +1662129924869767936 +1662129924914768896 +1662129924959769856 +1662129925001770752 +1662129925043771648 +1662129925085772544 +1662129925127773440 +1662129925172774400 +1662129925217775360 +1662129925259776256 +1662129925298777088 +1662129925343778048 +1662129925385778944 +1662129925430779904 +1662129925469780736 +1662129925511781632 +1662129925559782656 +1662129925607783680 +1662129925652784640 +1662129925697785600 +1662129925748786688 +1662129925790787584 +1662129925835788544 +1662129925883789568 +1662129925925790464 +1662129925970791424 +1662129926012792320 +1662129926054793216 +1662129926096794112 +1662129926138795008 +1662129926180795904 +1662129926225796864 +1662129926267797760 +1662129926312798720 +1662129926351799552 +1662129926393800448 +1662129926438801408 +1662129926489802496 +1662129926537803520 +1662129926579804416 +1662129926621805312 +1662129926675806464 +1662129926720807424 +1662129926762808320 +1662129926807809280 +1662129926852810240 +1662129926900811264 +1662129926951812352 +1662129926996813312 +1662129927044814336 +1662129927095815424 +1662129927146816512 +1662129927188817408 +1662129927233818368 +1662129927275819264 +1662129927320820224 +1662129927362821120 +1662129927407822080 +1662129927455823104 +1662129927497824000 +1662129927542824960 +1662129927587825920 +1662129927632826880 +1662129927680827904 +1662129927728828928 +1662129927779830016 +1662129927833831168 +1662129927878832128 +1662129927920833024 +1662129927962833920 +1662129928007834880 +1662129928049835776 +1662129928103836928 +1662129928145837824 +1662129928187838720 +1662129928229839616 +1662129928271840512 +1662129928316841472 +1662129928364842496 +1662129928409843456 +1662129928457844480 +1662129928493845248 +1662129928544846336 +1662129928586847232 +1662129928631848192 +1662129928676849152 +1662129928724850176 +1662129928763851008 +1662129928808851968 +1662129928847852800 +1662129928892853760 +1662129928940854784 +1662129928982855680 +1662129929024856576 +1662129929066857472 +1662129929108858368 +1662129929150859264 +1662129929195860224 +1662129929237861120 +1662129929279862016 +1662129929321862912 +1662129929363863808 +1662129929402864640 +1662129929447865600 +1662129929498866688 +1662129929540867584 +1662129929582868480 +1662129929627869440 +1662129929681870592 +1662129929729871616 +1662129929780872704 +1662129929825873664 +1662129929867874560 +1662129929918875648 +1662129929963876608 +1662129930008877568 +1662129930050878464 +1662129930092879360 +1662129930134880256 +1662129930182881280 +1662129930227882240 +1662129930269883136 +1662129930317884160 +1662129930362885120 +1662129930413886208 +1662129930458887168 +1662129930503888128 +1662129930551889152 +1662129930593890048 +1662129930635890944 +1662129930677891840 +1662129930719892736 +1662129930767893760 +1662129930818894848 +1662129930869895936 +1662129930914896896 +1662129930965897984 +1662129931010898944 +1662129931052899840 +1662129931100900864 +1662129931142901760 +1662129931184902656 +1662129931223903488 +1662129931265904384 +1662129931307905280 +1662129931346906112 +1662129931388907008 +1662129931433907968 +1662129931478908928 +1662129931526909952 +1662129931571910912 +1662129931619911936 +1662129931670913024 +1662129931721914112 +1662129931766915072 +1662129931820916224 +1662129931862917120 +1662129931910918144 +1662129931952919040 +1662129931997920000 +1662129932042920960 +1662129932084921856 +1662129932132922880 +1662129932177923840 +1662129932225924864 +1662129932267925760 +1662129932315926784 +1662129932363927808 +1662129932405928704 +1662129932447929600 +1662129932489930496 +1662129932537931520 +1662129932579932416 +1662129932621933312 +1662129932666934272 +1662129932711935232 +1662129932756936192 +1662129932807937280 +1662129932846938112 +1662129932885938944 +1662129932933939968 +1662129932984941056 +1662129933029942016 +1662129933068942848 +1662129933113943808 +1662129933155944704 +1662129933203945728 +1662129933245946624 +1662129933284947456 +1662129933326948352 +1662129933371949312 +1662129933416950272 +1662129933464951296 +1662129933506952192 +1662129933551953152 +1662129933593954048 +1662129933635954944 +1662129933686956032 +1662129933731956992 +1662129933773957888 +1662129933821958912 +1662129933863959808 +1662129933908960768 +1662129933956961792 +1662129933998962688 +1662129934040963584 +1662129934085964544 +1662129934130965504 +1662129934181966592 +1662129934226967552 +1662129934268968448 +1662129934313969408 +1662129934364970496 +1662129934409971456 +1662129934451972352 +1662129934508973568 +1662129934556974592 +1662129934604975616 +1662129934646976512 +1662129934688977408 +1662129934736978432 +1662129934778979328 +1662129934820980224 +1662129934862981120 +1662129934904982016 +1662129934946982912 +1662129934988983808 +1662129935033984768 +1662129935078985728 +1662129935120986624 +1662129935162987520 +1662129935204988416 +1662129935246989312 +1662129935294990336 +1662129935348991488 +1662129935399992576 +1662129935441993472 +1662129935483994368 +1662129935528995328 +1662129935570996224 +1662129935615997184 +1662129935657998080 +1662129935696998912 +1662129935738999808 +1662129935781000704 +1662129935826001664 +1662129935868002560 +1662129935910003456 +1662129935955004416 +1662129936000005376 +1662129936048006400 +1662129936099007488 +1662129936141008384 +1662129936192009472 +1662129936240010496 +1662129936285011456 +1662129936327012352 +1662129936369013248 +1662129936414014208 +1662129936471015424 +1662129936513016320 +1662129936564017408 +1662129936609018368 +1662129936654019328 +1662129936696020224 +1662129936738021120 +1662129936783022080 +1662129936825022976 +1662129936867023872 +1662129936912024832 +1662129936951025664 +1662129936993026560 +1662129937035027456 +1662129937086028544 +1662129937131029504 +1662129937176030464 +1662129937218031360 +1662129937260032256 +1662129937305033216 +1662129937353034240 +1662129937395035136 +1662129937437036032 +1662129937479036928 +1662129937524037888 +1662129937569038848 +1662129937608039680 +1662129937653040640 +1662129937701041664 +1662129937752042752 +1662129937797043712 +1662129937839044608 +1662129937881045504 +1662129937923046400 +1662129937974047488 +1662129938019048448 +1662129938073049600 +1662129938118050560 +1662129938169051648 +1662129938211052544 +1662129938259053568 +1662129938304054528 +1662129938349055488 +1662129938391056384 +1662129938436057344 +1662129938484058368 +1662129938532059392 +1662129938574060288 +1662129938619061248 +1662129938661062144 +1662129938703063040 +1662129938745063936 +1662129938787064832 +1662129938832065792 +1662129938871066624 +1662129938913067520 +1662129938961068544 +1662129939006069504 +1662129939048070400 +1662129939096071424 +1662129939135072256 +1662129939186073344 +1662129939231074304 +1662129939273075200 +1662129939315076096 +1662129939360077056 +1662129939408078080 +1662129939450078976 +1662129939492079872 +1662129939534080768 +1662129939579081728 +1662129939621082624 +1662129939669083648 +1662129939714084608 +1662129939759085568 +1662129939804086528 +1662129939843087360 +1662129939888088320 +1662129939933089280 +1662129939975090176 +1662129940017091072 +1662129940062092032 +1662129940107092992 +1662129940149093888 +1662129940191094784 +1662129940236095744 +1662129940275096576 +1662129940317097472 +1662129940359098368 +1662129940404099328 +1662129940452100352 +1662129940500101376 +1662129940539102208 +1662129940581103104 +1662129940629104128 +1662129940671105024 +1662129940716105984 +1662129940764107008 +1662129940812108032 +1662129940854108928 +1662129940896109824 +1662129940938110720 +1662129940980111616 +1662129941019112448 +1662129941061113344 +1662129941103114240 +1662129941148115200 +1662129941187116032 +1662129941235117056 +1662129941277117952 +1662129941322118912 +1662129941364119808 +1662129941406120704 +1662129941448121600 +1662129941496122624 +1662129941541123584 +1662129941586124544 +1662129941628125440 +1662129941685126656 +1662129941733127680 +1662129941778128640 +1662129941823129600 +1662129941865130496 +1662129941910131456 +1662129941967132672 +1662129942012133632 +1662129942051134464 +1662129942093135360 +1662129942135136256 +1662129942174137088 +1662129942216137984 +1662129942258138880 +1662129942297139712 +1662129942339140608 +1662129942390141696 +1662129942429142528 +1662129942471143424 +1662129942513144320 +1662129942558145280 +1662129942600146176 +1662129942639147008 +1662129942681147904 +1662129942723148800 +1662129942771149824 +1662129942810150656 +1662129942864151808 +1662129942906152704 +1662129942957153792 +1662129943005154816 +1662129943047155712 +1662129943086156544 +1662129943128157440 +1662129943167158272 +1662129943215159296 +1662129943257160192 +1662129943299161088 +1662129943344162048 +1662129943395163136 +1662129943440164096 +1662129943482164992 +1662129943527165952 +1662129943578167040 +1662129943623168000 +1662129943671169024 +1662129943710169856 +1662129943752170752 +1662129943797171712 +1662129943845172736 +1662129943893173760 +1662129943935174656 +1662129943977175552 +1662129944022176512 +1662129944064177408 +1662129944109178368 +1662129944151179264 +1662129944199180288 +1662129944247181312 +1662129944295182336 +1662129944337183232 +1662129944379184128 +1662129944421185024 +1662129944466185984 +1662129944511186944 +1662129944553187840 +1662129944595188736 +1662129944643189760 +1662129944685190656 +1662129944730191616 +1662129944772192512 +1662129944814193408 +1662129944859194368 +1662129944904195328 +1662129944946196224 +1662129944997197312 +1662129945039198208 +1662129945087199232 +1662129945135200256 +1662129945177201152 +1662129945222202112 +1662129945273203200 +1662129945324204288 +1662129945375205376 +1662129945426206464 +1662129945468207360 +1662129945510208256 +1662129945558209280 +1662129945609210368 +1662129945654211328 +1662129945696212224 +1662129945738213120 +1662129945783214080 +1662129945825214976 +1662129945873216000 +1662129945927217152 +1662129945966217984 +1662129946014219008 +1662129946059219968 +1662129946107220992 +1662129946155222016 +1662129946197222912 +1662129946242223872 +1662129946290224896 +1662129946332225792 +1662129946377226752 +1662129946425227776 +1662129946479228928 +1662129946521229824 +1662129946563230720 +1662129946608231680 +1662129946650232576 +1662129946692233472 +1662129946737234432 +1662129946782235392 +1662129946824236288 +1662129946866237184 +1662129946911238144 +1662129946956239104 +1662129946998240000 +1662129947040240896 +1662129947082241792 +1662129947124242688 +1662129947169243648 +1662129947211244544 +1662129947250245376 +1662129947292246272 +1662129947346247424 +1662129947391248384 +1662129947433249280 +1662129947478250240 +1662129947526251264 +1662129947574252288 +1662129947619253248 +1662129947667254272 +1662129947709255168 +1662129947754256128 +1662129947796257024 +1662129947841257984 +1662129947895259136 +1662129947940260096 +1662129947982260992 +1662129948033262080 +1662129948084263168 +1662129948129264128 +1662129948174265088 +1662129948219266048 +1662129948261266944 +1662129948312268032 +1662129948360269056 +1662129948402269952 +1662129948441270784 +1662129948486271744 +1662129948528272640 +1662129948570273536 +1662129948618274560 +1662129948660275456 +1662129948702276352 +1662129948750277376 +1662129948798278400 +1662129948840279296 +1662129948885280256 +1662129948927281152 +1662129948969282048 +1662129949011282944 +1662129949056283904 +1662129949095284736 +1662129949137285632 +1662129949185286656 +1662129949230287616 +1662129949272288512 +1662129949314289408 +1662129949356290304 +1662129949401291264 +1662129949443292160 +1662129949488293120 +1662129949533294080 +1662129949575294976 +1662129949617295872 +1662129949668296960 +1662129949710297856 +1662129949758298880 +1662129949800299776 +1662129949842300672 +1662129949884301568 +1662129949929302528 +1662129949977303552 +1662129950022304512 +1662129950067305472 +1662129950106306304 +1662129950148307200 +1662129950193308160 +1662129950235309056 +1662129950283310080 +1662129950328311040 +1662129950370311936 +1662129950415312896 +1662129950463313920 +1662129950505314816 +1662129950559315968 +1662129950601316864 +1662129950661318144 +1662129950706319104 +1662129950763320320 +1662129950808321280 +1662129950850322176 +1662129950892323072 +1662129950931323904 +1662129950982324992 +1662129951027325952 +1662129951069326848 +1662129951111327744 +1662129951156328704 +1662129951198329600 +1662129951240330496 +1662129951291331584 +1662129951333332480 +1662129951384333568 +1662129951429334528 +1662129951471335424 +1662129951516336384 +1662129951561337344 +1662129951606338304 +1662129951648339200 +1662129951693340160 +1662129951735341056 +1662129951780342016 +1662129951825342976 +1662129951867343872 +1662129951909344768 +1662129951954345728 +1662129951996346624 +1662129952044347648 +1662129952086348544 +1662129952128349440 +1662129952179350528 +1662129952221351424 +1662129952263352320 +1662129952305353216 +1662129952350354176 +1662129952386354944 +1662129952434355968 +1662129952479356928 +1662129952524357888 +1662129952572358912 +1662129952617359872 +1662129952665360896 +1662129952707361792 +1662129952752362752 +1662129952797363712 +1662129952842364672 +1662129952887365632 +1662129952929366528 +1662129952971367424 +1662129953016368384 +1662129953058369280 +1662129953106370304 +1662129953154371328 +1662129953199372288 +1662129953247373312 +1662129953298374400 +1662129953340375296 +1662129953394376448 +1662129953436377344 +1662129953475378176 +1662129953514379008 +1662129953568380160 +1662129953613381120 +1662129953655382016 +1662129953700382976 +1662129953739383808 +1662129953781384704 +1662129953826385664 +1662129953865386496 +1662129953907387392 +1662129953955388416 +1662129954000389376 +1662129954051390464 +1662129954093391360 +1662129954138392320 +1662129954183393280 +1662129954225394176 +1662129954267395072 +1662129954306395904 +1662129954354396928 +1662129954399397888 +1662129954441398784 +1662129954489399808 +1662129954531400704 +1662129954579401728 +1662129954630402816 +1662129954672403712 +1662129954714404608 +1662129954756405504 +1662129954798406400 +1662129954840407296 +1662129954888408320 +1662129954930409216 +1662129954975410176 +1662129955023411200 +1662129955071412224 +1662129955116413184 +1662129955158414080 +1662129955206415104 +1662129955254416128 +1662129955299417088 +1662129955344418048 +1662129955386418944 +1662129955428419840 +1662129955473420800 +1662129955518421760 +1662129955560422656 +1662129955608423680 +1662129955659424768 +1662129955701425664 +1662129955746426624 +1662129955800427776 +1662129955845428736 +1662129955887429632 +1662129955929430528 +1662129955968431360 +1662129956010432256 +1662129956052433152 +1662129956094434048 +1662129956139435008 +1662129956184435968 +1662129956226436864 +1662129956268437760 +1662129956313438720 +1662129956358439680 +1662129956406440704 +1662129956445441536 +1662129956490442496 +1662129956535443456 +1662129956583444480 +1662129956634445568 +1662129956676446464 +1662129956718447360 +1662129956760448256 +1662129956802449152 +1662129956850450176 +1662129956889451008 +1662129956931451904 +1662129956973452800 +1662129957015453696 +1662129957057454592 +1662129957102455552 +1662129957150456576 +1662129957198457600 +1662129957240458496 +1662129957288459520 +1662129957330460416 +1662129957378461440 +1662129957420462336 +1662129957462463232 +1662129957510464256 +1662129957555465216 +1662129957597466112 +1662129957642467072 +1662129957687468032 +1662129957729468928 +1662129957777469952 +1662129957825470976 +1662129957867471872 +1662129957912472832 +1662129957954473728 +1662129957999474688 +1662129958044475648 +1662129958089476608 +1662129958131477504 +1662129958191478784 +1662129958233479680 +1662129958278480640 +1662129958320481536 +1662129958362482432 +1662129958407483392 +1662129958452484352 +1662129958500485376 +1662129958545486336 +1662129958581487104 +1662129958626488064 +1662129958668488960 +1662129958710489856 +1662129958752490752 +1662129958797491712 +1662129958842492672 +1662129958884493568 +1662129958929494528 +1662129958971495424 +1662129959013496320 +1662129959055497216 +1662129959100498176 +1662129959142499072 +1662129959187500032 +1662129959229500928 +1662129959271501824 +1662129959313502720 +1662129959355503616 +1662129959397504512 +1662129959448505600 +1662129959499506688 +1662129959544507648 +1662129959589508608 +1662129959634509568 +1662129959679510528 +1662129959721511424 +1662129959766512384 +1662129959817513472 +1662129959859514368 +1662129959910515456 +1662129959955516416 +1662129959997517312 +1662129960039518208 +1662129960081519104 +1662129960123520000 +1662129960174521088 +1662129960219522048 +1662129960267523072 +1662129960309523968 +1662129960363525120 +1662129960405526016 +1662129960447526912 +1662129960489527808 +1662129960531528704 +1662129960576529664 +1662129960624530688 +1662129960666531584 +1662129960708532480 +1662129960750533376 +1662129960792534272 +1662129960831535104 +1662129960876536064 +1662129960921537024 +1662129960966537984 +1662129961005538816 +1662129961047539712 +1662129961092540672 +1662129961134541568 +1662129961179542528 +1662129961221543424 +1662129961263544320 +1662129961305545216 +1662129961350546176 +1662129961401547264 +1662129961443548160 +1662129961482548992 +1662129961524549888 +1662129961572550912 +1662129961614551808 +1662129961656552704 +1662129961698553600 +1662129961740554496 +1662129961779555328 +1662129961818556160 +1662129961860557056 +1662129961908558080 +1662129961953559040 +1662129961995559936 +1662129962037560832 +1662129962082561792 +1662129962124562688 +1662129962163563520 +1662129962205564416 +1662129962247565312 +1662129962289566208 +1662129962334567168 +1662129962385568256 +1662129962445569536 +1662129962496570624 +1662129962538571520 +1662129962583572480 +1662129962628573440 +1662129962676574464 +1662129962715575296 +1662129962757576192 +1662129962802577152 +1662129962847578112 +1662129962892579072 +1662129962943580160 +1662129962988581120 +1662129963039582208 +1662129963081583104 +1662129963126584064 +1662129963174585088 +1662129963216585984 +1662129963264587008 +1662129963306587904 +1662129963348588800 +1662129963390589696 +1662129963435590656 +1662129963477591552 +1662129963519592448 +1662129963561593344 +1662129963603594240 +1662129963648595200 +1662129963687596032 +1662129963729596928 +1662129963771597824 +1662129963822598912 +1662129963867599872 +1662129963909600768 +1662129963954601728 +1662129964005602816 +1662129964047603712 +1662129964101604864 +1662129964143605760 +1662129964188606720 +1662129964230607616 +1662129964275608576 +1662129964317609472 +1662129964359610368 +1662129964401611264 +1662129964446612224 +1662129964497613312 +1662129964539614208 +1662129964581615104 +1662129964626616064 +1662129964671617024 +1662129964713617920 +1662129964755618816 +1662129964800619776 +1662129964842620672 +1662129964887621632 +1662129964929622528 +1662129964977623552 +1662129965019624448 +1662129965067625472 +1662129965112626432 +1662129965157627392 +1662129965199628288 +1662129965253629440 +1662129965295630336 +1662129965334631168 +1662129965382632192 +1662129965427633152 +1662129965472634112 +1662129965514635008 +1662129965559635968 +1662129965604636928 +1662129965649637888 +1662129965694638848 +1662129965736639744 +1662129965784640768 +1662129965829641728 +1662129965880642816 +1662129965922643712 +1662129965964644608 +1662129966012645632 +1662129966054646528 +1662129966093647360 +1662129966138648320 +1662129966183649280 +1662129966228650240 +1662129966273651200 +1662129966324652288 +1662129966375653376 +1662129966420654336 +1662129966471655424 +1662129966516656384 +1662129966561657344 +1662129966606658304 +1662129966651659264 +1662129966696660224 +1662129966738661120 +1662129966780662016 +1662129966828663040 +1662129966870663936 +1662129966912664832 +1662129966954665728 +1662129966996666624 +1662129967041667584 +1662129967086668544 +1662129967128669440 +1662129967170670336 +1662129967209671168 +1662129967257672192 +1662129967296673024 +1662129967338673920 +1662129967386674944 +1662129967425675776 +1662129967467676672 +1662129967518677760 +1662129967560678656 +1662129967602679552 +1662129967647680512 +1662129967689681408 +1662129967731682304 +1662129967773683200 +1662129967818684160 +1662129967860685056 +1662129967905686016 +1662129967947686912 +1662129967992687872 +1662129968037688832 +1662129968088689920 +1662129968127690752 +1662129968172691712 +1662129968220692736 +1662129968271693824 +1662129968313694720 +1662129968355695616 +1662129968394696448 +1662129968433697280 +1662129968475698176 +1662129968517699072 +1662129968571700224 +1662129968622701312 +1662129968673702400 +1662129968715703296 +1662129968757704192 +1662129968805705216 +1662129968850706176 +1662129968895707136 +1662129968937708032 +1662129968979708928 +1662129969021709824 +1662129969063710720 +1662129969105711616 +1662129969162712832 +1662129969201713664 +1662129969252714752 +1662129969297715712 +1662129969339716608 +1662129969381717504 +1662129969423718400 +1662129969465719296 +1662129969513720320 +1662129969555721216 +1662129969600722176 +1662129969648723200 +1662129969690724096 +1662129969738725120 +1662129969783726080 +1662129969825726976 +1662129969870727936 +1662129969918728960 +1662129969966729984 +1662129970008730880 +1662129970059731968 +1662129970104732928 +1662129970149733888 +1662129970194734848 +1662129970242735872 +1662129970284736768 +1662129970335737856 +1662129970377738752 +1662129970419739648 +1662129970461740544 +1662129970503741440 +1662129970545742336 +1662129970590743296 +1662129970635744256 +1662129970677745152 +1662129970719746048 +1662129970764747008 +1662129970806747904 +1662129970851748864 +1662129970896749824 +1662129970941750784 +1662129970995751936 +1662129971043752960 +1662129971088753920 +1662129971136754944 +1662129971178755840 +1662129971220756736 +1662129971265757696 +1662129971313758720 +1662129971355759616 +1662129971403760640 +1662129971445761536 +1662129971496762624 +1662129971538763520 +1662129971583764480 +1662129971643765760 +1662129971682766592 +1662129971724767488 +1662129971769768448 +1662129971811769344 +1662129971859770368 +1662129971901771264 +1662129971943772160 +1662129971982772992 +1662129972024773888 +1662129972066774784 +1662129972108775680 +1662129972153776640 +1662129972195777536 +1662129972240778496 +1662129972285779456 +1662129972327780352 +1662129972369781248 +1662129972414782208 +1662129972456783104 +1662129972501784064 +1662129972540784896 +1662129972582785792 +1662129972627786752 +1662129972669787648 +1662129972717788672 +1662129972762789632 +1662129972804790528 +1662129972852791552 +1662129972894792448 +1662129972939793408 +1662129972981794304 +1662129973020795136 +1662129973062796032 +1662129973113797120 +1662129973155798016 +1662129973197798912 +1662129973239799808 +1662129973281800704 +1662129973323801600 +1662129973368802560 +1662129973416803584 +1662129973461804544 +1662129973506805504 +1662129973548806400 +1662129973590807296 +1662129973632808192 +1662129973674809088 +1662129973722810112 +1662129973773811200 +1662129973818812160 +1662129973866813184 +1662129973911814144 +1662129973953815040 +1662129973998816000 +1662129974040816896 +1662129974082817792 +1662129974124818688 +1662129974169819648 +1662129974211820544 +1662129974253821440 +1662129974295822336 +1662129974349823488 +1662129974391824384 +1662129974436825344 +1662129974481826304 +1662129974523827200 +1662129974580828416 +1662129974622829312 +1662129974667830272 +1662129974709831168 +1662129974754832128 +1662129974799833088 +1662129974844834048 +1662129974886834944 +1662129974940836096 +1662129974985837056 +1662129975027837952 +1662129975072838912 +1662129975114839808 +1662129975156840704 +1662129975201841664 +1662129975249842688 +1662129975291843584 +1662129975336844544 +1662129975384845568 +1662129975426846464 +1662129975471847424 +1662129975510848256 +1662129975561849344 +1662129975606850304 +1662129975657851392 +1662129975702852352 +1662129975747853312 +1662129975789854208 +1662129975834855168 +1662129975873856000 +1662129975918856960 +1662129975972858112 +1662129976017859072 +1662129976065860096 +1662129976110861056 +1662129976152861952 +1662129976197862912 +1662129976245863936 +1662129976287864832 +1662129976329865728 +1662129976377866752 +1662129976422867712 +1662129976473868800 +1662129976512869632 +1662129976557870592 +1662129976602871552 +1662129976644872448 +1662129976689873408 +1662129976731874304 +1662129976770875136 +1662129976812876032 +1662129976857876992 +1662129976896877824 +1662129976938878720 +1662129976983879680 +1662129977025880576 +1662129977070881536 +1662129977115882496 +1662129977154883328 +1662129977199884288 +1662129977250885376 +1662129977295886336 +1662129977334887168 +1662129977373888000 +1662129977415888896 +1662129977457889792 +1662129977499890688 +1662129977541891584 +1662129977583892480 +1662129977625893376 +1662129977670894336 +1662129977715895296 +1662129977757896192 +1662129977799897088 +1662129977844898048 +1662129977886898944 +1662129977937900032 +1662129977982900992 +1662129978030902016 +1662129978072902912 +1662129978111903744 +1662129978153904640 +1662129978201905664 +1662129978249906688 +1662129978297907712 +1662129978339908608 +1662129978381909504 +1662129978426910464 +1662129978477911552 +1662129978525912576 +1662129978567913472 +1662129978606914304 +1662129978648915200 +1662129978690916096 +1662129978732916992 +1662129978777917952 +1662129978822918912 +1662129978870919936 +1662129978921921024 +1662129978966921984 +1662129979014923008 +1662129979062924032 +1662129979104924928 +1662129979146925824 +1662129979188926720 +1662129979230927616 +1662129979272928512 +1662129979314929408 +1662129979353930240 +1662129979395931136 +1662129979437932032 +1662129979476932864 +1662129979521933824 +1662129979566934784 +1662129979611935744 +1662129979656936704 +1662129979704937728 +1662129979746938624 +1662129979788939520 +1662129979836940544 +1662129979875941376 +1662129979917942272 +1662129979956943104 +1662129980007944192 +1662129980052945152 +1662129980094946048 +1662129980139947008 +1662129980190948096 +1662129980232948992 +1662129980274949888 +1662129980316950784 +1662129980358951680 +1662129980400952576 +1662129980442953472 +1662129980490954496 +1662129980535955456 +1662129980577956352 +1662129980616957184 +1662129980661958144 +1662129980703959040 +1662129980745959936 +1662129980793960960 +1662129980841961984 +1662129980883962880 +1662129980928963840 +1662129980976964864 +1662129981027965952 +1662129981072966912 +1662129981117967872 +1662129981159968768 +1662129981201969664 +1662129981246970624 +1662129981285971456 +1662129981327972352 +1662129981378973440 +1662129981423974400 +1662129981462975232 +1662129981501976064 +1662129981543976960 +1662129981582977792 +1662129981624978688 +1662129981669979648 +1662129981711980544 +1662129981750981376 +1662129981792982272 +1662129981834983168 +1662129981876984064 +1662129981933985280 +1662129981975986176 +1662129982017987072 +1662129982059987968 +1662129982104988928 +1662129982146989824 +1662129982185990656 +1662129982230991616 +1662129982272992512 +1662129982314993408 +1662129982356994304 +1662129982401995264 +1662129982452996352 +1662129982494997248 +1662129982533998080 +1662129982575998976 +1662129982620999936 +1662129982669000960 +1662129982720002048 +1662129982774003200 +1662129982816004096 +1662129982858004992 +1662129982900005888 +1662129982942006784 +1662129982987007744 +1662129983029008640 +1662129983071009536 +1662129983131010816 +1662129983173011712 +1662129983221012736 +1662129983269013760 +1662129983311014656 +1662129983353015552 +1662129983398016512 +1662129983443017472 +1662129983488018432 +1662129983533019392 +1662129983575020288 +1662129983620021248 +1662129983668022272 +1662129983710023168 +1662129983752024064 +1662129983791024896 +1662129983833025792 +1662129983872026624 +1662129983917027584 +1662129983959028480 +1662129984013029632 +1662129984058030592 +1662129984100031488 +1662129984142032384 +1662129984181033216 +1662129984226034176 +1662129984274035200 +1662129984319036160 +1662129984367037184 +1662129984409038080 +1662129984457039104 +1662129984496039936 +1662129984541040896 +1662129984583041792 +1662129984628042752 +1662129984670043648 +1662129984724044800 +1662129984766045696 +1662129984811046656 +1662129984850047488 +1662129984892048384 +1662129984937049344 +1662129984979050240 +1662129985024051200 +1662129985069052160 +1662129985108052992 +1662129985150053888 +1662129985195054848 +1662129985243055872 +1662129985297057024 +1662129985342057984 +1662129985387058944 +1662129985432059904 +1662129985480060928 +1662129985525061888 +1662129985567062784 +1662129985615063808 +1662129985660064768 +1662129985711065856 +1662129985753066752 +1662129985792067584 +1662129985837068544 +1662129985879069440 +1662129985927070464 +1662129985975071488 +1662129986017072384 +1662129986065073408 +1662129986104074240 +1662129986149075200 +1662129986194076160 +1662129986233076992 +1662129986275077888 +1662129986320078848 +1662129986362079744 +1662129986404080640 +1662129986446081536 +1662129986488082432 +1662129986527083264 +1662129986569084160 +1662129986614085120 +1662129986665086208 +1662129986707087104 +1662129986755088128 +1662129986800089088 +1662129986842089984 +1662129986881090816 +1662129986923091712 +1662129986968092672 +1662129987013093632 +1662129987055094528 +1662129987097095424 +1662129987139096320 +1662129987178097152 +1662129987220098048 +1662129987268099072 +1662129987310099968 +1662129987352100864 +1662129987394101760 +1662129987439102720 +1662129987481103616 +1662129987529104640 +1662129987574105600 +1662129987622106624 +1662129987664107520 +1662129987706108416 +1662129987745109248 +1662129987790110208 +1662129987835111168 +1662129987880112128 +1662129987922113024 +1662129987961113856 +1662129988006114816 +1662129988048115712 +1662129988090116608 +1662129988132117504 +1662129988180118528 +1662129988225119488 +1662129988267120384 +1662129988309121280 +1662129988348122112 +1662129988390123008 +1662129988432123904 +1662129988474124800 +1662129988513125632 +1662129988561126656 +1662129988600127488 +1662129988648128512 +1662129988696129536 +1662129988738130432 +1662129988780131328 +1662129988831132416 +1662129988873133312 +1662129988921134336 +1662129988966135296 +1662129989011136256 +1662129989053137152 +1662129989092137984 +1662129989134138880 +1662129989179139840 +1662129989227140864 +1662129989269141760 +1662129989311142656 +1662129989356143616 +1662129989401144576 +1662129989443145472 +1662129989491146496 +1662129989533147392 +1662129989587148544 +1662129989629149440 +1662129989683150592 +1662129989725151488 +1662129989770152448 +1662129989812153344 +1662129989857154304 +1662129989899155200 +1662129989944156160 +1662129989986157056 +1662129990037158144 +1662129990079159040 +1662129990118159872 +1662129990160160768 +1662129990208161792 +1662129990253162752 +1662129990298163712 +1662129990334164480 +1662129990379165440 +1662129990421166336 +1662129990466167296 +1662129990508168192 +1662129990550169088 +1662129990601170176 +1662129990646171136 +1662129990691172096 +1662129990736173056 +1662129990781174016 +1662129990823174912 +1662129990865175808 +1662129990907176704 +1662129990949177600 +1662129990988178432 +1662129991027179264 +1662129991072180224 +1662129991111181056 +1662129991150181888 +1662129991192182784 +1662129991234183680 +1662129991276184576 +1662129991321185536 +1662129991366186496 +1662129991420187648 +1662129991462188544 +1662129991501189376 +1662129991540190208 +1662129991579191040 +1662129991621191936 +1662129991663192832 +1662129991708193792 +1662129991750194688 +1662129991792195584 +1662129991834196480 +1662129991882197504 +1662129991924198400 +1662129991966199296 +1662129992008200192 +1662129992047201024 +1662129992089201920 +1662129992131202816 +1662129992170203648 +1662129992209204480 +1662129992251205376 +1662129992290206208 +1662129992335207168 +1662129992380208128 +1662129992422209024 +1662129992464209920 +1662129992506210816 +1662129992551211776 +1662129992599212800 +1662129992641213696 +1662129992686214656 +1662129992731215616 +1662129992773216512 +1662129992821217536 +1662129992860218368 +1662129992905219328 +1662129992947220224 +1662129992989221120 +1662129993031222016 +1662129993073222912 +1662129993115223808 +1662129993163224832 +1662129993208225792 +1662129993250226688 +1662129993298227712 +1662129993355228928 +1662129993397229824 +1662129993439230720 +1662129993481231616 +1662129993523232512 +1662129993562233344 +1662129993607234304 +1662129993649235200 +1662129993691236096 +1662129993733236992 +1662129993775237888 +1662129993826238976 +1662129993877240064 +1662129993922241024 +1662129993976242176 +1662129994027243264 +1662129994072244224 +1662129994114245120 +1662129994156246016 +1662129994198246912 +1662129994243247872 +1662129994285248768 +1662129994327249664 +1662129994372250624 +1662129994414251520 +1662129994456252416 +1662129994498253312 +1662129994537254144 +1662129994579255040 +1662129994627256064 +1662129994672257024 +1662129994717257984 +1662129994759258880 +1662129994798259712 +1662129994843260672 +1662129994882261504 +1662129994924262400 +1662129994966263296 +1662129995008264192 +1662129995056265216 +1662129995104266240 +1662129995155267328 +1662129995197268224 +1662129995242269184 +1662129995287270144 +1662129995329271040 +1662129995371271936 +1662129995419272960 +1662129995458273792 +1662129995500274688 +1662129995545275648 +1662129995593276672 +1662129995635277568 +1662129995677278464 +1662129995719279360 +1662129995761280256 +1662129995803281152 +1662129995845282048 +1662129995887282944 +1662129995932283904 +1662129995983284992 +1662129996025285888 +1662129996067286784 +1662129996115287808 +1662129996157288704 +1662129996202289664 +1662129996244290560 +1662129996295291648 +1662129996340292608 +1662129996397293824 +1662129996442294784 +1662129996493295872 +1662129996538296832 +1662129996580297728 +1662129996622298624 +1662129996667299584 +1662129996712300544 +1662129996754301440 +1662129996796302336 +1662129996838303232 +1662129996880304128 +1662129996928305152 +1662129996970306048 +1662129997009306880 +1662129997054307840 +1662129997102308864 +1662129997147309824 +1662129997192310784 +1662129997234311680 +1662129997279312640 +1662129997321313536 +1662129997363314432 +1662129997405315328 +1662129997447316224 +1662129997489317120 +1662129997531318016 +1662129997573318912 +1662129997615319808 +1662129997657320704 +1662129997702321664 +1662129997741322496 +1662129997783323392 +1662129997828324352 +1662129997870325248 +1662129997912326144 +1662129997954327040 +1662129997999328000 +1662129998050329088 +1662129998098330112 +1662129998140331008 +1662129998188332032 +1662129998230332928 +1662129998275333888 +1662129998320334848 +1662129998365335808 +1662129998407336704 +1662129998446337536 +1662129998491338496 +1662129998542339584 +1662129998584340480 +1662129998626341376 +1662129998668342272 +1662129998713343232 +1662129998764344320 +1662129998806345216 +1662129998845346048 +1662129998887346944 +1662129998926347776 +1662129998968348672 +1662129999010349568 +1662129999052350464 +1662129999094351360 +1662129999139352320 +1662129999181353216 +1662129999226354176 +1662129999274355200 +1662129999316356096 +1662129999358356992 +1662129999406358016 +1662129999448358912 +1662129999496359936 +1662129999538360832 +1662129999577361664 +1662129999616362496 +1662129999658363392 +1662129999697364224 +1662129999739365120 +1662129999778365952 +1662129999817366784 +1662129999874368000 +1662129999916368896 +1662129999958369792 +1662130000012370944 +1662130000057371904 +1662130000099372800 +1662130000147373824 +1662130000189374720 +1662130000240375808 +1662130000282376704 +1662130000327377664 +1662130000375378688 +1662130000420379648 +1662130000462380544 +1662130000504381440 +1662130000546382336 +1662130000588383232 +1662130000630384128 +1662130000672385024 +1662130000714385920 +1662130000762386944 +1662130000807387904 +1662130000855388928 +1662130000903389952 +1662130000948390912 +1662130000987391744 +1662130001029392640 +1662130001071393536 +1662130001113394432 +1662130001161395456 +1662130001203396352 +1662130001245397248 +1662130001299398400 +1662130001341399296 +1662130001389400320 +1662130001428401152 +1662130001479402240 +1662130001524403200 +1662130001572404224 +1662130001620405248 +1662130001662406144 +1662130001704407040 +1662130001746407936 +1662130001788408832 +1662130001830409728 +1662130001872410624 +1662130001911411456 +1662130001953412352 +1662130001995413248 +1662130002037414144 +1662130002079415040 +1662130002124416000 +1662130002169416960 +1662130002214417920 +1662130002256418816 +1662130002301419776 +1662130002349420800 +1662130002394421760 +1662130002436422656 +1662130002481423616 +1662130002523424512 +1662130002568425472 +1662130002610426368 +1662130002652427264 +1662130002697428224 +1662130002739429120 +1662130002781430016 +1662130002826430976 +1662130002874432000 +1662130002916432896 +1662130002955433728 +1662130003000434688 +1662130003039435520 +1662130003081436416 +1662130003126437376 +1662130003171438336 +1662130003213439232 +1662130003255440128 +1662130003297441024 +1662130003339441920 +1662130003381442816 +1662130003423443712 +1662130003465444608 +1662130003507445504 +1662130003549446400 +1662130003591447296 +1662130003639448320 +1662130003681449216 +1662130003723450112 +1662130003768451072 +1662130003813452032 +1662130003855452928 +1662130003900453888 +1662130003948454912 +1662130003993455872 +1662130004035456768 +1662130004077457664 +1662130004122458624 +1662130004164459520 +1662130004209460480 +1662130004257461504 +1662130004302462464 +1662130004344463360 +1662130004398464512 +1662130004437465344 +1662130004485466368 +1662130004530467328 +1662130004578468352 +1662130004626469376 +1662130004665470208 +1662130004710471168 +1662130004749472000 +1662130004791472896 +1662130004833473792 +1662130004875474688 +1662130004917475584 +1662130004959476480 +1662130005013477632 +1662130005058478592 +1662130005103479552 +1662130005145480448 +1662130005184481280 +1662130005223482112 +1662130005265483008 +1662130005319484160 +1662130005361485056 +1662130005406486016 +1662130005448486912 +1662130005496487936 +1662130005538488832 +1662130005580489728 +1662130005628490752 +1662130005679491840 +1662130005721492736 +1662130005763493632 +1662130005817494784 +1662130005859495680 +1662130005901496576 +1662130005952497664 +1662130005991498496 +1662130006030499328 +1662130006075500288 +1662130006126501376 +1662130006171502336 +1662130006213503232 +1662130006261504256 +1662130006303505152 +1662130006342505984 +1662130006390507008 +1662130006432507904 +1662130006480508928 +1662130006522509824 +1662130006573510912 +1662130006615511808 +1662130006660512768 +1662130006702513664 +1662130006744514560 +1662130006786515456 +1662130006828516352 +1662130006867517184 +1662130006912518144 +1662130006960519168 +1662130006999520000 +1662130007041520896 +1662130007083521792 +1662130007128522752 +1662130007179523840 +1662130007227524864 +1662130007272525824 +1662130007317526784 +1662130007356527616 +1662130007398528512 +1662130007440529408 +1662130007485530368 +1662130007527531264 +1662130007572532224 +1662130007614533120 +1662130007665534208 +1662130007707535104 +1662130007749536000 +1662130007800537088 +1662130007848538112 +1662130007893539072 +1662130007938540032 +1662130007977540864 +1662130008022541824 +1662130008064542720 +1662130008115543808 +1662130008160544768 +1662130008208545792 +1662130008253546752 +1662130008295547648 +1662130008340548608 +1662130008385549568 +1662130008424550400 +1662130008466551296 +1662130008508552192 +1662130008547553024 +1662130008589553920 +1662130008634554880 +1662130008676555776 +1662130008724556800 +1662130008763557632 +1662130008805558528 +1662130008847559424 +1662130008895560448 +1662130008937561344 +1662130008982562304 +1662130009024563200 +1662130009063564032 +1662130009111565056 +1662130009153565952 +1662130009198566912 +1662130009240567808 +1662130009282568704 +1662130009327569664 +1662130009375570688 +1662130009417571584 +1662130009468572672 +1662130009519573760 +1662130009561574656 +1662130009603575552 +1662130009645576448 +1662130009687577344 +1662130009732578304 +1662130009774579200 +1662130009816580096 +1662130009864581120 +1662130009912582144 +1662130009954583040 +1662130009996583936 +1662130010038584832 +1662130010080585728 +1662130010128586752 +1662130010170587648 +1662130010209588480 +1662130010248589312 +1662130010290590208 +1662130010332591104 +1662130010386592256 +1662130010434593280 +1662130010476594176 +1662130010521595136 +1662130010560595968 +1662130010602596864 +1662130010650597888 +1662130010695598848 +1662130010737599744 +1662130010788600832 +1662130010830601728 +1662130010875602688 +1662130010920603648 +1662130010968604672 +1662130011013605632 +1662130011058606592 +1662130011100607488 +1662130011142608384 +1662130011190609408 +1662130011229610240 +1662130011286611456 +1662130011331612416 +1662130011373613312 +1662130011415614208 +1662130011463615232 +1662130011508616192 +1662130011550617088 +1662130011592617984 +1662130011637618944 +1662130011679619840 +1662130011724620800 +1662130011766621696 +1662130011811622656 +1662130011856623616 +1662130011904624640 +1662130011946625536 +1662130011988626432 +1662130012030627328 +1662130012072628224 +1662130012114629120 +1662130012156630016 +1662130012198630912 +1662130012237631744 +1662130012279632640 +1662130012321633536 +1662130012369634560 +1662130012414635520 +1662130012456636416 +1662130012513637632 +1662130012555638528 +1662130012606639616 +1662130012648640512 +1662130012690641408 +1662130012732642304 +1662130012777643264 +1662130012819644160 +1662130012867645184 +1662130012912646144 +1662130012954647040 +1662130013002648064 +1662130013053649152 +1662130013095650048 +1662130013140651008 +1662130013185651968 +1662130013230652928 +1662130013275653888 +1662130013317654784 +1662130013365655808 +1662130013407656704 +1662130013455657728 +1662130013494658560 +1662130013542659584 +1662130013584660480 +1662130013626661376 +1662130013668662272 +1662130013713663232 +1662130013767664384 +1662130013812665344 +1662130013851666176 +1662130013902667264 +1662130013941668096 +1662130013983668992 +1662130014028669952 +1662130014070670848 +1662130014112671744 +1662130014154672640 +1662130014208673792 +1662130014259674880 +1662130014301675776 +1662130014352676864 +1662130014400677888 +1662130014442678784 +1662130014484679680 +1662130014523680512 +1662130014565681408 +1662130014610682368 +1662130014652683264 +1662130014700684288 +1662130014742685184 +1662130014787686144 +1662130014832687104 +1662130014874688000 +1662130014919688960 +1662130014976690176 +1662130015024691200 +1662130015072692224 +1662130015114693120 +1662130015156694016 +1662130015201694976 +1662130015240695808 +1662130015279696640 +1662130015321697536 +1662130015369698560 +1662130015420699648 +1662130015462700544 +1662130015504701440 +1662130015552702464 +1662130015594703360 +1662130015636704256 +1662130015678705152 +1662130015720706048 +1662130015768707072 +1662130015819708160 +1662130015861709056 +1662130015903709952 +1662130015945710848 +1662130015996711936 +1662130016038712832 +1662130016080713728 +1662130016128714752 +1662130016179715840 +1662130016221716736 +1662130016263717632 +1662130016308718592 +1662130016362719744 +1662130016401720576 +1662130016443721472 +1662130016482722304 +1662130016527723264 +1662130016569724160 +1662130016611725056 +1662130016668726272 +1662130016710727168 +1662130016761728256 +1662130016812729344 +1662130016854730240 +1662130016896731136 +1662130016938732032 +1662130016977732864 +1662130017022733824 +1662130017061734656 +1662130017103735552 +1662130017154736640 +1662130017202737664 +1662130017247738624 +1662130017289739520 +1662130017334740480 +1662130017379741440 +1662130017421742336 +1662130017469743360 +1662130017517744384 +1662130017559745280 +1662130017601746176 +1662130017649747200 +1662130017691748096 +1662130017733748992 +1662130017781750016 +1662130017826750976 +1662130017877752064 +1662130017922753024 +1662130017964753920 +1662130018006754816 +1662130018045755648 +1662130018093756672 +1662130018147757824 +1662130018189758720 +1662130018228759552 +1662130018273760512 +1662130018318761472 +1662130018357762304 +1662130018402763264 +1662130018447764224 +1662130018489765120 +1662130018528765952 +1662130018573766912 +1662130018618767872 +1662130018660768768 +1662130018702769664 +1662130018744770560 +1662130018795771648 +1662130018837772544 +1662130018888773632 +1662130018936774656 +1662130018978775552 +1662130019032776704 +1662130019077777664 +1662130019116778496 +1662130019161779456 +1662130019209780480 +1662130019248781312 +1662130019287782144 +1662130019335783168 +1662130019383784192 +1662130019425785088 +1662130019473786112 +1662130019515787008 +1662130019557787904 +1662130019596788736 +1662130019644789760 +1662130019683790592 +1662130019728791552 +1662130019776792576 +1662130019821793536 +1662130019863794432 +1662130019905795328 +1662130019950796288 +1662130019992797184 +1662130020055798528 +1662130020097799424 +1662130020145800448 +1662130020190801408 +1662130020232802304 +1662130020274803200 +1662130020316804096 +1662130020364805120 +1662130020412806144 +1662130020454807040 +1662130020505808128 +1662130020550809088 +1662130020592809984 +1662130020634810880 +1662130020682811904 +1662130020724812800 +1662130020769813760 +1662130020811814656 +1662130020859815680 +1662130020904816640 +1662130020946817536 +1662130021000818688 +1662130021045819648 +1662130021093820672 +1662130021138821632 +1662130021180822528 +1662130021222823424 +1662130021267824384 +1662130021315825408 +1662130021357826304 +1662130021399827200 +1662130021441828096 +1662130021483828992 +1662130021522829824 +1662130021570830848 +1662130021615831808 +1662130021666832896 +1662130021720834048 +1662130021768835072 +1662130021822836224 +1662130021873837312 +1662130021921838336 +1662130021969839360 +1662130022014840320 +1662130022059841280 +1662130022104842240 +1662130022143843072 +1662130022188844032 +1662130022230844928 +1662130022278845952 +1662130022323846912 +1662130022374848000 +1662130022416848896 +1662130022467849984 +1662130022512850944 +1662130022554851840 +1662130022599852800 +1662130022638853632 +1662130022680854528 +1662130022722855424 +1662130022764856320 +1662130022812857344 +1662130022854858240 +1662130022896859136 +1662130022947860224 +1662130022989861120 +1662130023034862080 +1662130023076862976 +1662130023112863744 +1662130023157864704 +1662130023199865600 +1662130023244866560 +1662130023292867584 +1662130023334868480 +1662130023376869376 +1662130023418870272 +1662130023463871232 +1662130023505872128 +1662130023556873216 +1662130023607874304 +1662130023655875328 +1662130023697876224 +1662130023739877120 +1662130023787878144 +1662130023829879040 +1662130023877880064 +1662130023925881088 +1662130023970882048 +1662130024012882944 +1662130024054883840 +1662130024096884736 +1662130024150885888 +1662130024195886848 +1662130024240887808 +1662130024279888640 +1662130024324889600 +1662130024369890560 +1662130024414891520 +1662130024456892416 +1662130024501893376 +1662130024546894336 +1662130024597895424 +1662130024645896448 +1662130024690897408 +1662130024732898304 +1662130024774899200 +1662130024816900096 +1662130024858900992 +1662130024903901952 +1662130024948902912 +1662130024999904000 +1662130025041904896 +1662130025080905728 +1662130025128906752 +1662130025170907648 +1662130025224908800 +1662130025263909632 +1662130025302910464 +1662130025353911552 +1662130025398912512 +1662130025443913472 +1662130025485914368 +1662130025527915264 +1662130025569916160 +1662130025611917056 +1662130025647917824 +1662130025689918720 +1662130025734919680 +1662130025776920576 +1662130025824921600 +1662130025866922496 +1662130025908923392 +1662130025947924224 +1662130025989925120 +1662130026031926016 +1662130026076926976 +1662130026118927872 +1662130026163928832 +1662130026202929664 +1662130026244930560 +1662130026289931520 +1662130026337932544 +1662130026382933504 +1662130026424934400 +1662130026466935296 +1662130026508936192 +1662130026553937152 +1662130026595938048 +1662130026640939008 +1662130026682939904 +1662130026721940736 +1662130026763941632 +1662130026811942656 +1662130026856943616 +1662130026904944640 +1662130026955945728 +1662130026994946560 +1662130027039947520 +1662130027081948416 +1662130027117949184 +1662130027165950208 +1662130027207951104 +1662130027249952000 +1662130027297953024 +1662130027351954176 +1662130027396955136 +1662130027444956160 +1662130027489957120 +1662130027537958144 +1662130027579959040 +1662130027621959936 +1662130027660960768 +1662130027711961856 +1662130027753962752 +1662130027795963648 +1662130027837964544 +1662130027885965568 +1662130027930966528 +1662130027975967488 +1662130028026968576 +1662130028068969472 +1662130028113970432 +1662130028161971456 +1662130028209972480 +1662130028257973504 +1662130028296974336 +1662130028341975296 +1662130028383976192 +1662130028428977152 +1662130028473978112 +1662130028521979136 +1662130028563980032 +1662130028605980928 +1662130028647981824 +1662130028689982720 +1662130028731983616 +1662130028779984640 +1662130028815985408 +1662130028863986432 +1662130028908987392 +1662130028956988416 +1662130028998989312 +1662130029043990272 +1662130029085991168 +1662130029136992256 +1662130029178993152 +1662130029226994176 +1662130029271995136 +1662130029307995904 +1662130029352996864 +1662130029388997632 +1662130029433998592 +1662130029475999488 +1662130029518000384 +1662130029560001280 +1662130029605002240 +1662130029650003200 +1662130029692004096 +1662130029740005120 +1662130029782006016 +1662130029827006976 +1662130029872007936 +1662130029914008832 +1662130029959009792 +1662130030004010752 +1662130030058011904 +1662130030100012800 +1662130030145013760 +1662130030193014784 +1662130030238015744 +1662130030277016576 +1662130030319017472 +1662130030364018432 +1662130030406019328 +1662130030448020224 +1662130030496021248 +1662130030538022144 +1662130030583023104 +1662130030628024064 +1662130030676025088 +1662130030721026048 +1662130030763026944 +1662130030811027968 +1662130030856028928 +1662130030904029952 +1662130030952030976 +1662130030997031936 +1662130031045032960 +1662130031087033856 +1662130031126034688 +1662130031171035648 +1662130031213036544 +1662130031261037568 +1662130031306038528 +1662130031354039552 +1662130031396040448 +1662130031441041408 +1662130031480042240 +1662130031522043136 +1662130031567044096 +1662130031615045120 +1662130031660046080 +1662130031702046976 +1662130031744047872 +1662130031786048768 +1662130031831049728 +1662130031879050752 +1662130031921051648 +1662130031972052736 +1662130032020053760 +1662130032059054592 +1662130032110055680 +1662130032152056576 +1662130032191057408 +1662130032233058304 +1662130032278059264 +1662130032326060288 +1662130032368061184 +1662130032410062080 +1662130032452062976 +1662130032491063808 +1662130032530064640 +1662130032575065600 +1662130032617066496 +1662130032659067392 +1662130032701068288 +1662130032743069184 +1662130032782070016 +1662130032827070976 +1662130032869071872 +1662130032917072896 +1662130032959073792 +1662130033004074752 +1662130033046075648 +1662130033088076544 +1662130033133077504 +1662130033181078528 +1662130033226079488 +1662130033271080448 +1662130033319081472 +1662130033364082432 +1662130033406083328 +1662130033445084160 +1662130033493085184 +1662130033535086080 +1662130033577086976 +1662130033619087872 +1662130033661088768 +1662130033709089792 +1662130033751090688 +1662130033796091648 +1662130033838092544 +1662130033889093632 +1662130033931094528 +1662130033976095488 +1662130034018096384 +1662130034066097408 +1662130034108098304 +1662130034150099200 +1662130034195100160 +1662130034240101120 +1662130034285102080 +1662130034324102912 +1662130034366103808 +1662130034411104768 +1662130034453105664 +1662130034501106688 +1662130034543107584 +1662130034579108352 +1662130034621109248 +1662130034663110144 +1662130034708111104 +1662130034756112128 +1662130034798113024 +1662130034846114048 +1662130034888114944 +1662130034930115840 +1662130034969116672 +1662130035017117696 +1662130035059118592 +1662130035104119552 +1662130035149120512 +1662130035194121472 +1662130035236122368 +1662130035278123264 +1662130035323124224 +1662130035362125056 +1662130035404125952 +1662130035452126976 +1662130035500128000 +1662130035551129088 +1662130035593129984 +1662130035638130944 +1662130035686131968 +1662130035734132992 +1662130035776133888 +1662130035821134848 +1662130035863135744 +1662130035911136768 +1662130035953137664 +1662130036004138752 +1662130036046139648 +1662130036094140672 +1662130036139141632 +1662130036190142720 +1662130036235143680 +1662130036277144576 +1662130036328145664 +1662130036370146560 +1662130036415147520 +1662130036463148544 +1662130036502149376 +1662130036547150336 +1662130036586151168 +1662130036628152064 +1662130036676153088 +1662130036718153984 +1662130036760154880 +1662130036802155776 +1662130036844156672 +1662130036889157632 +1662130036931158528 +1662130036982159616 +1662130037021160448 +1662130037063161344 +1662130037105162240 +1662130037141163008 +1662130037183163904 +1662130037228164864 +1662130037270165760 +1662130037312166656 +1662130037354167552 +1662130037405168640 +1662130037450169600 +1662130037495170560 +1662130037537171456 +1662130037576172288 +1662130037627173376 +1662130037672174336 +1662130037711175168 +1662130037753176064 +1662130037795176960 +1662130037837177856 +1662130037885178880 +1662130037930179840 +1662130037972180736 +1662130038020181760 +1662130038059182592 +1662130038110183680 +1662130038161184768 +1662130038203185664 +1662130038251186688 +1662130038296187648 +1662130038341188608 +1662130038392189696 +1662130038434190592 +1662130038476191488 +1662130038524192512 +1662130038566193408 +1662130038614194432 +1662130038665195520 +1662130038713196544 +1662130038758197504 +1662130038800198400 +1662130038839199232 +1662130038881200128 +1662130038935201280 +1662130038980202240 +1662130039022203136 +1662130039064204032 +1662130039109204992 +1662130039154205952 +1662130039196206848 +1662130039241207808 +1662130039286208768 +1662130039325209600 +1662130039364210432 +1662130039412211456 +1662130039457212416 +1662130039499213312 +1662130039544214272 +1662130039592215296 +1662130039637216256 +1662130039679217152 +1662130039724218112 +1662130039769219072 +1662130039811219968 +1662130039853220864 +1662130039901221888 +1662130039946222848 +1662130039988223744 +1662130040027224576 +1662130040078225664 +1662130040132226816 +1662130040174227712 +1662130040213228544 +1662130040255229440 +1662130040294230272 +1662130040336231168 +1662130040375232000 +1662130040420232960 +1662130040468233984 +1662130040516235008 +1662130040558235904 +1662130040603236864 +1662130040648237824 +1662130040693238784 +1662130040738239744 +1662130040789240832 +1662130040828241664 +1662130040870242560 +1662130040912243456 +1662130040954244352 +1662130040999245312 +1662130041044246272 +1662130041089247232 +1662130041128248064 +1662130041170248960 +1662130041212249856 +1662130041254250752 +1662130041299251712 +1662130041341252608 +1662130041383253504 +1662130041428254464 +1662130041467255296 +1662130041518256384 +1662130041563257344 +1662130041608258304 +1662130041653259264 +1662130041698260224 +1662130041749261312 +1662130041785262080 +1662130041830263040 +1662130041872263936 +1662130041914264832 +1662130041971266048 +1662130042013266944 +1662130042061267968 +1662130042103268864 +1662130042145269760 +1662130042187270656 +1662130042238271744 +1662130042283272704 +1662130042334273792 +1662130042376274688 +1662130042418275584 +1662130042460276480 +1662130042517277696 +1662130042559278592 +1662130042601279488 +1662130042643280384 +1662130042691281408 +1662130042733282304 +1662130042775283200 +1662130042817284096 +1662130042859284992 +1662130042907286016 +1662130042955287040 +1662130043000288000 +1662130043054289152 +1662130043096290048 +1662130043135290880 +1662130043177291776 +1662130043228292864 +1662130043270293760 +1662130043312294656 +1662130043363295744 +1662130043405296640 +1662130043447297536 +1662130043501298688 +1662130043549299712 +1662130043594300672 +1662130043633301504 +1662130043678302464 +1662130043720303360 +1662130043759304192 +1662130043813305344 +1662130043858306304 +1662130043900307200 +1662130043945308160 +1662130043984308992 +1662130044026309888 +1662130044065310720 +1662130044110311680 +1662130044152312576 +1662130044194313472 +1662130044257314816 +1662130044293315584 +1662130044341316608 +1662130044383317504 +1662130044428318464 +1662130044470319360 +1662130044512320256 +1662130044557321216 +1662130044599322112 +1662130044647323136 +1662130044689324032 +1662130044734324992 +1662130044785326080 +1662130044827326976 +1662130044869327872 +1662130044911328768 +1662130044950329600 +1662130045001330688 +1662130045043331584 +1662130045091332608 +1662130045133333504 +1662130045175334400 +1662130045226335488 +1662130045268336384 +1662130045313337344 +1662130045355338240 +1662130045400339200 +1662130045448340224 +1662130045493341184 +1662130045544342272 +1662130045586343168 +1662130045628344064 +1662130045673345024 +1662130045715345920 +1662130045757346816 +1662130045799347712 +1662130045844348672 +1662130045886349568 +1662130045931350528 +1662130045973351424 +1662130046012352256 +1662130046054353152 +1662130046099354112 +1662130046138354944 +1662130046177355776 +1662130046219356672 +1662130046258357504 +1662130046300358400 +1662130046351359488 +1662130046396360448 +1662130046438361344 +1662130046477362176 +1662130046522363136 +1662130046561363968 +1662130046600364800 +1662130046642365696 +1662130046684366592 +1662130046726367488 +1662130046765368320 +1662130046807369216 +1662130046852370176 +1662130046900371200 +1662130046948372224 +1662130046990373120 +1662130047041374208 +1662130047086375168 +1662130047128376064 +1662130047170376960 +1662130047227378176 +1662130047269379072 +1662130047311379968 +1662130047356380928 +1662130047398381824 +1662130047443382784 +1662130047485383680 +1662130047530384640 +1662130047578385664 +1662130047626386688 +1662130047674387712 +1662130047725388800 +1662130047776389888 +1662130047815390720 +1662130047854391552 +1662130047896392448 +1662130047947393536 +1662130047995394560 +1662130048040395520 +1662130048088396544 +1662130048133397504 +1662130048181398528 +1662130048226399488 +1662130048274400512 +1662130048316401408 +1662130048364402432 +1662130048412403456 +1662130048460404480 +1662130048502405376 +1662130048553406464 +1662130048595407360 +1662130048643408384 +1662130048685409280 +1662130048736410368 +1662130048778411264 +1662130048829412352 +1662130048871413248 +1662130048916414208 +1662130048955415040 +1662130049003416064 +1662130049045416960 +1662130049090417920 +1662130049132418816 +1662130049180419840 +1662130049225420800 +1662130049270421760 +1662130049312422656 +1662130049375424000 +1662130049417424896 +1662130049462425856 +1662130049507426816 +1662130049552427776 +1662130049594428672 +1662130049633429504 +1662130049675430400 +1662130049726431488 +1662130049768432384 +1662130049810433280 +1662130049852434176 +1662130049897435136 +1662130049936435968 +1662130049984436992 +1662130050026437888 +1662130050068438784 +1662130050110439680 +1662130050155440640 +1662130050200441600 +1662130050245442560 +1662130050287443456 +1662130050329444352 +1662130050368445184 +1662130050410446080 +1662130050452446976 +1662130050500448000 +1662130050545448960 +1662130050587449856 +1662130050629450752 +1662130050674451712 +1662130050716452608 +1662130050761453568 +1662130050800454400 +1662130050845455360 +1662130050896456448 +1662130050941457408 +1662130050986458368 +1662130051031459328 +1662130051076460288 +1662130051118461184 +1662130051163462144 +1662130051211463168 +1662130051253464064 +1662130051298465024 +1662130051340465920 +1662130051385466880 +1662130051430467840 +1662130051478468864 +1662130051526469888 +1662130051571470848 +1662130051619471872 +1662130051664472832 +1662130051709473792 +1662130051751474688 +1662130051796475648 +1662130051838476544 +1662130051883477504 +1662130051925478400 +1662130051967479296 +1662130052006480128 +1662130052048481024 +1662130052090481920 +1662130052132482816 +1662130052180483840 +1662130052231484928 +1662130052273485824 +1662130052321486848 +1662130052363487744 +1662130052408488704 +1662130052453489664 +1662130052498490624 +1662130052546491648 +1662130052588492544 +1662130052639493632 +1662130052687494656 +1662130052729495552 +1662130052771496448 +1662130052816497408 +1662130052867498496 +1662130052912499456 +1662130052957500416 +1662130053008501504 +1662130053062502656 +1662130053107503616 +1662130053155504640 +1662130053197505536 +1662130053239506432 +1662130053281507328 +1662130053320508160 +1662130053362509056 +1662130053404509952 +1662130053446510848 +1662130053488511744 +1662130053536512768 +1662130053575513600 +1662130053629514752 +1662130053668515584 +1662130053713516544 +1662130053755517440 +1662130053800518400 +1662130053851519488 +1662130053896520448 +1662130053941521408 +1662130053983522304 +1662130054028523264 +1662130054073524224 +1662130054118525184 +1662130054160526080 +1662130054208527104 +1662130054250528000 +1662130054298529024 +1662130054346530048 +1662130054385530880 +1662130054427531776 +1662130054472532736 +1662130054514533632 +1662130054556534528 +1662130054604535552 +1662130054646536448 +1662130054694537472 +1662130054748538624 +1662130054796539648 +1662130054838540544 +1662130054880541440 +1662130054928542464 +1662130054976543488 +1662130055018544384 +1662130055060545280 +1662130055105546240 +1662130055153547264 +1662130055201548288 +1662130055246549248 +1662130055294550272 +1662130055342551296 +1662130055387552256 +1662130055429553152 +1662130055471554048 +1662130055510554880 +1662130055552555776 +1662130055594556672 +1662130055636557568 +1662130055693558784 +1662130055735559680 +1662130055777560576 +1662130055819561472 +1662130055861562368 +1662130055906563328 +1662130055948564224 +1662130055987565056 +1662130056032566016 +1662130056077566976 +1662130056119567872 +1662130056161568768 +1662130056203569664 +1662130056251570688 +1662130056290571520 +1662130056338572544 +1662130056386573568 +1662130056431574528 +1662130056476575488 +1662130056518576384 +1662130056563577344 +1662130056611578368 +1662130056656579328 +1662130056701580288 +1662130056743581184 +1662130056785582080 +1662130056827582976 +1662130056869583872 +1662130056914584832 +1662130056965585920 +1662130057010586880 +1662130057058587904 +1662130057106588928 +1662130057151589888 +1662130057193590784 +1662130057244591872 +1662130057286592768 +1662130057328593664 +1662130057376594688 +1662130057421595648 +1662130057466596608 +1662130057514597632 +1662130057553598464 +1662130057598599424 +1662130057646600448 +1662130057688601344 +1662130057730602240 +1662130057775603200 +1662130057823604224 +1662130057868605184 +1662130057910606080 +1662130057955607040 +1662130057994607872 +1662130058039608832 +1662130058084609792 +1662130058132610816 +1662130058180611840 +1662130058228612864 +1662130058279613952 +1662130058321614848 +1662130058363615744 +1662130058405616640 +1662130058450617600 +1662130058492618496 +1662130058537619456 +1662130058579620352 +1662130058624621312 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_dark.txt b/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_dark.txt new file mode 100644 index 0000000000..656025a687 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_dark.txt @@ -0,0 +1,2741 @@ +1662063934494348032 +1662063934536348928 +1662063934587350016 +1662063934629350912 +1662063934671351808 +1662063934713352704 +1662063934758353664 +1662063934803354624 +1662063934848355584 +1662063934893356544 +1662063934938357504 +1662063934977358336 +1662063935022359296 +1662063935064360192 +1662063935103361024 +1662063935145361920 +1662063935187362816 +1662063935229363712 +1662063935268364544 +1662063935310365440 +1662063935352366336 +1662063935394367232 +1662063935436368128 +1662063935478369024 +1662063935535370240 +1662063935577371136 +1662063935619372032 +1662063935670373120 +1662063935712374016 +1662063935757374976 +1662063935799375872 +1662063935844376832 +1662063935886377728 +1662063935931378688 +1662063935973379584 +1662063936015380480 +1662063936057381376 +1662063936099382272 +1662063936141383168 +1662063936180384000 +1662063936222384896 +1662063936267385856 +1662063936312386816 +1662063936360387840 +1662063936405388800 +1662063936447389696 +1662063936489390592 +1662063936531391488 +1662063936573392384 +1662063936615393280 +1662063936657394176 +1662063936699395072 +1662063936744396032 +1662063936786396928 +1662063936828397824 +1662063936870398720 +1662063936909399552 +1662063936948400384 +1662063936990401280 +1662063937038402304 +1662063937089403392 +1662063937134404352 +1662063937182405376 +1662063937224406272 +1662063937269407232 +1662063937314408192 +1662063937356409088 +1662063937401410048 +1662063937449411072 +1662063937488411904 +1662063937539412992 +1662063937584413952 +1662063937638415104 +1662063937677415936 +1662063937719416832 +1662063937761417728 +1662063937803418624 +1662063937842419456 +1662063937887420416 +1662063937935421440 +1662063937977422336 +1662063938019423232 +1662063938061424128 +1662063938106425088 +1662063938148425984 +1662063938193426944 +1662063938238427904 +1662063938283428864 +1662063938325429760 +1662063938370430720 +1662063938412431616 +1662063938457432576 +1662063938499433472 +1662063938544434432 +1662063938586435328 +1662063938631436288 +1662063938676437248 +1662063938718438144 +1662063938760439040 +1662063938802439936 +1662063938850440960 +1662063938898441984 +1662063938943442944 +1662063938988443904 +1662063939036444928 +1662063939078445824 +1662063939126446848 +1662063939165447680 +1662063939210448640 +1662063939252449536 +1662063939300450560 +1662063939342451456 +1662063939387452416 +1662063939429453312 +1662063939471454208 +1662063939510455040 +1662063939552455936 +1662063939594456832 +1662063939639457792 +1662063939681458688 +1662063939723459584 +1662063939765460480 +1662063939807461376 +1662063939852462336 +1662063939894463232 +1662063939939464192 +1662063939981465088 +1662063940026466048 +1662063940068466944 +1662063940113467904 +1662063940158468864 +1662063940209469952 +1662063940257470976 +1662063940299471872 +1662063940341472768 +1662063940383473664 +1662063940422474496 +1662063940464475392 +1662063940506476288 +1662063940548477184 +1662063940590478080 +1662063940632478976 +1662063940674479872 +1662063940716480768 +1662063940767481856 +1662063940806482688 +1662063940851483648 +1662063940899484672 +1662063940941485568 +1662063940989486592 +1662063941034487552 +1662063941079488512 +1662063941124489472 +1662063941169490432 +1662063941214491392 +1662063941262492416 +1662063941304493312 +1662063941346494208 +1662063941391495168 +1662063941436496128 +1662063941475496960 +1662063941517497856 +1662063941562498816 +1662063941604499712 +1662063941646500608 +1662063941688501504 +1662063941736502528 +1662063941784503552 +1662063941832504576 +1662063941874505472 +1662063941922506496 +1662063941964507392 +1662063942009508352 +1662063942051509248 +1662063942093510144 +1662063942138511104 +1662063942180512000 +1662063942222512896 +1662063942267513856 +1662063942309514752 +1662063942351515648 +1662063942396516608 +1662063942447517696 +1662063942498518784 +1662063942543519744 +1662063942585520640 +1662063942630521600 +1662063942672522496 +1662063942714523392 +1662063942762524416 +1662063942807525376 +1662063942852526336 +1662063942897527296 +1662063942942528256 +1662063942984529152 +1662063943029530112 +1662063943074531072 +1662063943116531968 +1662063943167533056 +1662063943206533888 +1662063943248534784 +1662063943287535616 +1662063943329536512 +1662063943374537472 +1662063943416538368 +1662063943458539264 +1662063943503540224 +1662063943545541120 +1662063943584541952 +1662063943629542912 +1662063943671543808 +1662063943710544640 +1662063943752545536 +1662063943794546432 +1662063943836547328 +1662063943884548352 +1662063943935549440 +1662063943977550336 +1662063944019551232 +1662063944061552128 +1662063944103553024 +1662063944145553920 +1662063944184554752 +1662063944229555712 +1662063944277556736 +1662063944319557632 +1662063944361558528 +1662063944418559744 +1662063944463560704 +1662063944508561664 +1662063944553562624 +1662063944595563520 +1662063944640564480 +1662063944682565376 +1662063944733566464 +1662063944778567424 +1662063944823568384 +1662063944865569280 +1662063944910570240 +1662063944955571200 +1662063944997572096 +1662063945039572992 +1662063945081573888 +1662063945126574848 +1662063945171575808 +1662063945213576704 +1662063945255577600 +1662063945297578496 +1662063945339579392 +1662063945381580288 +1662063945420581120 +1662063945465582080 +1662063945507582976 +1662063945549583872 +1662063945588584704 +1662063945642585856 +1662063945690586880 +1662063945732587776 +1662063945780588800 +1662063945822589696 +1662063945867590656 +1662063945912591616 +1662063945954592512 +1662063945999593472 +1662063946041594368 +1662063946089595392 +1662063946131596288 +1662063946173597184 +1662063946215598080 +1662063946263599104 +1662063946302599936 +1662063946344600832 +1662063946392601856 +1662063946437602816 +1662063946479603712 +1662063946524604672 +1662063946566605568 +1662063946608606464 +1662063946650607360 +1662063946692608256 +1662063946731609088 +1662063946776610048 +1662063946818610944 +1662063946863611904 +1662063946908612864 +1662063946950613760 +1662063946992614656 +1662063947037615616 +1662063947076616448 +1662063947124617472 +1662063947163618304 +1662063947205619200 +1662063947247620096 +1662063947292621056 +1662063947337622016 +1662063947382622976 +1662063947430624000 +1662063947472624896 +1662063947517625856 +1662063947565626880 +1662063947604627712 +1662063947649628672 +1662063947694629632 +1662063947736630528 +1662063947787631616 +1662063947832632576 +1662063947871633408 +1662063947913634304 +1662063947955635200 +1662063947997636096 +1662063948045637120 +1662063948087638016 +1662063948129638912 +1662063948171639808 +1662063948213640704 +1662063948270641920 +1662063948309642752 +1662063948354643712 +1662063948402644736 +1662063948444645632 +1662063948486646528 +1662063948534647552 +1662063948576648448 +1662063948621649408 +1662063948663650304 +1662063948699651072 +1662063948741651968 +1662063948783652864 +1662063948831653888 +1662063948879654912 +1662063948924655872 +1662063948966656768 +1662063949008657664 +1662063949050658560 +1662063949092659456 +1662063949134660352 +1662063949176661248 +1662063949215662080 +1662063949263663104 +1662063949305664000 +1662063949347664896 +1662063949389665792 +1662063949431666688 +1662063949473667584 +1662063949518668544 +1662063949563669504 +1662063949602670336 +1662063949641671168 +1662063949686672128 +1662063949728673024 +1662063949770673920 +1662063949812674816 +1662063949854675712 +1662063949902676736 +1662063949941677568 +1662063949986678528 +1662063950031679488 +1662063950073680384 +1662063950112681216 +1662063950154682112 +1662063950199683072 +1662063950244684032 +1662063950289684992 +1662063950334685952 +1662063950382686976 +1662063950430688000 +1662063950472688896 +1662063950520689920 +1662063950562690816 +1662063950604691712 +1662063950646692608 +1662063950688693504 +1662063950733694464 +1662063950778695424 +1662063950823696384 +1662063950865697280 +1662063950907698176 +1662063950949699072 +1662063951003700224 +1662063951042701056 +1662063951084701952 +1662063951135703040 +1662063951177703936 +1662063951222704896 +1662063951267705856 +1662063951309706752 +1662063951357707776 +1662063951402708736 +1662063951447709696 +1662063951495710720 +1662063951537711616 +1662063951585712640 +1662063951627713536 +1662063951672714496 +1662063951717715456 +1662063951759716352 +1662063951807717376 +1662063951849718272 +1662063951891719168 +1662063951933720064 +1662063951975720960 +1662063952017721856 +1662063952062722816 +1662063952104723712 +1662063952149724672 +1662063952194725632 +1662063952242726656 +1662063952287727616 +1662063952335728640 +1662063952380729600 +1662063952425730560 +1662063952470731520 +1662063952512732416 +1662063952551733248 +1662063952590734080 +1662063952635735040 +1662063952680736000 +1662063952722736896 +1662063952767737856 +1662063952809738752 +1662063952851739648 +1662063952890740480 +1662063952932741376 +1662063952980742400 +1662063953022743296 +1662063953067744256 +1662063953112745216 +1662063953154746112 +1662063953199747072 +1662063953241747968 +1662063953280748800 +1662063953325749760 +1662063953370750720 +1662063953415751680 +1662063953457752576 +1662063953502753536 +1662063953544754432 +1662063953586755328 +1662063953628756224 +1662063953676757248 +1662063953718758144 +1662063953763759104 +1662063953808760064 +1662063953850760960 +1662063953892761856 +1662063953934762752 +1662063953979763712 +1662063954024764672 +1662063954066765568 +1662063954108766464 +1662063954150767360 +1662063954192768256 +1662063954240769280 +1662063954282770176 +1662063954330771200 +1662063954375772160 +1662063954414772992 +1662063954456773888 +1662063954501774848 +1662063954543775744 +1662063954588776704 +1662063954633777664 +1662063954678778624 +1662063954720779520 +1662063954765780480 +1662063954807781376 +1662063954849782272 +1662063954891783168 +1662063954933784064 +1662063954975784960 +1662063955017785856 +1662063955065786880 +1662063955113787904 +1662063955155788800 +1662063955197789696 +1662063955242790656 +1662063955284791552 +1662063955329792512 +1662063955374793472 +1662063955425794560 +1662063955464795392 +1662063955509796352 +1662063955548797184 +1662063955590798080 +1662063955629798912 +1662063955671799808 +1662063955713800704 +1662063955755801600 +1662063955800802560 +1662063955854803712 +1662063955896804608 +1662063955938805504 +1662063955986806528 +1662063956031807488 +1662063956079808512 +1662063956121809408 +1662063956163810304 +1662063956205811200 +1662063956247812096 +1662063956289812992 +1662063956331813888 +1662063956376814848 +1662063956415815680 +1662063956457816576 +1662063956502817536 +1662063956547818496 +1662063956589819392 +1662063956637820416 +1662063956679821312 +1662063956718822144 +1662063956766823168 +1662063956814824192 +1662063956865825280 +1662063956910826240 +1662063956952827136 +1662063956997828096 +1662063957039828992 +1662063957084829952 +1662063957126830848 +1662063957171831808 +1662063957216832768 +1662063957261833728 +1662063957303834624 +1662063957348835584 +1662063957387836416 +1662063957429837312 +1662063957474838272 +1662063957522839296 +1662063957564840192 +1662063957603841024 +1662063957645841920 +1662063957690842880 +1662063957732843776 +1662063957777844736 +1662063957819845632 +1662063957864846592 +1662063957912847616 +1662063957954848512 +1662063957996849408 +1662063958041850368 +1662063958083851264 +1662063958131852288 +1662063958176853248 +1662063958224854272 +1662063958269855232 +1662063958320856320 +1662063958365857280 +1662063958407858176 +1662063958452859136 +1662063958494860032 +1662063958536860928 +1662063958584861952 +1662063958626862848 +1662063958668863744 +1662063958713864704 +1662063958752865536 +1662063958803866624 +1662063958848867584 +1662063958893868544 +1662063958941869568 +1662063958992870656 +1662063959034871552 +1662063959079872512 +1662063959121873408 +1662063959166874368 +1662063959208875264 +1662063959253876224 +1662063959301877248 +1662063959355878400 +1662063959397879296 +1662063959436880128 +1662063959478881024 +1662063959529882112 +1662063959574883072 +1662063959616883968 +1662063959658884864 +1662063959700885760 +1662063959742886656 +1662063959784887552 +1662063959829888512 +1662063959871889408 +1662063959913890304 +1662063959955891200 +1662063959997892096 +1662063960039892992 +1662063960084893952 +1662063960129894912 +1662063960174895872 +1662063960216896768 +1662063960258897664 +1662063960300898560 +1662063960342899456 +1662063960387900416 +1662063960429901312 +1662063960474902272 +1662063960525903360 +1662063960567904256 +1662063960606905088 +1662063960648905984 +1662063960687906816 +1662063960732907776 +1662063960774908672 +1662063960816909568 +1662063960861910528 +1662063960906911488 +1662063960948912384 +1662063960990913280 +1662063961032914176 +1662063961074915072 +1662063961119916032 +1662063961164916992 +1662063961209917952 +1662063961254918912 +1662063961299919872 +1662063961344920832 +1662063961389921792 +1662063961428922624 +1662063961470923520 +1662063961515924480 +1662063961563925504 +1662063961608926464 +1662063961650927360 +1662063961689928192 +1662063961728929024 +1662063961776930048 +1662063961821931008 +1662063961863931904 +1662063961908932864 +1662063961956933888 +1662063961998934784 +1662063962040935680 +1662063962088936704 +1662063962136937728 +1662063962178938624 +1662063962223939584 +1662063962271940608 +1662063962316941568 +1662063962367942656 +1662063962409943552 +1662063962451944448 +1662063962496945408 +1662063962547946496 +1662063962592947456 +1662063962640948480 +1662063962682949376 +1662063962724950272 +1662063962769951232 +1662063962814952192 +1662063962871953408 +1662063962913954304 +1662063962958955264 +1662063963006956288 +1662063963045957120 +1662063963090958080 +1662063963132958976 +1662063963183960064 +1662063963225960960 +1662063963267961856 +1662063963309962752 +1662063963354963712 +1662063963396964608 +1662063963435965440 +1662063963483966464 +1662063963531967488 +1662063963579968512 +1662063963621969408 +1662063963663970304 +1662063963711971328 +1662063963759972352 +1662063963801973248 +1662063963840974080 +1662063963885975040 +1662063963927975936 +1662063963972976896 +1662063964017977856 +1662063964059978752 +1662063964101979648 +1662063964143980544 +1662063964185981440 +1662063964227982336 +1662063964275983360 +1662063964320984320 +1662063964359985152 +1662063964401986048 +1662063964440986880 +1662063964479987712 +1662063964524988672 +1662063964566989568 +1662063964608990464 +1662063964653991424 +1662063964701992448 +1662063964749993472 +1662063964794994432 +1662063964836995328 +1662063964878996224 +1662063964923997184 +1662063964968998144 +1662063965010999040 +1662063965052999936 +1662063965098000896 +1662063965155002112 +1662063965197003008 +1662063965245004032 +1662063965287004928 +1662063965332005888 +1662063965377006848 +1662063965422007808 +1662063965461008640 +1662063965506009600 +1662063965545010432 +1662063965593011456 +1662063965635012352 +1662063965677013248 +1662063965719014144 +1662063965761015040 +1662063965809016064 +1662063965851016960 +1662063965893017856 +1662063965935018752 +1662063965980019712 +1662063966028020736 +1662063966073021696 +1662063966115022592 +1662063966160023552 +1662063966205024512 +1662063966250025472 +1662063966295026432 +1662063966337027328 +1662063966382028288 +1662063966427029248 +1662063966472030208 +1662063966514031104 +1662063966559032064 +1662063966601032960 +1662063966646033920 +1662063966688034816 +1662063966736035840 +1662063966781036800 +1662063966823037696 +1662063966868038656 +1662063966919039744 +1662063966964040704 +1662063967009041664 +1662063967054042624 +1662063967096043520 +1662063967138044416 +1662063967183045376 +1662063967225046272 +1662063967267047168 +1662063967309048064 +1662063967351048960 +1662063967393049856 +1662063967435050752 +1662063967477051648 +1662063967525052672 +1662063967570053632 +1662063967612054528 +1662063967654055424 +1662063967702056448 +1662063967741057280 +1662063967786058240 +1662063967828059136 +1662063967867059968 +1662063967909060864 +1662063967954061824 +1662063968002062848 +1662063968047063808 +1662063968089064704 +1662063968137065728 +1662063968179066624 +1662063968230067712 +1662063968275068672 +1662063968320069632 +1662063968365070592 +1662063968410071552 +1662063968455072512 +1662063968497073408 +1662063968539074304 +1662063968584075264 +1662063968623076096 +1662063968665076992 +1662063968710077952 +1662063968761079040 +1662063968803079936 +1662063968848080896 +1662063968893081856 +1662063968938082816 +1662063968983083776 +1662063969025084672 +1662063969073085696 +1662063969115086592 +1662063969157087488 +1662063969205088512 +1662063969253089536 +1662063969295090432 +1662063969346091520 +1662063969391092480 +1662063969433093376 +1662063969478094336 +1662063969523095296 +1662063969565096192 +1662063969610097152 +1662063969655098112 +1662063969700099072 +1662063969739099904 +1662063969781100800 +1662063969826101760 +1662063969868102656 +1662063969913103616 +1662063969967104768 +1662063970009105664 +1662063970051106560 +1662063970093107456 +1662063970132108288 +1662063970180109312 +1662063970228110336 +1662063970267111168 +1662063970309112064 +1662063970360113152 +1662063970405114112 +1662063970447115008 +1662063970492115968 +1662063970531116800 +1662063970576117760 +1662063970615118592 +1662063970660119552 +1662063970711120640 +1662063970750121472 +1662063970792122368 +1662063970834123264 +1662063970876124160 +1662063970918125056 +1662063970960125952 +1662063971002126848 +1662063971044127744 +1662063971089128704 +1662063971131129600 +1662063971176130560 +1662063971218131456 +1662063971260132352 +1662063971299133184 +1662063971341134080 +1662063971389135104 +1662063971431136000 +1662063971473136896 +1662063971515137792 +1662063971557138688 +1662063971605139712 +1662063971650140672 +1662063971692141568 +1662063971740142592 +1662063971782143488 +1662063971827144448 +1662063971869145344 +1662063971914146304 +1662063971956147200 +1662063971998148096 +1662063972040148992 +1662063972088150016 +1662063972142151168 +1662063972187152128 +1662063972232153088 +1662063972271153920 +1662063972316154880 +1662063972358155776 +1662063972400156672 +1662063972448157696 +1662063972490158592 +1662063972535159552 +1662063972577160448 +1662063972622161408 +1662063972661162240 +1662063972703163136 +1662063972754164224 +1662063972802165248 +1662063972853166336 +1662063972895167232 +1662063972937168128 +1662063972982169088 +1662063973024169984 +1662063973072171008 +1662063973114171904 +1662063973156172800 +1662063973201173760 +1662063973252174848 +1662063973300175872 +1662063973348176896 +1662063973402178048 +1662063973444178944 +1662063973486179840 +1662063973525180672 +1662063973564181504 +1662063973618182656 +1662063973660183552 +1662063973699184384 +1662063973744185344 +1662063973789186304 +1662063973834187264 +1662063973876188160 +1662063973921189120 +1662063973963190016 +1662063974014191104 +1662063974056192000 +1662063974095192832 +1662063974137193728 +1662063974176194560 +1662063974218195456 +1662063974260196352 +1662063974302197248 +1662063974350198272 +1662063974389199104 +1662063974440200192 +1662063974482201088 +1662063974527202048 +1662063974572203008 +1662063974614203904 +1662063974659204864 +1662063974704205824 +1662063974749206784 +1662063974797207808 +1662063974839208704 +1662063974881209600 +1662063974929210624 +1662063974971211520 +1662063975016212480 +1662063975064213504 +1662063975106214400 +1662063975154215424 +1662063975196216320 +1662063975238217216 +1662063975280218112 +1662063975325219072 +1662063975370220032 +1662063975412220928 +1662063975454221824 +1662063975493222656 +1662063975532223488 +1662063975577224448 +1662063975619225344 +1662063975661226240 +1662063975703227136 +1662063975748228096 +1662063975790228992 +1662063975832229888 +1662063975874230784 +1662063975910231552 +1662063975955232512 +1662063975994233344 +1662063976036234240 +1662063976084235264 +1662063976126236160 +1662063976168237056 +1662063976219238144 +1662063976261239040 +1662063976303239936 +1662063976345240832 +1662063976387241728 +1662063976429242624 +1662063976471243520 +1662063976519244544 +1662063976561245440 +1662063976603246336 +1662063976648247296 +1662063976693248256 +1662063976735249152 +1662063976780250112 +1662063976822251008 +1662063976867251968 +1662063976909252864 +1662063976954253824 +1662063977002254848 +1662063977044255744 +1662063977089256704 +1662063977134257664 +1662063977176258560 +1662063977218259456 +1662063977263260416 +1662063977305261312 +1662063977347262208 +1662063977389263104 +1662063977434264064 +1662063977476264960 +1662063977521265920 +1662063977563266816 +1662063977617267968 +1662063977659268864 +1662063977704269824 +1662063977761271040 +1662063977806272000 +1662063977854273024 +1662063977896273920 +1662063977938274816 +1662063977977275648 +1662063978022276608 +1662063978067277568 +1662063978112278528 +1662063978151279360 +1662063978196280320 +1662063978238281216 +1662063978286282240 +1662063978340283392 +1662063978397284608 +1662063978445285632 +1662063978484286464 +1662063978529287424 +1662063978571288320 +1662063978616289280 +1662063978658290176 +1662063978703291136 +1662063978745292032 +1662063978784292864 +1662063978826293760 +1662063978868294656 +1662063978913295616 +1662063978961296640 +1662063979003297536 +1662063979051298560 +1662063979093299456 +1662063979138300416 +1662063979186301440 +1662063979228302336 +1662063979267303168 +1662063979318304256 +1662063979363305216 +1662063979408306176 +1662063979453307136 +1662063979495308032 +1662063979534308864 +1662063979585309952 +1662063979627310848 +1662063979669311744 +1662063979711312640 +1662063979756313600 +1662063979798314496 +1662063979843315456 +1662063979888316416 +1662063979930317312 +1662063979978318336 +1662063980020319232 +1662063980065320192 +1662063980110321152 +1662063980158322176 +1662063980200323072 +1662063980239323904 +1662063980284324864 +1662063980326325760 +1662063980368326656 +1662063980410327552 +1662063980455328512 +1662063980503329536 +1662063980545330432 +1662063980587331328 +1662063980635332352 +1662063980683333376 +1662063980722334208 +1662063980764335104 +1662063980806336000 +1662063980854337024 +1662063980896337920 +1662063980947339008 +1662063980992339968 +1662063981034340864 +1662063981073341696 +1662063981118342656 +1662063981157343488 +1662063981199344384 +1662063981250345472 +1662063981292346368 +1662063981337347328 +1662063981379348224 +1662063981421349120 +1662063981472350208 +1662063981517351168 +1662063981574352384 +1662063981616353280 +1662063981667354368 +1662063981712355328 +1662063981757356288 +1662063981796357120 +1662063981841358080 +1662063981889359104 +1662063981931360000 +1662063981982361088 +1662063982024361984 +1662063982066362880 +1662063982114363904 +1662063982159364864 +1662063982201365760 +1662063982240366592 +1662063982288367616 +1662063982333368576 +1662063982384369664 +1662063982426370560 +1662063982465371392 +1662063982519372544 +1662063982561373440 +1662063982606374400 +1662063982648375296 +1662063982693376256 +1662063982738377216 +1662063982780378112 +1662063982822379008 +1662063982867379968 +1662063982909380864 +1662063982954381824 +1662063982993382656 +1662063983035383552 +1662063983080384512 +1662063983122385408 +1662063983173386496 +1662063983212387328 +1662063983257388288 +1662063983296389120 +1662063983338390016 +1662063983386391040 +1662063983434392064 +1662063983479393024 +1662063983524393984 +1662063983566394880 +1662063983608395776 +1662063983656396800 +1662063983698397696 +1662063983737398528 +1662063983779399424 +1662063983824400384 +1662063983863401216 +1662063983905402112 +1662063983959403264 +1662063984001404160 +1662063984043405056 +1662063984085405952 +1662063984124406784 +1662063984166407680 +1662063984220408832 +1662063984262409728 +1662063984310410752 +1662063984355411712 +1662063984397412608 +1662063984436413440 +1662063984478414336 +1662063984520415232 +1662063984568416256 +1662063984613417216 +1662063984658418176 +1662063984703419136 +1662063984745420032 +1662063984790420992 +1662063984835421952 +1662063984880422912 +1662063984940424192 +1662063984979425024 +1662063985021425920 +1662063985063426816 +1662063985111427840 +1662063985153428736 +1662063985195429632 +1662063985249430784 +1662063985291431680 +1662063985330432512 +1662063985375433472 +1662063985420434432 +1662063985459435264 +1662063985504436224 +1662063985546437120 +1662063985591438080 +1662063985636439040 +1662063985678439936 +1662063985726440960 +1662063985765441792 +1662063985807442688 +1662063985855443712 +1662063985900444672 +1662063985939445504 +1662063985987446528 +1662063986029447424 +1662063986074448384 +1662063986116449280 +1662063986158450176 +1662063986200451072 +1662063986248452096 +1662063986290452992 +1662063986335453952 +1662063986377454848 +1662063986419455744 +1662063986461456640 +1662063986509457664 +1662063986551458560 +1662063986593459456 +1662063986647460608 +1662063986686461440 +1662063986728462336 +1662063986770463232 +1662063986809464064 +1662063986851464960 +1662063986896465920 +1662063986938466816 +1662063986980467712 +1662063987022468608 +1662063987070469632 +1662063987112470528 +1662063987157471488 +1662063987196472320 +1662063987238473216 +1662063987289474304 +1662063987334475264 +1662063987391476480 +1662063987430477312 +1662063987475478272 +1662063987517479168 +1662063987559480064 +1662063987601480960 +1662063987637481728 +1662063987679482624 +1662063987721483520 +1662063987763484416 +1662063987805485312 +1662063987847486208 +1662063987889487104 +1662063987937488128 +1662063987979489024 +1662063988021489920 +1662063988057490688 +1662063988102491648 +1662063988144492544 +1662063988186493440 +1662063988231494400 +1662063988273495296 +1662063988318496256 +1662063988360497152 +1662063988402498048 +1662063988441498880 +1662063988483499776 +1662063988525500672 +1662063988567501568 +1662063988609502464 +1662063988651503360 +1662063988696504320 +1662063988738505216 +1662063988783506176 +1662063988825507072 +1662063988879508224 +1662063988921509120 +1662063988963510016 +1662063989008510976 +1662063989050511872 +1662063989092512768 +1662063989140513792 +1662063989185514752 +1662063989227515648 +1662063989269516544 +1662063989317517568 +1662063989362518528 +1662063989404519424 +1662063989449520384 +1662063989491521280 +1662063989533522176 +1662063989578523136 +1662063989623524096 +1662063989665524992 +1662063989707525888 +1662063989755526912 +1662063989797527808 +1662063989839528704 +1662063989881529600 +1662063989926530560 +1662063989971531520 +1662063990016532480 +1662063990055533312 +1662063990097534208 +1662063990139535104 +1662063990181536000 +1662063990223536896 +1662063990265537792 +1662063990307538688 +1662063990349539584 +1662063990391540480 +1662063990439541504 +1662063990481542400 +1662063990526543360 +1662063990571544320 +1662063990610545152 +1662063990652546048 +1662063990694546944 +1662063990739547904 +1662063990784548864 +1662063990826549760 +1662063990874550784 +1662063990916551680 +1662063990958552576 +1662063991003553536 +1662063991045554432 +1662063991087555328 +1662063991135556352 +1662063991183557376 +1662063991231558400 +1662063991270559232 +1662063991318560256 +1662063991360561152 +1662063991405562112 +1662063991450563072 +1662063991492563968 +1662063991540564992 +1662063991579565824 +1662063991618566656 +1662063991666567680 +1662063991708568576 +1662063991753569536 +1662063991801570560 +1662063991843571456 +1662063991888572416 +1662063991930573312 +1662063991975574272 +1662063992020575232 +1662063992065576192 +1662063992113577216 +1662063992158578176 +1662063992197579008 +1662063992245580032 +1662063992284580864 +1662063992332581888 +1662063992374582784 +1662063992422583808 +1662063992470584832 +1662063992521585920 +1662063992563586816 +1662063992602587648 +1662063992647588608 +1662063992692589568 +1662063992740590592 +1662063992785591552 +1662063992836592640 +1662063992875593472 +1662063992917594368 +1662063992962595328 +1662063993004596224 +1662063993049597184 +1662063993094598144 +1662063993139599104 +1662063993178599936 +1662063993223600896 +1662063993262601728 +1662063993304602624 +1662063993349603584 +1662063993388604416 +1662063993430605312 +1662063993475606272 +1662063993517607168 +1662063993559608064 +1662063993601608960 +1662063993649609984 +1662063993691610880 +1662063993733611776 +1662063993775612672 +1662063993826613760 +1662063993865614592 +1662063993907615488 +1662063993949616384 +1662063994000617472 +1662063994045618432 +1662063994084619264 +1662063994126620160 +1662063994162620928 +1662063994207621888 +1662063994255622912 +1662063994303623936 +1662063994345624832 +1662063994399625984 +1662063994444626944 +1662063994486627840 +1662063994525628672 +1662063994573629696 +1662063994621630720 +1662063994669631744 +1662063994711632640 +1662063994756633600 +1662063994798634496 +1662063994846635520 +1662063994888636416 +1662063994939637504 +1662063994990638592 +1662063995032639488 +1662063995077640448 +1662063995119641344 +1662063995164642304 +1662063995209643264 +1662063995254644224 +1662063995299645184 +1662063995347646208 +1662063995389647104 +1662063995434648064 +1662063995479649024 +1662063995527650048 +1662063995569650944 +1662063995608651776 +1662063995650652672 +1662063995695653632 +1662063995737654528 +1662063995785655552 +1662063995830656512 +1662063995872657408 +1662063995914658304 +1662063995953659136 +1662063995998660096 +1662063996040660992 +1662063996085661952 +1662063996133662976 +1662063996181664000 +1662063996229665024 +1662063996283666176 +1662063996325667072 +1662063996373668096 +1662063996412668928 +1662063996463670016 +1662063996508670976 +1662063996550671872 +1662063996592672768 +1662063996637673728 +1662063996679674624 +1662063996730675712 +1662063996775676672 +1662063996817677568 +1662063996859678464 +1662063996904679424 +1662063996952680448 +1662063996997681408 +1662063997048682496 +1662063997087683328 +1662063997126684160 +1662063997177685248 +1662063997222686208 +1662063997264687104 +1662063997306688000 +1662063997345688832 +1662063997396689920 +1662063997444690944 +1662063997486691840 +1662063997531692800 +1662063997573693696 +1662063997621694720 +1662063997666695680 +1662063997708696576 +1662063997750697472 +1662063997795698432 +1662063997840699392 +1662063997888700416 +1662063997933701376 +1662063997975702272 +1662063998020703232 +1662063998062704128 +1662063998107705088 +1662063998149705984 +1662063998200707072 +1662063998242707968 +1662063998287708928 +1662063998335709952 +1662063998377710848 +1662063998428711936 +1662063998473712896 +1662063998527714048 +1662063998575715072 +1662063998626716160 +1662063998677717248 +1662063998725718272 +1662063998770719232 +1662063998812720128 +1662063998854721024 +1662063998896721920 +1662063998944722944 +1662063998986723840 +1662063999028724736 +1662063999079725824 +1662063999121726720 +1662063999163727616 +1662063999208728576 +1662063999250729472 +1662063999292730368 +1662063999334731264 +1662063999385732352 +1662063999433733376 +1662063999475734272 +1662063999517735168 +1662063999559736064 +1662063999604737024 +1662063999646737920 +1662063999688738816 +1662063999730739712 +1662063999769740544 +1662063999811741440 +1662063999856742400 +1662063999904743424 +1662063999946744320 +1662063999988745216 +1662064000027746048 +1662064000069746944 +1662064000114747904 +1662064000156748800 +1662064000201749760 +1662064000246750720 +1662064000291751680 +1662064000333752576 +1662064000378753536 +1662064000420754432 +1662064000465755392 +1662064000510756352 +1662064000555757312 +1662064000603758336 +1662064000648759296 +1662064000687760128 +1662064000729761024 +1662064000771761920 +1662064000816762880 +1662064000864763904 +1662064000906764800 +1662064000948765696 +1662064000993766656 +1662064001044767744 +1662064001086768640 +1662064001128769536 +1662064001173770496 +1662064001215771392 +1662064001260772352 +1662064001308773376 +1662064001350774272 +1662064001398775296 +1662064001440776192 +1662064001488777216 +1662064001533778176 +1662064001578779136 +1662064001629780224 +1662064001671781120 +1662064001713782016 +1662064001755782912 +1662064001797783808 +1662064001839784704 +1662064001881785600 +1662064001929786624 +1662064001971787520 +1662064002013788416 +1662064002055789312 +1662064002097790208 +1662064002142791168 +1662064002187792128 +1662064002229793024 +1662064002274793984 +1662064002319794944 +1662064002373796096 +1662064002415796992 +1662064002457797888 +1662064002499798784 +1662064002550799872 +1662064002592800768 +1662064002634801664 +1662064002673802496 +1662064002718803456 +1662064002760804352 +1662064002805805312 +1662064002847806208 +1662064002889807104 +1662064002931808000 +1662064002979809024 +1662064003030810112 +1662064003075811072 +1662064003120812032 +1662064003168813056 +1662064003207813888 +1662064003249814784 +1662064003294815744 +1662064003342816768 +1662064003390817792 +1662064003435818752 +1662064003477819648 +1662064003522820608 +1662064003564821504 +1662064003606822400 +1662064003654823424 +1662064003699824384 +1662064003747825408 +1662064003789826304 +1662064003828827136 +1662064003873828096 +1662064003915828992 +1662064003960829952 +1662064004008830976 +1662064004053831936 +1662064004092832768 +1662064004134833664 +1662064004176834560 +1662064004218835456 +1662064004266836480 +1662064004308837376 +1662064004350838272 +1662064004392839168 +1662064004434840064 +1662064004485841152 +1662064004527842048 +1662064004575843072 +1662064004617843968 +1662064004668845056 +1662064004713846016 +1662064004758846976 +1662064004800847872 +1662064004842848768 +1662064004887849728 +1662064004929850624 +1662064004971851520 +1662064005019852544 +1662064005064853504 +1662064005115854592 +1662064005160855552 +1662064005202856448 +1662064005247857408 +1662064005289858304 +1662064005331859200 +1662064005373860096 +1662064005424861184 +1662064005466862080 +1662064005511863040 +1662064005553863936 +1662064005598864896 +1662064005640865792 +1662064005682866688 +1662064005736867840 +1662064005781868800 +1662064005826869760 +1662064005871870720 +1662064005910871552 +1662064005955872512 +1662064006000873472 +1662064006045874432 +1662064006090875392 +1662064006132876288 +1662064006177877248 +1662064006222878208 +1662064006264879104 +1662064006309880064 +1662064006360881152 +1662064006402882048 +1662064006444882944 +1662064006489883904 +1662064006531884800 +1662064006576885760 +1662064006621886720 +1662064006669887744 +1662064006717888768 +1662064006762889728 +1662064006804890624 +1662064006855891712 +1662064006897892608 +1662064006942893568 +1662064006990894592 +1662064007032895488 +1662064007077896448 +1662064007119897344 +1662064007161898240 +1662064007206899200 +1662064007248900096 +1662064007290900992 +1662064007332901888 +1662064007374902784 +1662064007425903872 +1662064007464904704 +1662064007512905728 +1662064007557906688 +1662064007602907648 +1662064007647908608 +1662064007692909568 +1662064007746910720 +1662064007791911680 +1662064007833912576 +1662064007878913536 +1662064007920914432 +1662064007962915328 +1662064008004916224 +1662064008046917120 +1662064008091918080 +1662064008133918976 +1662064008175919872 +1662064008220920832 +1662064008262921728 +1662064008307922688 +1662064008352923648 +1662064008394924544 +1662064008436925440 +1662064008478926336 +1662064008520927232 +1662064008565928192 +1662064008610929152 +1662064008664930304 +1662064008709931264 +1662064008754932224 +1662064008796933120 +1662064008844934144 +1662064008889935104 +1662064008934936064 +1662064008985937152 +1662064009027938048 +1662064009075939072 +1662064009120940032 +1662064009162940928 +1662064009207941888 +1662064009249942784 +1662064009288943616 +1662064009339944704 +1662064009381945600 +1662064009423946496 +1662064009465947392 +1662064009510948352 +1662064009558949376 +1662064009597950208 +1662064009636951040 +1662064009678951936 +1662064009717952768 +1662064009762953728 +1662064009807954688 +1662064009849955584 +1662064009897956608 +1662064009948957696 +1662064009990958592 +1662064010035959552 +1662064010077960448 +1662064010122961408 +1662064010170962432 +1662064010215963392 +1662064010260964352 +1662064010317965568 +1662064010365966592 +1662064010410967552 +1662064010458968576 +1662064010500969472 +1662064010542970368 +1662064010587971328 +1662064010629972224 +1662064010674973184 +1662064010719974144 +1662064010767975168 +1662064010809976064 +1662064010857977088 +1662064010902978048 +1662064010947979008 +1662064010989979904 +1662064011031980800 +1662064011073981696 +1662064011121982720 +1662064011172983808 +1662064011214984704 +1662064011259985664 +1662064011307986688 +1662064011346987520 +1662064011391988480 +1662064011436989440 +1662064011478990336 +1662064011523991296 +1662064011568992256 +1662064011610993152 +1662064011655994112 +1662064011700995072 +1662064011748996096 +1662064011790996992 +1662064011835997952 +1662064011877998848 +1662064011919999744 +1662064011965000704 +1662064012010001664 +1662064012049002496 +1662064012091003392 +1662064012133004288 +1662064012175005184 +1662064012217006080 +1662064012262007040 +1662064012301007872 +1662064012346008832 +1662064012391009792 +1662064012433010688 +1662064012481011712 +1662064012526012672 +1662064012568013568 +1662064012610014464 +1662064012652015360 +1662064012694016256 +1662064012748017408 +1662064012790018304 +1662064012832019200 +1662064012874020096 +1662064012916020992 +1662064012961021952 +1662064013015023104 +1662064013060024064 +1662064013105025024 +1662064013150025984 +1662064013192026880 +1662064013237027840 +1662064013279028736 +1662064013321029632 +1662064013369030656 +1662064013411031552 +1662064013456032512 +1662064013501033472 +1662064013543034368 +1662064013585035264 +1662064013630036224 +1662064013678037248 +1662064013720038144 +1662064013768039168 +1662064013810040064 +1662064013855041024 +1662064013900041984 +1662064013948043008 +1662064013993043968 +1662064014038044928 +1662064014089046016 +1662064014134046976 +1662064014179047936 +1662064014224048896 +1662064014275049984 +1662064014314050816 +1662064014356051712 +1662064014401052672 +1662064014446053632 +1662064014488054528 +1662064014533055488 +1662064014578056448 +1662064014623057408 +1662064014662058240 +1662064014710059264 +1662064014758060288 +1662064014797061120 +1662064014839062016 +1662064014887063040 +1662064014935064064 +1662064014980065024 +1662064015031066112 +1662064015082067200 +1662064015124068096 +1662064015166068992 +1662064015211069952 +1662064015259070976 +1662064015304071936 +1662064015349072896 +1662064015391073792 +1662064015436074752 +1662064015478075648 +1662064015520076544 +1662064015574077696 +1662064015634078976 +1662064015685080064 +1662064015727080960 +1662064015769081856 +1662064015811082752 +1662064015850083584 +1662064015889084416 +1662064015931085312 +1662064015973086208 +1662064016018087168 +1662064016060088064 +1662064016111089152 +1662064016153090048 +1662064016198091008 +1662064016240091904 +1662064016294093056 +1662064016342094080 +1662064016387095040 +1662064016435096064 +1662064016477096960 +1662064016522097920 +1662064016564098816 +1662064016609099776 +1662064016660100864 +1662064016705101824 +1662064016750102784 +1662064016792103680 +1662064016837104640 +1662064016879105536 +1662064016924106496 +1662064016966107392 +1662064017011108352 +1662064017053109248 +1662064017095110144 +1662064017140111104 +1662064017182112000 +1662064017227112960 +1662064017269113856 +1662064017311114752 +1662064017353115648 +1662064017395116544 +1662064017437117440 +1662064017482118400 +1662064017524119296 +1662064017566120192 +1662064017608121088 +1662064017656122112 +1662064017704123136 +1662064017749124096 +1662064017791124992 +1662064017836125952 +1662064017878126848 +1662064017920127744 +1662064017965128704 +1662064018010129664 +1662064018055130624 +1662064018103131648 +1662064018145132544 +1662064018187133440 +1662064018232134400 +1662064018289135616 +1662064018334136576 +1662064018382137600 +1662064018421138432 +1662064018463139328 +1662064018505140224 +1662064018550141184 +1662064018595142144 +1662064018640143104 +1662064018682144000 +1662064018721144832 +1662064018766145792 +1662064018808146688 +1662064018850147584 +1662064018892148480 +1662064018934149376 +1662064018976150272 +1662064019024151296 +1662064019066152192 +1662064019111153152 +1662064019153154048 +1662064019198155008 +1662064019243155968 +1662064019288156928 +1662064019327157760 +1662064019378158848 +1662064019417159680 +1662064019462160640 +1662064019507161600 +1662064019552162560 +1662064019594163456 +1662064019636164352 +1662064019672165120 +1662064019717166080 +1662064019756166912 +1662064019798167808 +1662064019843168768 +1662064019888169728 +1662064019936170752 +1662064019978171648 +1662064020020172544 +1662064020065173504 +1662064020107174400 +1662064020152175360 +1662064020194176256 +1662064020239177216 +1662064020284178176 +1662064020329179136 +1662064020377180160 +1662064020428181248 +1662064020479182336 +1662064020521183232 +1662064020572184320 +1662064020614185216 +1662064020662186240 +1662064020707187200 +1662064020752188160 +1662064020794189056 +1662064020836189952 +1662064020878190848 +1662064020923191808 +1662064020968192768 +1662064021013193728 +1662064021058194688 +1662064021100195584 +1662064021154196736 +1662064021205197824 +1662064021247198720 +1662064021289199616 +1662064021331200512 +1662064021373201408 +1662064021421202432 +1662064021463203328 +1662064021508204288 +1662064021553205248 +1662064021595206144 +1662064021637207040 +1662064021682208000 +1662064021724208896 +1662064021766209792 +1662064021811210752 +1662064021853211648 +1662064021901212672 +1662064021949213696 +1662064021994214656 +1662064022036215552 +1662064022081216512 +1662064022120217344 +1662064022162218240 +1662064022210219264 +1662064022255220224 +1662064022297221120 +1662064022342222080 +1662064022384222976 +1662064022432224000 +1662064022474224896 +1662064022525225984 +1662064022567226880 +1662064022612227840 +1662064022660228864 +1662064022702229760 +1662064022747230720 +1662064022789231616 +1662064022831232512 +1662064022888233728 +1662064022930234624 +1662064022978235648 +1662064023017236480 +1662064023065237504 +1662064023116238592 +1662064023155239424 +1662064023197240320 +1662064023239241216 +1662064023281242112 +1662064023323243008 +1662064023365243904 +1662064023407244800 +1662064023449245696 +1662064023500246784 +1662064023542247680 +1662064023584248576 +1662064023632249600 +1662064023677250560 +1662064023725251584 +1662064023767252480 +1662064023809253376 +1662064023857254400 +1662064023902255360 +1662064023944256256 +1662064023989257216 +1662064024031258112 +1662064024076259072 +1662064024127260160 +1662064024175261184 +1662064024217262080 +1662064024262263040 +1662064024304263936 +1662064024352264960 +1662064024397265920 +1662064024448267008 +1662064024496268032 +1662064024538268928 +1662064024583269888 +1662064024634270976 +1662064024679271936 +1662064024727272960 +1662064024778274048 +1662064024820274944 +1662064024871276032 +1662064024913276928 +1662064024955277824 +1662064024997278720 +1662064025039279616 +1662064025090280704 +1662064025129281536 +1662064025177282560 +1662064025228283648 +1662064025270284544 +1662064025312285440 +1662064025354286336 +1662064025396287232 +1662064025456288512 +1662064025507289600 +1662064025549290496 +1662064025594291456 +1662064025636292352 +1662064025678293248 +1662064025720294144 +1662064025768295168 +1662064025807296000 +1662064025852296960 +1662064025891297792 +1662064025933298688 +1662064025972299520 +1662064026020300544 +1662064026059301376 +1662064026101302272 +1662064026152303360 +1662064026197304320 +1662064026242305280 +1662064026284306176 +1662064026326307072 +1662064026368307968 +1662064026413308928 +1662064026455309824 +1662064026500310784 +1662064026539311616 +1662064026578312448 +1662064026620313344 +1662064026659314176 +1662064026701315072 +1662064026740315904 +1662064026785316864 +1662064026833317888 +1662064026878318848 +1662064026917319680 +1662064026962320640 +1662064027007321600 +1662064027061322752 +1662064027103323648 +1662064027142324480 +1662064027184325376 +1662064027226326272 +1662064027271327232 +1662064027313328128 +1662064027355329024 +1662064027397329920 +1662064027442330880 +1662064027484331776 +1662064027532332800 +1662064027571333632 +1662064027613334528 +1662064027655335424 +1662064027700336384 +1662064027745337344 +1662064027787338240 +1662064027832339200 +1662064027877340160 +1662064027922341120 +1662064027964342016 +1662064028006342912 +1662064028051343872 +1662064028093344768 +1662064028144345856 +1662064028192346880 +1662064028234347776 +1662064028288348928 +1662064028333349888 +1662064028378350848 +1662064028423351808 +1662064028462352640 +1662064028510353664 +1662064028549354496 +1662064028591355392 +1662064028636356352 +1662064028678357248 +1662064028723358208 +1662064028768359168 +1662064028810360064 +1662064028849360896 +1662064028891361792 +1662064028933362688 +1662064028975363584 +1662064029029364736 +1662064029071365632 +1662064029113366528 +1662064029158367488 +1662064029203368448 +1662064029245369344 +1662064029284370176 +1662064029329371136 +1662064029374372096 +1662064029416372992 +1662064029458373888 +1662064029503374848 +1662064029545375744 +1662064029593376768 +1662064029635377664 +1662064029683378688 +1662064029725379584 +1662064029767380480 +1662064029818381568 +1662064029866382592 +1662064029908383488 +1662064029950384384 +1662064029998385408 +1662064030052386560 +1662064030097387520 +1662064030145388544 +1662064030196389632 +1662064030238390528 +1662064030286391552 +1662064030331392512 +1662064030385393664 +1662064030430394624 +1662064030469395456 +1662064030514396416 +1662064030574397696 +1662064030616398592 +1662064030658399488 +1662064030700400384 +1662064030748401408 +1662064030793402368 +1662064030841403392 +1662064030886404352 +1662064030928405248 +1662064030979406336 +1662064031024407296 +1662064031066408192 +1662064031114409216 +1662064031156410112 +1662064031204411136 +1662064031246412032 +1662064031291412992 +1662064031333413888 +1662064031378414848 +1662064031417415680 +1662064031459416576 +1662064031519417856 +1662064031564418816 +1662064031612419840 +1662064031654420736 +1662064031699421696 +1662064031747422720 +1662064031798423808 +1662064031846424832 +1662064031888425728 +1662064031930426624 +1662064031972427520 +1662064032014428416 +1662064032056429312 +1662064032098430208 +1662064032143431168 +1662064032188432128 +1662064032230433024 +1662064032272433920 +1662064032314434816 +1662064032356435712 +1662064032401436672 +1662064032443437568 +1662064032488438528 +1662064032530439424 +1662064032584440576 +1662064032623441408 +1662064032665442304 +1662064032716443392 +1662064032758444288 +1662064032800445184 +1662064032845446144 +1662064032899447296 +1662064032947448320 +1662064032989449216 +1662064033031450112 +1662064033070450944 +1662064033112451840 +1662064033154452736 +1662064033205453824 +1662064033247454720 +1662064033295455744 +1662064033337456640 +1662064033385457664 +1662064033427458560 +1662064033472459520 +1662064033514460416 +1662064033559461376 +1662064033607462400 +1662064033652463360 +1662064033694464256 +1662064033736465152 +1662064033781466112 +1662064033826467072 +1662064033868467968 +1662064033910468864 +1662064033955469824 +1662064033997470720 +1662064034042471680 +1662064034084472576 +1662064034129473536 +1662064034168474368 +1662064034210475264 +1662064034252476160 +1662064034294477056 +1662064034336477952 +1662064034378478848 +1662064034417479680 +1662064034459480576 +1662064034504481536 +1662064034549482496 +1662064034597483520 +1662064034636484352 +1662064034681485312 +1662064034723486208 +1662064034765487104 +1662064034810488064 +1662064034855489024 +1662064034897489920 +1662064034936490752 +1662064034984491776 +1662064035032492800 +1662064035074493696 +1662064035122494720 +1662064035164495616 +1662064035206496512 +1662064035248497408 +1662064035290498304 +1662064035332499200 +1662064035374500096 +1662064035419501056 +1662064035458501888 +1662064035500502784 +1662064035542503680 +1662064035584504576 +1662064035626505472 +1662064035671506432 +1662064035713507328 +1662064035758508288 +1662064035806509312 +1662064035854510336 +1662064035896511232 +1662064035947512320 +1662064035995513344 +1662064036037514240 +1662064036085515264 +1662064036130516224 +1662064036172517120 +1662064036214518016 +1662064036256518912 +1662064036310520064 +1662064036352520960 +1662064036400521984 +1662064036445522944 +1662064036487523840 +1662064036529524736 +1662064036571525632 +1662064036613526528 +1662064036658527488 +1662064036697528320 +1662064036739529216 +1662064036787530240 +1662064036835531264 +1662064036877532160 +1662064036922533120 +1662064036967534080 +1662064037015535104 +1662064037057536000 +1662064037099536896 +1662064037147537920 +1662064037189538816 +1662064037234539776 +1662064037282540800 +1662064037324541696 +1662064037369542656 +1662064037408543488 +1662064037450544384 +1662064037492545280 +1662064037534546176 +1662064037576547072 +1662064037621548032 +1662064037663548928 +1662064037705549824 +1662064037750550784 +1662064037795551744 +1662064037843552768 +1662064037885553664 +1662064037930554624 +1662064037972555520 +1662064038014556416 +1662064038056557312 +1662064038104558336 +1662064038149559296 +1662064038191560192 +1662064038239561216 +1662064038281562112 +1662064038323563008 +1662064038365563904 +1662064038413564928 +1662064038455565824 +1662064038497566720 +1662064038542567680 +1662064038590568704 +1662064038638569728 +1662064038680570624 +1662064038719571456 +1662064038761572352 +1662064038806573312 +1662064038851574272 +1662064038896575232 +1662064038938576128 +1662064038983577088 +1662064039028578048 +1662064039076579072 +1662064039118579968 +1662064039160580864 +1662064039205581824 +1662064039253582848 +1662064039295583744 +1662064039340584704 +1662064039382585600 +1662064039424586496 +1662064039469587456 +1662064039508588288 +1662064039550589184 +1662064039595590144 +1662064039637591040 +1662064039685592064 +1662064039727592960 +1662064039766593792 +1662064039811594752 +1662064039853595648 +1662064039898596608 +1662064039940597504 +1662064039982598400 +1662064040024599296 +1662064040072600320 +1662064040114601216 +1662064040162602240 +1662064040207603200 +1662064040252604160 +1662064040303605248 +1662064040348606208 +1662064040390607104 +1662064040435608064 +1662064040477608960 +1662064040519609856 +1662064040561610752 +1662064040603611648 +1662064040642612480 +1662064040699613696 +1662064040738614528 +1662064040777615360 +1662064040819616256 +1662064040864617216 +1662064040906618112 +1662064040945618944 +1662064040990619904 +1662064041032620800 +1662064041074621696 +1662064041122622720 +1662064041164623616 +1662064041209624576 +1662064041254625536 +1662064041296626432 +1662064041347627520 +1662064041395628544 +1662064041443629568 +1662064041488630528 +1662064041533631488 +1662064041584632576 +1662064041629633536 +1662064041671634432 +1662064041713635328 +1662064041755636224 +1662064041806637312 +1662064041845638144 +1662064041887639040 +1662064041932640000 +1662064041977640960 +1662064042025641984 +1662064042076643072 +1662064042121644032 +1662064042163644928 +1662064042205645824 +1662064042247646720 +1662064042292647680 +1662064042334648576 +1662064042379649536 +1662064042424650496 +1662064042466651392 +1662064042508652288 +1662064042553653248 +1662064042598654208 +1662064042646655232 +1662064042691656192 +1662064042733657088 +1662064042778658048 +1662064042829659136 +1662064042871660032 +1662064042916660992 +1662064042964662016 +1662064043015663104 +1662064043057664000 +1662064043108665088 +1662064043153666048 +1662064043198667008 +1662064043240667904 +1662064043288668928 +1662064043330669824 +1662064043378670848 +1662064043423671808 +1662064043471672832 +1662064043513673728 +1662064043558674688 +1662064043603675648 +1662064043657676800 +1662064043705677824 +1662064043750678784 +1662064043792679680 +1662064043843680768 +1662064043882681600 +1662064043927682560 +1662064043966683392 +1662064044011684352 +1662064044062685440 +1662064044107686400 +1662064044146687232 +1662064044197688320 +1662064044239689216 +1662064044290690304 +1662064044332691200 +1662064044383692288 +1662064044431693312 +1662064044473694208 +1662064044515695104 +1662064044563696128 +1662064044602696960 +1662064044647697920 +1662064044698699008 +1662064044743699968 +1662064044788700928 +1662064044830701824 +1662064044872702720 +1662064044923703808 +1662064044965704704 +1662064045016705792 +1662064045058706688 +1662064045100707584 +1662064045145708544 +1662064045187709440 +1662064045238710528 +1662064045280711424 +1662064045328712448 +1662064045370713344 +1662064045415714304 +1662064045454715136 +1662064045496716032 +1662064045544717056 +1662064045589718016 +1662064045634718976 +1662064045679719936 +1662064045721720832 +1662064045763721728 +1662064045805722624 +1662064045850723584 +1662064045895724544 +1662064045940725504 +1662064045982726400 +1662064046027727360 +1662064046075728384 +1662064046123729408 +1662064046165730304 +1662064046207731200 +1662064046258732288 +1662064046303733248 +1662064046351734272 +1662064046396735232 +1662064046441736192 +1662064046492737280 +1662064046534738176 +1662064046576739072 +1662064046621740032 +1662064046666740992 +1662064046711741952 +1662064046756742912 +1662064046804743936 +1662064046846744832 +1662064046885745664 +1662064046927746560 +1662064046969747456 +1662064047014748416 +1662064047056749312 +1662064047101750272 +1662064047149751296 +1662064047194752256 +1662064047239753216 +1662064047284754176 +1662064047326755072 +1662064047371756032 +1662064047419757056 +1662064047464758016 +1662064047509758976 +1662064047554759936 +1662064047605761024 +1662064047653762048 +1662064047707763200 +1662064047752764160 +1662064047794765056 +1662064047836765952 +1662064047878766848 +1662064047923767808 +1662064047965768704 +1662064048010769664 +1662064048052770560 +1662064048094771456 +1662064048142772480 +1662064048184773376 +1662064048226774272 +1662064048277775360 +1662064048319776256 +1662064048361777152 +1662064048406778112 +1662064048448779008 +1662064048493779968 +1662064048535780864 +1662064048577781760 +1662064048619782656 +1662064048664783616 +1662064048706784512 +1662064048754785536 +1662064048793786368 +1662064048832787200 +1662064048877788160 +1662064048922789120 +1662064048967790080 +1662064049009790976 +1662064049048791808 +1662064049096792832 +1662064049141793792 +1662064049186794752 +1662064049234795776 +1662064049276796672 +1662064049318797568 +1662064049366798592 +1662064049408799488 +1662064049450800384 +1662064049495801344 +1662064049537802240 +1662064049576803072 +1662064049618803968 +1662064049660804864 +1662064049702805760 +1662064049744806656 +1662064049789807616 +1662064049834808576 +1662064049876809472 +1662064049918810368 +1662064049960811264 +1662064050002812160 +1662064050053813248 +1662064050095814144 +1662064050137815040 +1662064050179815936 +1662064050221816832 +1662064050263817728 +1662064050305818624 +1662064050347819520 +1662064050389820416 +1662064050434821376 +1662064050482822400 +1662064050524823296 +1662064050584824576 +1662064050626825472 +1662064050668826368 +1662064050713827328 +1662064050755828224 +1662064050797829120 +1662064050845830144 +1662064050887831040 +1662064050932832000 +1662064050977832960 +1662064051016833792 +1662064051070834944 +1662064051115835904 +1662064051157836800 +1662064051199837696 +1662064051241838592 +1662064051283839488 +1662064051325840384 +1662064051367841280 +1662064051409842176 +1662064051454843136 +1662064051499844096 +1662064051544845056 +1662064051592846080 +1662064051631846912 +1662064051673847808 +1662064051715848704 +1662064051763849728 +1662064051808850688 +1662064051853851648 +1662064051901852672 +1662064051943853568 +1662064051985854464 +1662064052036855552 +1662064052081856512 +1662064052129857536 +1662064052171858432 +1662064052213859328 +1662064052261860352 +1662064052303861248 +1662064052345862144 +1662064052387863040 +1662064052438864128 +1662064052483865088 +1662064052525865984 +1662064052573867008 +1662064052624868096 +1662064052669869056 +1662064052714870016 +1662064052759870976 +1662064052795871744 +1662064052840872704 +1662064052885873664 +1662064052924874496 +1662064052969875456 +1662064053011876352 +1662064053056877312 +1662064053098878208 +1662064053143879168 +1662064053188880128 +1662064053233881088 +1662064053278882048 +1662064053323883008 +1662064053365883904 +1662064053407884800 +1662064053452885760 +1662064053491886592 +1662064053533887488 +1662064053575888384 +1662064053614889216 +1662064053659890176 +1662064053698891008 +1662064053746892032 +1662064053791892992 +1662064053842894080 +1662064053884894976 +1662064053929895936 +1662064053974896896 +1662064054019897856 +1662064054061898752 +1662064054103899648 +1662064054142900480 +1662064054184901376 +1662064054223902208 +1662064054265903104 +1662064054307904000 +1662064054355905024 +1662064054409906176 +1662064054457907200 +1662064054502908160 +1662064054541908992 +1662064054589910016 +1662064054631910912 +1662064054676911872 +1662064054727912960 +1662064054772913920 +1662064054814914816 +1662064054865915904 +1662064054910916864 +1662064054946917632 +1662064054997918720 +1662064055042919680 +1662064055090920704 +1662064055138921728 +1662064055180922624 +1662064055225923584 +1662064055270924544 +1662064055315925504 +1662064055360926464 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_light.txt b/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_light.txt new file mode 100644 index 0000000000..b9447370b4 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_light.txt @@ -0,0 +1,2605 @@ +1662121584099220736 +1662121584144221696 +1662121584186222592 +1662121584234223616 +1662121584279224576 +1662121584321225472 +1662121584369226496 +1662121584417227520 +1662121584459228416 +1662121584498229248 +1662121584540230144 +1662121584582231040 +1662121584624231936 +1662121584669232896 +1662121584717233920 +1662121584762234880 +1662121584807235840 +1662121584855236864 +1662121584900237824 +1662121584942238720 +1662121584987239680 +1662121585032240640 +1662121585074241536 +1662121585119242496 +1662121585161243392 +1662121585203244288 +1662121585251245312 +1662121585296246272 +1662121585338247168 +1662121585389248256 +1662121585434249216 +1662121585476250112 +1662121585524251136 +1662121585575252224 +1662121585617253120 +1662121585671254272 +1662121585716255232 +1662121585758256128 +1662121585803257088 +1662121585845257984 +1662121585887258880 +1662121585932259840 +1662121585977260800 +1662121586019261696 +1662121586061262592 +1662121586106263552 +1662121586151264512 +1662121586193265408 +1662121586235266304 +1662121586277267200 +1662121586319268096 +1662121586364269056 +1662121586409270016 +1662121586460271104 +1662121586502272000 +1662121586553273088 +1662121586595273984 +1662121586634274816 +1662121586679275776 +1662121586724276736 +1662121586766277632 +1662121586823278848 +1662121586868279808 +1662121586916280832 +1662121586961281792 +1662121587003282688 +1662121587048283648 +1662121587093284608 +1662121587135285504 +1662121587177286400 +1662121587216287232 +1662121587258288128 +1662121587303289088 +1662121587345289984 +1662121587387290880 +1662121587429291776 +1662121587474292736 +1662121587522293760 +1662121587567294720 +1662121587615295744 +1662121587657296640 +1662121587702297600 +1662121587747298560 +1662121587789299456 +1662121587834300416 +1662121587876301312 +1662121587921302272 +1662121587966303232 +1662121588008304128 +1662121588053305088 +1662121588101306112 +1662121588143307008 +1662121588197308160 +1662121588245309184 +1662121588290310144 +1662121588332311040 +1662121588383312128 +1662121588428313088 +1662121588470313984 +1662121588512314880 +1662121588557315840 +1662121588602316800 +1662121588644317696 +1662121588686318592 +1662121588737319680 +1662121588779320576 +1662121588821321472 +1662121588872322560 +1662121588914323456 +1662121588962324480 +1662121589004325376 +1662121589043326208 +1662121589088327168 +1662121589130328064 +1662121589172328960 +1662121589214329856 +1662121589265330944 +1662121589307331840 +1662121589349332736 +1662121589397333760 +1662121589439334656 +1662121589478335488 +1662121589520336384 +1662121589565337344 +1662121589604338176 +1662121589646339072 +1662121589691340032 +1662121589739341056 +1662121589784342016 +1662121589826342912 +1662121589871343872 +1662121589919344896 +1662121589961345792 +1662121590003346688 +1662121590051347712 +1662121590093348608 +1662121590135349504 +1662121590183350528 +1662121590228351488 +1662121590279352576 +1662121590321353472 +1662121590360354304 +1662121590405355264 +1662121590447356160 +1662121590492357120 +1662121590540358144 +1662121590579358976 +1662121590621359872 +1662121590663360768 +1662121590705361664 +1662121590747362560 +1662121590792363520 +1662121590837364480 +1662121590885365504 +1662121590927366400 +1662121590969367296 +1662121591014368256 +1662121591062369280 +1662121591107370240 +1662121591155371264 +1662121591194372096 +1662121591236372992 +1662121591284374016 +1662121591329374976 +1662121591374375936 +1662121591428377088 +1662121591473378048 +1662121591518379008 +1662121591560379904 +1662121591611380992 +1662121591650381824 +1662121591701382912 +1662121591743383808 +1662121591785384704 +1662121591830385664 +1662121591875386624 +1662121591917387520 +1662121591962388480 +1662121592007389440 +1662121592049390336 +1662121592091391232 +1662121592133392128 +1662121592175393024 +1662121592226394112 +1662121592268395008 +1662121592313395968 +1662121592352396800 +1662121592391397632 +1662121592439398656 +1662121592496399872 +1662121592538400768 +1662121592583401728 +1662121592625402624 +1662121592670403584 +1662121592712404480 +1662121592751405312 +1662121592799406336 +1662121592844407296 +1662121592883408128 +1662121592925409024 +1662121592970409984 +1662121593024411136 +1662121593069412096 +1662121593114413056 +1662121593156413952 +1662121593201414912 +1662121593246415872 +1662121593294416896 +1662121593342417920 +1662121593390418944 +1662121593444420096 +1662121593486420992 +1662121593531421952 +1662121593576422912 +1662121593627424000 +1662121593672424960 +1662121593726426112 +1662121593777427200 +1662121593816428032 +1662121593855428864 +1662121593900429824 +1662121593948430848 +1662121594005432064 +1662121594050433024 +1662121594092433920 +1662121594143435008 +1662121594185435904 +1662121594230436864 +1662121594278437888 +1662121594323438848 +1662121594371439872 +1662121594416440832 +1662121594461441792 +1662121594503442688 +1662121594551443712 +1662121594599444736 +1662121594641445632 +1662121594683446528 +1662121594725447424 +1662121594770448384 +1662121594812449280 +1662121594857450240 +1662121594899451136 +1662121594941452032 +1662121594983452928 +1662121595034454016 +1662121595076454912 +1662121595124455936 +1662121595184457216 +1662121595226458112 +1662121595274459136 +1662121595316460032 +1662121595361460992 +1662121595406461952 +1662121595454462976 +1662121595496463872 +1662121595541464832 +1662121595583465728 +1662121595631466752 +1662121595676467712 +1662121595724468736 +1662121595772469760 +1662121595826470912 +1662121595868471808 +1662121595919472896 +1662121595964473856 +1662121596006474752 +1662121596051475712 +1662121596099476736 +1662121596144477696 +1662121596186478592 +1662121596234479616 +1662121596276480512 +1662121596318481408 +1662121596357482240 +1662121596399483136 +1662121596447484160 +1662121596489485056 +1662121596534486016 +1662121596576486912 +1662121596630488064 +1662121596675489024 +1662121596720489984 +1662121596768491008 +1662121596819492096 +1662121596861492992 +1662121596912494080 +1662121596951494912 +1662121596993495808 +1662121597038496768 +1662121597083497728 +1662121597125498624 +1662121597173499648 +1662121597215500544 +1662121597260501504 +1662121597305502464 +1662121597344503296 +1662121597389504256 +1662121597443505408 +1662121597485506304 +1662121597524507136 +1662121597572508160 +1662121597617509120 +1662121597662510080 +1662121597710511104 +1662121597761512192 +1662121597812513280 +1662121597863514368 +1662121597908515328 +1662121597950516224 +1662121598001517312 +1662121598043518208 +1662121598097519360 +1662121598148520448 +1662121598190521344 +1662121598238522368 +1662121598283523328 +1662121598334524416 +1662121598379525376 +1662121598427526400 +1662121598472527360 +1662121598520528384 +1662121598565529344 +1662121598607530240 +1662121598652531200 +1662121598694532096 +1662121598742533120 +1662121598781533952 +1662121598823534848 +1662121598868535808 +1662121598913536768 +1662121598955537664 +1662121598997538560 +1662121599042539520 +1662121599090540544 +1662121599135541504 +1662121599183542528 +1662121599231543552 +1662121599279544576 +1662121599324545536 +1662121599369546496 +1662121599411547392 +1662121599456548352 +1662121599498549248 +1662121599543550208 +1662121599585551104 +1662121599633552128 +1662121599678553088 +1662121599717553920 +1662121599762554880 +1662121599807555840 +1662121599852556800 +1662121599894557696 +1662121599936558592 +1662121599984559616 +1662121600026560512 +1662121600071561472 +1662121600122562560 +1662121600179563776 +1662121600221564672 +1662121600263565568 +1662121600302566400 +1662121600350567424 +1662121600395568384 +1662121600437569280 +1662121600482570240 +1662121600536571392 +1662121600581572352 +1662121600623573248 +1662121600665574144 +1662121600710575104 +1662121600752576000 +1662121600806577152 +1662121600848578048 +1662121600890578944 +1662121600932579840 +1662121600974580736 +1662121601025581824 +1662121601070582784 +1662121601115583744 +1662121601157584640 +1662121601205585664 +1662121601247586560 +1662121601289587456 +1662121601337588480 +1662121601382589440 +1662121601433590528 +1662121601475591424 +1662121601517592320 +1662121601559593216 +1662121601604594176 +1662121601652595200 +1662121601697596160 +1662121601742597120 +1662121601784598016 +1662121601835599104 +1662121601880600064 +1662121601928601088 +1662121601970601984 +1662121602027603200 +1662121602075604224 +1662121602117605120 +1662121602162606080 +1662121602204606976 +1662121602255608064 +1662121602297608960 +1662121602336609792 +1662121602378610688 +1662121602426611712 +1662121602468612608 +1662121602519613696 +1662121602555614464 +1662121602600615424 +1662121602645616384 +1662121602699617536 +1662121602741618432 +1662121602783619328 +1662121602825620224 +1662121602867621120 +1662121602909622016 +1662121602951622912 +1662121602999623936 +1662121603047624960 +1662121603089625856 +1662121603140626944 +1662121603185627904 +1662121603227628800 +1662121603281629952 +1662121603326630912 +1662121603368631808 +1662121603422632960 +1662121603467633920 +1662121603509634816 +1662121603563635968 +1662121603608636928 +1662121603650637824 +1662121603692638720 +1662121603734639616 +1662121603776640512 +1662121603818641408 +1662121603860642304 +1662121603905643264 +1662121603953644288 +1662121604001645312 +1662121604043646208 +1662121604088647168 +1662121604133648128 +1662121604175649024 +1662121604217649920 +1662121604262650880 +1662121604307651840 +1662121604355652864 +1662121604394653696 +1662121604442654720 +1662121604484655616 +1662121604523656448 +1662121604574657536 +1662121604619658496 +1662121604664659456 +1662121604709660416 +1662121604754661376 +1662121604805662464 +1662121604850663424 +1662121604895664384 +1662121604940665344 +1662121604988666368 +1662121605042667520 +1662121605084668416 +1662121605129669376 +1662121605174670336 +1662121605216671232 +1662121605255672064 +1662121605300673024 +1662121605342673920 +1662121605396675072 +1662121605438675968 +1662121605480676864 +1662121605528677888 +1662121605573678848 +1662121605618679808 +1662121605663680768 +1662121605705681664 +1662121605747682560 +1662121605798683648 +1662121605840684544 +1662121605882685440 +1662121605930686464 +1662121605975687424 +1662121606017688320 +1662121606059689216 +1662121606104690176 +1662121606146691072 +1662121606188691968 +1662121606230692864 +1662121606275693824 +1662121606323694848 +1662121606368695808 +1662121606413696768 +1662121606455697664 +1662121606497698560 +1662121606542699520 +1662121606587700480 +1662121606626701312 +1662121606665702144 +1662121606710703104 +1662121606758704128 +1662121606803705088 +1662121606857706240 +1662121606902707200 +1662121606944708096 +1662121606986708992 +1662121607031709952 +1662121607076710912 +1662121607124711936 +1662121607169712896 +1662121607217713920 +1662121607262714880 +1662121607304715776 +1662121607346716672 +1662121607391717632 +1662121607436718592 +1662121607487719680 +1662121607532720640 +1662121607577721600 +1662121607628722688 +1662121607670723584 +1662121607715724544 +1662121607763725568 +1662121607805726464 +1662121607847727360 +1662121607889728256 +1662121607928729088 +1662121607970729984 +1662121608018731008 +1662121608060731904 +1662121608102732800 +1662121608147733760 +1662121608198734848 +1662121608246735872 +1662121608288736768 +1662121608333737728 +1662121608375738624 +1662121608426739712 +1662121608468740608 +1662121608510741504 +1662121608552742400 +1662121608597743360 +1662121608639744256 +1662121608681745152 +1662121608729746176 +1662121608777747200 +1662121608822748160 +1662121608867749120 +1662121608909750016 +1662121608951750912 +1662121609002752000 +1662121609044752896 +1662121609086753792 +1662121609134754816 +1662121609182755840 +1662121609230756864 +1662121609272757760 +1662121609317758720 +1662121609359759616 +1662121609398760448 +1662121609443761408 +1662121609491762432 +1662121609533763328 +1662121609575764224 +1662121609617765120 +1662121609662766080 +1662121609710767104 +1662121609755768064 +1662121609797768960 +1662121609839769856 +1662121609884770816 +1662121609935771904 +1662121609977772800 +1662121610022773760 +1662121610064774656 +1662121610106775552 +1662121610151776512 +1662121610196777472 +1662121610238778368 +1662121610292779520 +1662121610331780352 +1662121610382781440 +1662121610427782400 +1662121610469783296 +1662121610511784192 +1662121610559785216 +1662121610604786176 +1662121610646787072 +1662121610691788032 +1662121610733788928 +1662121610787790080 +1662121610832791040 +1662121610874791936 +1662121610922792960 +1662121610964793856 +1662121611006794752 +1662121611048795648 +1662121611096796672 +1662121611147797760 +1662121611198798848 +1662121611252800000 +1662121611294800896 +1662121611336801792 +1662121611381802752 +1662121611432803840 +1662121611474804736 +1662121611519805696 +1662121611561806592 +1662121611603807488 +1662121611651808512 +1662121611702809600 +1662121611747810560 +1662121611789811456 +1662121611834812416 +1662121611879813376 +1662121611927814400 +1662121611972815360 +1662121612017816320 +1662121612062817280 +1662121612107818240 +1662121612152819200 +1662121612194820096 +1662121612236820992 +1662121612278821888 +1662121612323822848 +1662121612368823808 +1662121612410824704 +1662121612449825536 +1662121612491826432 +1662121612548827648 +1662121612593828608 +1662121612635829504 +1662121612683830528 +1662121612731831552 +1662121612770832384 +1662121612818833408 +1662121612860834304 +1662121612902835200 +1662121612947836160 +1662121612989837056 +1662121613037838080 +1662121613082839040 +1662121613124839936 +1662121613166840832 +1662121613211841792 +1662121613259842816 +1662121613307843840 +1662121613349844736 +1662121613397845760 +1662121613442846720 +1662121613484847616 +1662121613526848512 +1662121613577849600 +1662121613625850624 +1662121613670851584 +1662121613724852736 +1662121613769853696 +1662121613817854720 +1662121613859855616 +1662121613907856640 +1662121613958857728 +1662121614009858816 +1662121614054859776 +1662121614096860672 +1662121614138861568 +1662121614177862400 +1662121614219863296 +1662121614267864320 +1662121614318865408 +1662121614360866304 +1662121614405867264 +1662121614450868224 +1662121614492869120 +1662121614540870144 +1662121614582871040 +1662121614630872064 +1662121614672872960 +1662121614720873984 +1662121614768875008 +1662121614816876032 +1662121614855876864 +1662121614897877760 +1662121614939878656 +1662121614987879680 +1662121615032880640 +1662121615077881600 +1662121615119882496 +1662121615164883456 +1662121615209884416 +1662121615254885376 +1662121615302886400 +1662121615350887424 +1662121615395888384 +1662121615443889408 +1662121615488890368 +1662121615530891264 +1662121615584892416 +1662121615626893312 +1662121615668894208 +1662121615707895040 +1662121615752896000 +1662121615800897024 +1662121615845897984 +1662121615896899072 +1662121615947900160 +1662121615992901120 +1662121616034902016 +1662121616079902976 +1662121616127904000 +1662121616178905088 +1662121616223906048 +1662121616268907008 +1662121616316908032 +1662121616358908928 +1662121616412910080 +1662121616463911168 +1662121616505912064 +1662121616547912960 +1662121616589913856 +1662121616634914816 +1662121616679915776 +1662121616727916800 +1662121616769917696 +1662121616823918848 +1662121616865919744 +1662121616913920768 +1662121616955921664 +1662121616997922560 +1662121617045923584 +1662121617087924480 +1662121617132925440 +1662121617177926400 +1662121617222927360 +1662121617264928256 +1662121617312929280 +1662121617360930304 +1662121617402931200 +1662121617444932096 +1662121617501933312 +1662121617543934208 +1662121617591935232 +1662121617639936256 +1662121617690937344 +1662121617741938432 +1662121617789939456 +1662121617831940352 +1662121617873941248 +1662121617918942208 +1662121617966943232 +1662121618014944256 +1662121618062945280 +1662121618104946176 +1662121618149947136 +1662121618200948224 +1662121618245949184 +1662121618287950080 +1662121618326950912 +1662121618368951808 +1662121618410952704 +1662121618452953600 +1662121618500954624 +1662121618545955584 +1662121618599956736 +1662121618641957632 +1662121618686958592 +1662121618728959488 +1662121618770960384 +1662121618815961344 +1662121618863962368 +1662121618905963264 +1662121618947964160 +1662121618992965120 +1662121619034966016 +1662121619079966976 +1662121619124967936 +1662121619166968832 +1662121619211969792 +1662121619253970688 +1662121619304971776 +1662121619346972672 +1662121619400973824 +1662121619442974720 +1662121619490975744 +1662121619535976704 +1662121619577977600 +1662121619619978496 +1662121619667979520 +1662121619706980352 +1662121619751981312 +1662121619802982400 +1662121619847983360 +1662121619892984320 +1662121619937985280 +1662121619979986176 +1662121620027987200 +1662121620075988224 +1662121620117989120 +1662121620162990080 +1662121620207991040 +1662121620252992000 +1662121620306993152 +1662121620351994112 +1662121620396995072 +1662121620438995968 +1662121620480996864 +1662121620525997824 +1662121620570998784 +1662121620615999744 +1662121620658000640 +1662121620703001600 +1662121620757002752 +1662121620799003648 +1662121620847004672 +1662121620892005632 +1662121620934006528 +1662121620976007424 +1662121621018008320 +1662121621060009216 +1662121621111010304 +1662121621159011328 +1662121621204012288 +1662121621246013184 +1662121621291014144 +1662121621330014976 +1662121621372015872 +1662121621414016768 +1662121621462017792 +1662121621507018752 +1662121621555019776 +1662121621594020608 +1662121621645021696 +1662121621687022592 +1662121621729023488 +1662121621774024448 +1662121621816025344 +1662121621861026304 +1662121621912027392 +1662121621957028352 +1662121622005029376 +1662121622050030336 +1662121622095031296 +1662121622137032192 +1662121622182033152 +1662121622227034112 +1662121622272035072 +1662121622323036160 +1662121622374037248 +1662121622413038080 +1662121622458039040 +1662121622503040000 +1662121622548040960 +1662121622593041920 +1662121622638042880 +1662121622686043904 +1662121622731044864 +1662121622773045760 +1662121622818046720 +1662121622863047680 +1662121622908048640 +1662121622953049600 +1662121623001050624 +1662121623049051648 +1662121623097052672 +1662121623148053760 +1662121623193054720 +1662121623238055680 +1662121623295056896 +1662121623340057856 +1662121623385058816 +1662121623427059712 +1662121623472060672 +1662121623514061568 +1662121623559062528 +1662121623604063488 +1662121623658064640 +1662121623700065536 +1662121623742066432 +1662121623784067328 +1662121623829068288 +1662121623877069312 +1662121623919070208 +1662121623961071104 +1662121624006072064 +1662121624051073024 +1662121624093073920 +1662121624135074816 +1662121624180075776 +1662121624225076736 +1662121624279077888 +1662121624324078848 +1662121624369079808 +1662121624411080704 +1662121624456081664 +1662121624498082560 +1662121624543083520 +1662121624594084608 +1662121624642085632 +1662121624687086592 +1662121624735087616 +1662121624780088576 +1662121624828089600 +1662121624879090688 +1662121624924091648 +1662121624966092544 +1662121625020093696 +1662121625065094656 +1662121625107095552 +1662121625152096512 +1662121625197097472 +1662121625239098368 +1662121625284099328 +1662121625335100416 +1662121625380101376 +1662121625425102336 +1662121625467103232 +1662121625512104192 +1662121625560105216 +1662121625608106240 +1662121625653107200 +1662121625698108160 +1662121625752109312 +1662121625797110272 +1662121625839111168 +1662121625887112192 +1662121625929113088 +1662121625977114112 +1662121626016114944 +1662121626058115840 +1662121626100116736 +1662121626148117760 +1662121626193118720 +1662121626241119744 +1662121626283120640 +1662121626325121536 +1662121626370122496 +1662121626412123392 +1662121626457124352 +1662121626502125312 +1662121626544126208 +1662121626589127168 +1662121626631128064 +1662121626673128960 +1662121626715129856 +1662121626760130816 +1662121626808131840 +1662121626859132928 +1662121626904133888 +1662121626952134912 +1662121626997135872 +1662121627042136832 +1662121627090137856 +1662121627135138816 +1662121627177139712 +1662121627228140800 +1662121627276141824 +1662121627318142720 +1662121627360143616 +1662121627405144576 +1662121627447145472 +1662121627498146560 +1662121627549147648 +1662121627597148672 +1662121627639149568 +1662121627690150656 +1662121627732151552 +1662121627774152448 +1662121627816153344 +1662121627858154240 +1662121627900155136 +1662121627942156032 +1662121627984156928 +1662121628029157888 +1662121628071158784 +1662121628119159808 +1662121628173160960 +1662121628212161792 +1662121628254162688 +1662121628299163648 +1662121628350164736 +1662121628398165760 +1662121628440166656 +1662121628488167680 +1662121628533168640 +1662121628581169664 +1662121628623170560 +1662121628671171584 +1662121628722172672 +1662121628770173696 +1662121628818174720 +1662121628860175616 +1662121628908176640 +1662121628953177600 +1662121629001178624 +1662121629049179648 +1662121629094180608 +1662121629145181696 +1662121629196182784 +1662121629244183808 +1662121629289184768 +1662121629331185664 +1662121629376186624 +1662121629424187648 +1662121629472188672 +1662121629517189632 +1662121629571190784 +1662121629616191744 +1662121629661192704 +1662121629703193600 +1662121629739194368 +1662121629787195392 +1662121629838196480 +1662121629883197440 +1662121629931198464 +1662121629973199360 +1662121630015200256 +1662121630057201152 +1662121630102202112 +1662121630153203200 +1662121630195204096 +1662121630237204992 +1662121630282205952 +1662121630324206848 +1662121630369207808 +1662121630423208960 +1662121630474210048 +1662121630525211136 +1662121630582212352 +1662121630621213184 +1662121630660214016 +1662121630702214912 +1662121630750215936 +1662121630792216832 +1662121630843217920 +1662121630885218816 +1662121630933219840 +1662121630975220736 +1662121631026221824 +1662121631068222720 +1662121631119223808 +1662121631167224832 +1662121631212225792 +1662121631254226688 +1662121631305227776 +1662121631347228672 +1662121631389229568 +1662121631431230464 +1662121631482231552 +1662121631530232576 +1662121631575233536 +1662121631620234496 +1662121631662235392 +1662121631707236352 +1662121631752237312 +1662121631800238336 +1662121631854239488 +1662121631896240384 +1662121631938241280 +1662121631983242240 +1662121632022243072 +1662121632064243968 +1662121632109244928 +1662121632154245888 +1662121632196246784 +1662121632244247808 +1662121632289248768 +1662121632334249728 +1662121632382250752 +1662121632424251648 +1662121632466252544 +1662121632508253440 +1662121632553254400 +1662121632598255360 +1662121632649256448 +1662121632697257472 +1662121632751258624 +1662121632793259520 +1662121632838260480 +1662121632883261440 +1662121632925262336 +1662121632976263424 +1662121633018264320 +1662121633066265344 +1662121633111266304 +1662121633159267328 +1662121633204268288 +1662121633246269184 +1662121633291270144 +1662121633339271168 +1662121633390272256 +1662121633435273216 +1662121633477274112 +1662121633519275008 +1662121633564275968 +1662121633609276928 +1662121633651277824 +1662121633696278784 +1662121633738279680 +1662121633786280704 +1662121633828281600 +1662121633876282624 +1662121633921283584 +1662121633963284480 +1662121634008285440 +1662121634050286336 +1662121634098287360 +1662121634143288320 +1662121634185289216 +1662121634233290240 +1662121634281291264 +1662121634320292096 +1662121634368293120 +1662121634422294272 +1662121634467295232 +1662121634515296256 +1662121634554297088 +1662121634602298112 +1662121634644299008 +1662121634692300032 +1662121634746301184 +1662121634797302272 +1662121634842303232 +1662121634884304128 +1662121634929305088 +1662121634980306176 +1662121635022307072 +1662121635073308160 +1662121635124309248 +1662121635169310208 +1662121635211311104 +1662121635262312192 +1662121635307313152 +1662121635349314048 +1662121635391314944 +1662121635436315904 +1662121635484316928 +1662121635526317824 +1662121635574318848 +1662121635622319872 +1662121635670320896 +1662121635724322048 +1662121635769323008 +1662121635811323904 +1662121635853324800 +1662121635901325824 +1662121635946326784 +1662121635991327744 +1662121636033328640 +1662121636078329600 +1662121636123330560 +1662121636174331648 +1662121636219332608 +1662121636267333632 +1662121636309334528 +1662121636351335424 +1662121636396336384 +1662121636438337280 +1662121636480338176 +1662121636525339136 +1662121636567340032 +1662121636609340928 +1662121636657341952 +1662121636702342912 +1662121636744343808 +1662121636789344768 +1662121636840345856 +1662121636894347008 +1662121636942348032 +1662121636987348992 +1662121637029349888 +1662121637074350848 +1662121637125351936 +1662121637170352896 +1662121637212353792 +1662121637254354688 +1662121637302355712 +1662121637350356736 +1662121637398357760 +1662121637443358720 +1662121637485359616 +1662121637533360640 +1662121637587361792 +1662121637632362752 +1662121637677363712 +1662121637719364608 +1662121637761365504 +1662121637803366400 +1662121637848367360 +1662121637887368192 +1662121637929369088 +1662121637974370048 +1662121638019371008 +1662121638061371904 +1662121638103372800 +1662121638145373696 +1662121638190374656 +1662121638232375552 +1662121638277376512 +1662121638319377408 +1662121638361378304 +1662121638406379264 +1662121638448380160 +1662121638490381056 +1662121638532381952 +1662121638574382848 +1662121638616383744 +1662121638655384576 +1662121638703385600 +1662121638748386560 +1662121638799387648 +1662121638841388544 +1662121638895389696 +1662121638937390592 +1662121638979391488 +1662121639024392448 +1662121639063393280 +1662121639105394176 +1662121639159395328 +1662121639204396288 +1662121639249397248 +1662121639300398336 +1662121639342399232 +1662121639387400192 +1662121639432401152 +1662121639477402112 +1662121639519403008 +1662121639564403968 +1662121639609404928 +1662121639651405824 +1662121639699406848 +1662121639750407936 +1662121639792408832 +1662121639834409728 +1662121639876410624 +1662121639924411648 +1662121639969412608 +1662121640011413504 +1662121640062414592 +1662121640113415680 +1662121640155416576 +1662121640197417472 +1662121640239418368 +1662121640284419328 +1662121640326420224 +1662121640371421184 +1662121640419422208 +1662121640464423168 +1662121640506424064 +1662121640554425088 +1662121640590425856 +1662121640644427008 +1662121640692428032 +1662121640737428992 +1662121640785430016 +1662121640824430848 +1662121640866431744 +1662121640911432704 +1662121640959433728 +1662121641004434688 +1662121641049435648 +1662121641091436544 +1662121641142437632 +1662121641193438720 +1662121641238439680 +1662121641283440640 +1662121641337441792 +1662121641379442688 +1662121641421443584 +1662121641463444480 +1662121641505445376 +1662121641550446336 +1662121641601447424 +1662121641643448320 +1662121641694449408 +1662121641739450368 +1662121641778451200 +1662121641823452160 +1662121641868453120 +1662121641907453952 +1662121641952454912 +1662121641997455872 +1662121642042456832 +1662121642090457856 +1662121642132458752 +1662121642174459648 +1662121642219460608 +1662121642264461568 +1662121642312462592 +1662121642354463488 +1662121642399464448 +1662121642441465344 +1662121642483466240 +1662121642528467200 +1662121642570468096 +1662121642612468992 +1662121642660470016 +1662121642705470976 +1662121642747471872 +1662121642801473024 +1662121642843473920 +1662121642891474944 +1662121642939475968 +1662121642981476864 +1662121643023477760 +1662121643065478656 +1662121643107479552 +1662121643149480448 +1662121643191481344 +1662121643233482240 +1662121643275483136 +1662121643317484032 +1662121643362484992 +1662121643410486016 +1662121643455486976 +1662121643503488000 +1662121643542488832 +1662121643587489792 +1662121643629490688 +1662121643674491648 +1662121643719492608 +1662121643764493568 +1662121643806494464 +1662121643845495296 +1662121643887496192 +1662121643932497152 +1662121643983498240 +1662121644034499328 +1662121644079500288 +1662121644121501184 +1662121644160502016 +1662121644208503040 +1662121644250503936 +1662121644295504896 +1662121644337505792 +1662121644385506816 +1662121644433507840 +1662121644478508800 +1662121644526509824 +1662121644568510720 +1662121644613511680 +1662121644658512640 +1662121644706513664 +1662121644748514560 +1662121644799515648 +1662121644853516800 +1662121644898517760 +1662121644940518656 +1662121644988519680 +1662121645033520640 +1662121645078521600 +1662121645120522496 +1662121645162523392 +1662121645210524416 +1662121645252525312 +1662121645300526336 +1662121645342527232 +1662121645384528128 +1662121645426529024 +1662121645468529920 +1662121645510530816 +1662121645561531904 +1662121645603532800 +1662121645645533696 +1662121645690534656 +1662121645735535616 +1662121645780536576 +1662121645825537536 +1662121645870538496 +1662121645912539392 +1662121645957540352 +1662121646005541376 +1662121646053542400 +1662121646107543552 +1662121646149544448 +1662121646197545472 +1662121646239546368 +1662121646281547264 +1662121646329548288 +1662121646371549184 +1662121646419550208 +1662121646470551296 +1662121646521552384 +1662121646566553344 +1662121646611554304 +1662121646653555200 +1662121646698556160 +1662121646737556992 +1662121646779557888 +1662121646824558848 +1662121646869559808 +1662121646911560704 +1662121646956561664 +1662121646998562560 +1662121647040563456 +1662121647085564416 +1662121647127565312 +1662121647172566272 +1662121647214567168 +1662121647262568192 +1662121647304569088 +1662121647352570112 +1662121647400571136 +1662121647451572224 +1662121647496573184 +1662121647547574272 +1662121647589575168 +1662121647634576128 +1662121647676577024 +1662121647727578112 +1662121647784579328 +1662121647832580352 +1662121647874581248 +1662121647931582464 +1662121647973583360 +1662121648015584256 +1662121648069585408 +1662121648114586368 +1662121648156587264 +1662121648198588160 +1662121648240589056 +1662121648288590080 +1662121648336591104 +1662121648393592320 +1662121648435593216 +1662121648477594112 +1662121648519595008 +1662121648573596160 +1662121648627597312 +1662121648678598400 +1662121648723599360 +1662121648768600320 +1662121648813601280 +1662121648852602112 +1662121648894603008 +1662121648939603968 +1662121648981604864 +1662121649023605760 +1662121649080606976 +1662121649125607936 +1662121649167608832 +1662121649209609728 +1662121649251610624 +1662121649302611712 +1662121649341612544 +1662121649392613632 +1662121649437614592 +1662121649479615488 +1662121649521616384 +1662121649569617408 +1662121649614618368 +1662121649653619200 +1662121649692620032 +1662121649740621056 +1662121649785622016 +1662121649830622976 +1662121649875623936 +1662121649920624896 +1662121649971625984 +1662121650013626880 +1662121650058627840 +1662121650106628864 +1662121650148629760 +1662121650193630720 +1662121650241631744 +1662121650286632704 +1662121650331633664 +1662121650376634624 +1662121650424635648 +1662121650466636544 +1662121650517637632 +1662121650559638528 +1662121650601639424 +1662121650646640384 +1662121650688641280 +1662121650730642176 +1662121650772643072 +1662121650823644160 +1662121650868645120 +1662121650910646016 +1662121650952646912 +1662121651000647936 +1662121651042648832 +1662121651087649792 +1662121651129650688 +1662121651171651584 +1662121651213652480 +1662121651255653376 +1662121651300654336 +1662121651345655296 +1662121651384656128 +1662121651429657088 +1662121651477658112 +1662121651525659136 +1662121651573660160 +1662121651618661120 +1662121651669662208 +1662121651714663168 +1662121651765664256 +1662121651816665344 +1662121651864666368 +1662121651909667328 +1662121651951668224 +1662121652002669312 +1662121652050670336 +1662121652101671424 +1662121652143672320 +1662121652188673280 +1662121652236674304 +1662121652284675328 +1662121652335676416 +1662121652377677312 +1662121652425678336 +1662121652479679488 +1662121652521680384 +1662121652560681216 +1662121652608682240 +1662121652665683456 +1662121652707684352 +1662121652749685248 +1662121652791686144 +1662121652839687168 +1662121652881688064 +1662121652923688960 +1662121652971689984 +1662121653013690880 +1662121653055691776 +1662121653100692736 +1662121653142693632 +1662121653184694528 +1662121653229695488 +1662121653271696384 +1662121653319697408 +1662121653358698240 +1662121653403699200 +1662121653445700096 +1662121653487700992 +1662121653532701952 +1662121653577702912 +1662121653625703936 +1662121653670704896 +1662121653712705792 +1662121653754706688 +1662121653799707648 +1662121653841708544 +1662121653883709440 +1662121653934710528 +1662121653979711488 +1662121654024712448 +1662121654066713344 +1662121654108714240 +1662121654162715392 +1662121654210716416 +1662121654252717312 +1662121654300718336 +1662121654342719232 +1662121654387720192 +1662121654432721152 +1662121654471721984 +1662121654519723008 +1662121654564723968 +1662121654606724864 +1662121654657725952 +1662121654696726784 +1662121654738727680 +1662121654789728768 +1662121654831729664 +1662121654876730624 +1662121654918731520 +1662121654963732480 +1662121655002733312 +1662121655044734208 +1662121655086735104 +1662121655131736064 +1662121655176737024 +1662121655221737984 +1662121655278739200 +1662121655323740160 +1662121655365741056 +1662121655410742016 +1662121655455742976 +1662121655500743936 +1662121655539744768 +1662121655596745984 +1662121655638746880 +1662121655680747776 +1662121655722748672 +1662121655764749568 +1662121655806750464 +1662121655848751360 +1662121655893752320 +1662121655935753216 +1662121655977754112 +1662121656028755200 +1662121656073756160 +1662121656124757248 +1662121656172758272 +1662121656214759168 +1662121656262760192 +1662121656307761152 +1662121656355762176 +1662121656403763200 +1662121656445764096 +1662121656493765120 +1662121656544766208 +1662121656589767168 +1662121656631768064 +1662121656670768896 +1662121656715769856 +1662121656757770752 +1662121656805771776 +1662121656859772928 +1662121656901773824 +1662121656949774848 +1662121656991775744 +1662121657033776640 +1662121657075777536 +1662121657123778560 +1662121657168779520 +1662121657210780416 +1662121657258781440 +1662121657312782592 +1662121657360783616 +1662121657405784576 +1662121657453785600 +1662121657501786624 +1662121657546787584 +1662121657591788544 +1662121657636789504 +1662121657681790464 +1662121657723791360 +1662121657768792320 +1662121657813793280 +1662121657852794112 +1662121657897795072 +1662121657939795968 +1662121657984796928 +1662121658026797824 +1662121658068798720 +1662121658113799680 +1662121658158800640 +1662121658200801536 +1662121658254802688 +1662121658302803712 +1662121658350804736 +1662121658404805888 +1662121658446806784 +1662121658491807744 +1662121658536808704 +1662121658575809536 +1662121658626810624 +1662121658668811520 +1662121658716812544 +1662121658758813440 +1662121658809814528 +1662121658851815424 +1662121658905816576 +1662121658947817472 +1662121658989818368 +1662121659031819264 +1662121659076820224 +1662121659121821184 +1662121659166822144 +1662121659208823040 +1662121659253824000 +1662121659307825152 +1662121659361826304 +1662121659406827264 +1662121659454828288 +1662121659502829312 +1662121659547830272 +1662121659589831168 +1662121659640832256 +1662121659685833216 +1662121659739834368 +1662121659787835392 +1662121659835836416 +1662121659880837376 +1662121659925838336 +1662121659970839296 +1662121660012840192 +1662121660063841280 +1662121660108842240 +1662121660150843136 +1662121660195844096 +1662121660240845056 +1662121660288846080 +1662121660339847168 +1662121660387848192 +1662121660429849088 +1662121660474850048 +1662121660528851200 +1662121660570852096 +1662121660615853056 +1662121660657853952 +1662121660702854912 +1662121660747855872 +1662121660798856960 +1662121660840857856 +1662121660882858752 +1662121660924859648 +1662121660972860672 +1662121661020861696 +1662121661062862592 +1662121661104863488 +1662121661152864512 +1662121661197865472 +1662121661239866368 +1662121661284867328 +1662121661329868288 +1662121661374869248 +1662121661422870272 +1662121661470871296 +1662121661512872192 +1662121661557873152 +1662121661605874176 +1662121661650875136 +1662121661698876160 +1662121661740877056 +1662121661782877952 +1662121661833879040 +1662121661887880192 +1662121661929881088 +1662121661974882048 +1662121662013882880 +1662121662055883776 +1662121662103884800 +1662121662148885760 +1662121662190886656 +1662121662232887552 +1662121662283888640 +1662121662328889600 +1662121662370890496 +1662121662418891520 +1662121662463892480 +1662121662511893504 +1662121662556894464 +1662121662604895488 +1662121662649896448 +1662121662688897280 +1662121662736898304 +1662121662778899200 +1662121662823900160 +1662121662868901120 +1662121662913902080 +1662121662958903040 +1662121663006904064 +1662121663051905024 +1662121663102906112 +1662121663147907072 +1662121663195908096 +1662121663243909120 +1662121663282909952 +1662121663324910848 +1662121663366911744 +1662121663414912768 +1662121663459913728 +1662121663504914688 +1662121663549915648 +1662121663597916672 +1662121663639917568 +1662121663681918464 +1662121663723919360 +1662121663765920256 +1662121663810921216 +1662121663855922176 +1662121663903923200 +1662121663948924160 +1662121663993925120 +1662121664035926016 +1662121664089927168 +1662121664134928128 +1662121664182929152 +1662121664224930048 +1662121664272931072 +1662121664320932096 +1662121664365933056 +1662121664413934080 +1662121664461935104 +1662121664512936192 +1662121664554937088 +1662121664596937984 +1662121664647939072 +1662121664701940224 +1662121664752941312 +1662121664809942528 +1662121664854943488 +1662121664899944448 +1662121664941945344 +1662121664983946240 +1662121665037947392 +1662121665079948288 +1662121665121949184 +1662121665163950080 +1662121665214951168 +1662121665262952192 +1662121665307953152 +1662121665355954176 +1662121665400955136 +1662121665445956096 +1662121665502957312 +1662121665547958272 +1662121665592959232 +1662121665640960256 +1662121665685961216 +1662121665730962176 +1662121665772963072 +1662121665817964032 +1662121665856964864 +1662121665904965888 +1662121665946966784 +1662121665988967680 +1662121666030968576 +1662121666078969600 +1662121666120970496 +1662121666162971392 +1662121666210972416 +1662121666255973376 +1662121666297974272 +1662121666345975296 +1662121666390976256 +1662121666432977152 +1662121666474978048 +1662121666519979008 +1662121666567980032 +1662121666612980992 +1662121666666982144 +1662121666705982976 +1662121666756984064 +1662121666801985024 +1662121666858986240 +1662121666900987136 +1662121666942988032 +1662121666987988992 +1662121667041990144 +1662121667089991168 +1662121667137992192 +1662121667185993216 +1662121667230994176 +1662121667275995136 +1662121667320996096 +1662121667362996992 +1662121667410998016 +1662121667455998976 +1662121667500999936 +1662121667546000896 +1662121667594001920 +1662121667642002944 +1662121667687003904 +1662121667729004800 +1662121667771005696 +1662121667816006656 +1662121667861007616 +1662121667903008512 +1662121667957009664 +1662121667999010560 +1662121668041011456 +1662121668089012480 +1662121668134013440 +1662121668179014400 +1662121668224015360 +1662121668278016512 +1662121668323017472 +1662121668374018560 +1662121668413019392 +1662121668458020352 +1662121668500021248 +1662121668539022080 +1662121668581022976 +1662121668626023936 +1662121668668024832 +1662121668710025728 +1662121668752026624 +1662121668797027584 +1662121668842028544 +1662121668884029440 +1662121668926030336 +1662121668974031360 +1662121669019032320 +1662121669061033216 +1662121669103034112 +1662121669154035200 +1662121669199036160 +1662121669241037056 +1662121669283037952 +1662121669325038848 +1662121669367039744 +1662121669409040640 +1662121669454041600 +1662121669511042816 +1662121669556043776 +1662121669595044608 +1662121669634045440 +1662121669673046272 +1662121669715047168 +1662121669760048128 +1662121669802049024 +1662121669856050176 +1662121669901051136 +1662121669943052032 +1662121669988052992 +1662121670036054016 +1662121670081054976 +1662121670123055872 +1662121670165056768 +1662121670219057920 +1662121670267058944 +1662121670315059968 +1662121670360060928 +1662121670411062016 +1662121670456062976 +1662121670507064064 +1662121670561065216 +1662121670606066176 +1662121670654067200 +1662121670699068160 +1662121670753069312 +1662121670789070080 +1662121670831070976 +1662121670873071872 +1662121670921072896 +1662121670963073792 +1662121671005074688 +1662121671047075584 +1662121671089076480 +1662121671137077504 +1662121671179078400 +1662121671221079296 +1662121671263080192 +1662121671317081344 +1662121671359082240 +1662121671401083136 +1662121671443084032 +1662121671485084928 +1662121671536086016 +1662121671578086912 +1662121671620087808 +1662121671671088896 +1662121671713089792 +1662121671758090752 +1662121671800091648 +1662121671842092544 +1662121671893093632 +1662121671935094528 +1662121671977095424 +1662121672025096448 +1662121672073097472 +1662121672115098368 +1662121672157099264 +1662121672208100352 +1662121672259101440 +1662121672304102400 +1662121672349103360 +1662121672394104320 +1662121672436105216 +1662121672484106240 +1662121672526107136 +1662121672574108160 +1662121672616109056 +1662121672664110080 +1662121672709111040 +1662121672754112000 +1662121672799112960 +1662121672841113856 +1662121672886114816 +1662121672934115840 +1662121672985116928 +1662121673027117824 +1662121673066118656 +1662121673111119616 +1662121673159120640 +1662121673204121600 +1662121673243122432 +1662121673288123392 +1662121673339124480 +1662121673387125504 +1662121673435126528 +1662121673489127680 +1662121673537128704 +1662121673582129664 +1662121673639130880 +1662121673681131776 +1662121673726132736 +1662121673768133632 +1662121673819134720 +1662121673861135616 +1662121673906136576 +1662121673963137792 +1662121674002138624 +1662121674050139648 +1662121674092140544 +1662121674137141504 +1662121674182142464 +1662121674230143488 +1662121674275144448 +1662121674323145472 +1662121674365146368 +1662121674413147392 +1662121674458148352 +1662121674500149248 +1662121674542150144 +1662121674587151104 +1662121674629152000 +1662121674674152960 +1662121674719153920 +1662121674767154944 +1662121674818156032 +1662121674863156992 +1662121674917158144 +1662121674959159040 +1662121675007160064 +1662121675046160896 +1662121675094161920 +1662121675136162816 +1662121675178163712 +1662121675226164736 +1662121675268165632 +1662121675313166592 +1662121675355167488 +1662121675400168448 +1662121675445169408 +1662121675493170432 +1662121675535171328 +1662121675580172288 +1662121675625173248 +1662121675667174144 +1662121675709175040 +1662121675751175936 +1662121675799176960 +1662121675847177984 +1662121675892178944 +1662121675937179904 +1662121675979180800 +1662121676021181696 +1662121676066182656 +1662121676108183552 +1662121676153184512 +1662121676207185664 +1662121676249186560 +1662121676294187520 +1662121676339188480 +1662121676387189504 +1662121676432190464 +1662121676474191360 +1662121676519192320 +1662121676567193344 +1662121676621194496 +1662121676666195456 +1662121676708196352 +1662121676756197376 +1662121676798198272 +1662121676852199424 +1662121676903200512 +1662121676948201472 +1662121676993202432 +1662121677035203328 +1662121677083204352 +1662121677134205440 +1662121677188206592 +1662121677236207616 +1662121677278208512 +1662121677317209344 +1662121677365210368 +1662121677407211264 +1662121677449212160 +1662121677491213056 +1662121677533213952 +1662121677575214848 +1662121677617215744 +1662121677659216640 +1662121677701217536 +1662121677743218432 +1662121677785219328 +1662121677827220224 +1662121677869221120 +1662121677914222080 +1662121677956222976 +1662121678004224000 +1662121678055225088 +1662121678094225920 +1662121678136226816 +1662121678187227904 +1662121678229228800 +1662121678274229760 +1662121678319230720 +1662121678367231744 +1662121678412232704 +1662121678469233920 +1662121678520235008 +1662121678565235968 +1662121678607236864 +1662121678649237760 +1662121678691238656 +1662121678733239552 +1662121678775240448 +1662121678817241344 +1662121678862242304 +1662121678907243264 +1662121678952244224 +1662121679009245440 +1662121679051246336 +1662121679093247232 +1662121679138248192 +1662121679186249216 +1662121679228250112 +1662121679273251072 +1662121679321252096 +1662121679372253184 +1662121679420254208 +1662121679462255104 +1662121679504256000 +1662121679549256960 +1662121679594257920 +1662121679639258880 +1662121679684259840 +1662121679729260800 +1662121679768261632 +1662121679810262528 +1662121679861263616 +1662121679903264512 +1662121679948265472 +1662121679996266496 +1662121680035267328 +1662121680080268288 +1662121680125269248 +1662121680167270144 +1662121680218271232 +1662121680263272192 +1662121680305273088 +1662121680347273984 +1662121680392274944 +1662121680437275904 +1662121680479276800 +1662121680530277888 +1662121680578278912 +1662121680629280000 +1662121680671280896 +1662121680713281792 +1662121680761282816 +1662121680803283712 +1662121680851284736 +1662121680896285696 +1662121680935286528 +1662121680974287360 +1662121681016288256 +1662121681064289280 +1662121681109290240 +1662121681157291264 +1662121681208292352 +1662121681250293248 +1662121681295294208 +1662121681340295168 +1662121681391296256 +1662121681436297216 +1662121681484298240 +1662121681535299328 +1662121681577300224 +1662121681622301184 +1662121681673302272 +1662121681724303360 +1662121681772304384 +1662121681817305344 +1662121681862306304 +1662121681910307328 +1662121681958308352 +1662121682000309248 +1662121682048310272 +1662121682090311168 +1662121682132312064 +1662121682180313088 +1662121682225314048 +1662121682270315008 +1662121682321316096 +1662121682369317120 +1662121682417318144 +1662121682459319040 +1662121682504320000 +1662121682546320896 +1662121682597321984 +1662121682639322880 +1662121682684323840 +1662121682735324928 +1662121682789326080 +1662121682831326976 +1662121682873327872 +1662121682921328896 +1662121682966329856 +1662121683014330880 +1662121683062331904 +1662121683107332864 +1662121683161334016 +1662121683203334912 +1662121683248335872 +1662121683296336896 +1662121683341337856 +1662121683386338816 +1662121683434339840 +1662121683482340864 +1662121683527341824 +1662121683575342848 +1662121683623343872 +1662121683668344832 +1662121683713345792 +1662121683761346816 +1662121683806347776 +1662121683848348672 +1662121683899349760 +1662121683941350656 +1662121683983351552 +1662121684025352448 +1662121684067353344 +1662121684109354240 +1662121684157355264 +1662121684202356224 +1662121684250357248 +1662121684298358272 +1662121684346359296 +1662121684391360256 +1662121684433361152 +1662121684475362048 +1662121684517362944 +1662121684562363904 +1662121684616365056 +1662121684661366016 +1662121684703366912 +1662121684754368000 +1662121684799368960 +1662121684850370048 +1662121684898371072 +1662121684940371968 +1662121684997373184 +1662121685036374016 +1662121685081374976 +1662121685123375872 +1662121685171376896 +1662121685228378112 +1662121685282379264 +1662121685330380288 +1662121685375381248 +1662121685420382208 +1662121685468383232 +1662121685510384128 +1662121685561385216 +1662121685609386240 +1662121685651387136 +1662121685693388032 +1662121685738388992 +1662121685783389952 +1662121685834391040 +1662121685897392384 +1662121685948393472 +1662121685993394432 +1662121686044395520 +1662121686086396416 +1662121686131397376 +1662121686176398336 +1662121686215399168 +1662121686260400128 +1662121686305401088 +1662121686353402112 +1662121686404403200 +1662121686449404160 +1662121686491405056 +1662121686533405952 +1662121686575406848 +1662121686626407936 +1662121686668408832 +1662121686716409856 +1662121686767410944 +1662121686812411904 +1662121686854412800 +1662121686899413760 +1662121686941414656 +1662121686992415744 +1662121687040416768 +1662121687085417728 +1662121687133418752 +1662121687175419648 +1662121687217420544 +1662121687265421568 +1662121687307422464 +1662121687352423424 +1662121687397424384 +1662121687445425408 +1662121687490426368 +1662121687532427264 +1662121687574428160 +1662121687619429120 +1662121687664430080 +1662121687709431040 +1662121687751431936 +1662121687793432832 +1662121687832433664 +1662121687880434688 +1662121687928435712 +1662121687970436608 +1662121688018437632 +1662121688069438720 +1662121688126439936 +1662121688171440896 +1662121688216441856 +1662121688258442752 +1662121688303443712 +1662121688345444608 +1662121688387445504 +1662121688429446400 +1662121688474447360 +1662121688522448384 +1662121688570449408 +1662121688609450240 +1662121688651451136 +1662121688705452288 +1662121688747453184 +1662121688795454208 +1662121688840455168 +1662121688885456128 +1662121688924456960 +1662121688975458048 +1662121689017458944 +1662121689059459840 +1662121689101460736 +1662121689149461760 +1662121689194462720 +1662121689239463680 +1662121689287464704 +1662121689329465600 +1662121689380466688 +1662121689422467584 +1662121689467468544 +1662121689509469440 +1662121689554470400 +1662121689602471424 +1662121689644472320 +1662121689686473216 +1662121689734474240 +1662121689773475072 +1662121689812475904 +1662121689857476864 +1662121689908477952 +1662121689950478848 +1662121689995479808 +1662121690046480896 +1662121690094481920 +1662121690139482880 +1662121690178483712 +1662121690220484608 +1662121690268485632 +1662121690313486592 +1662121690361487616 +1662121690403488512 +1662121690454489600 +1662121690496490496 +1662121690538491392 +1662121690583492352 +1662121690625493248 +1662121690673494272 +1662121690721495296 +1662121690766496256 +1662121690805497088 +1662121690850498048 +1662121690892498944 +1662121690934499840 +1662121690976500736 +1662121691027501824 +1662121691072502784 +1662121691114503680 +1662121691156504576 +1662121691201505536 +1662121691246506496 +1662121691297507584 +1662121691342508544 +1662121691384509440 +1662121691429510400 +1662121691471511296 +1662121691522512384 +1662121691564513280 +1662121691612514304 +1662121691660515328 +1662121691705516288 +1662121691747517184 +1662121691792518144 +1662121691834519040 +1662121691885520128 +1662121691927521024 +1662121691969521920 +1662121692023523072 +1662121692068524032 +1662121692125525248 +1662121692182526464 +1662121692224527360 +1662121692266528256 +1662121692311529216 +1662121692359530240 +1662121692407531264 +1662121692449532160 +1662121692491533056 +1662121692545534208 +1662121692593535232 +1662121692644536320 +1662121692686537216 +1662121692731538176 +1662121692779539200 +1662121692818540032 +1662121692866541056 +1662121692911542016 +1662121692956542976 +1662121692998543872 +1662121693046544896 +1662121693097545984 +1662121693139546880 +1662121693184547840 +1662121693229548800 +1662121693277549824 +1662121693322550784 +1662121693364551680 +1662121693409552640 +1662121693457553664 +1662121693502554624 +1662121693547555584 +1662121693589556480 +1662121693634557440 +1662121693673558272 +1662121693718559232 +1662121693763560192 +1662121693805561088 +1662121693847561984 +1662121693895563008 +1662121693937563904 +1662121693982564864 +1662121694033565952 +1662121694081566976 +1662121694132568064 +1662121694177569024 +1662121694219569920 +1662121694267570944 +1662121694312571904 +1662121694360572928 +1662121694408573952 +1662121694462575104 +1662121694507576064 +1662121694549576960 +1662121694594577920 +1662121694636578816 +1662121694678579712 +1662121694729580800 +1662121694771581696 +1662121694822582784 +1662121694864583680 +1662121694909584640 +1662121694951585536 +1662121695002586624 +1662121695047587584 +1662121695089588480 +1662121695137589504 +1662121695185590528 +1662121695227591424 +1662121695269592320 +1662121695311593216 +1662121695353594112 +1662121695398595072 +1662121695449596160 +1662121695491597056 +1662121695548598272 +1662121695593599232 +1662121695638600192 +1662121695683601152 +1662121695725602048 +1662121695767602944 +1662121695809603840 +1662121695854604800 +1662121695896605696 +1662121695947606784 +1662121695998607872 +1662121696046608896 +1662121696091609856 +1662121696151611136 +1662121696202612224 +1662121696250613248 +1662121696298614272 +1662121696340615168 +1662121696385616128 +1662121696433617152 +1662121696478618112 +1662121696526619136 +1662121696571620096 +1662121696616621056 +1662121696661622016 +1662121696709623040 +1662121696757624064 +1662121696802625024 +1662121696847625984 +1662121696889626880 +1662121696943628032 +1662121696985628928 +1662121697036630016 +1662121697084631040 +1662121697123631872 +1662121697171632896 +1662121697219633920 +1662121697267634944 +1662121697312635904 +1662121697354636800 +1662121697399637760 +1662121697441638656 +1662121697489639680 +1662121697534640640 +1662121697582641664 +1662121697633642752 +1662121697678643712 +1662121697732644864 +1662121697780645888 +1662121697831646976 +1662121697873647872 +1662121697915648768 +1662121697960649728 +1662121698005650688 +1662121698047651584 +1662121698098652672 +1662121698143653632 +1662121698191654656 +1662121698242655744 +1662121698287656704 +1662121698329657600 +1662121698371658496 +1662121698413659392 +1662121698458660352 +1662121698506661376 +1662121698554662400 +1662121698602663424 +1662121698647664384 +1662121698689665280 +1662121698737666304 +1662121698782667264 +1662121698827668224 +1662121698866669056 +1662121698914670080 +1662121698959671040 +1662121699004672000 +1662121699049672960 +1662121699094673920 +1662121699136674816 +1662121699181675776 +1662121699226676736 +1662121699268677632 +1662121699310678528 +1662121699358679552 +1662121699400680448 +1662121699445681408 +1662121699487682304 +1662121699532683264 +1662121699577684224 +1662121699622685184 +1662121699667686144 +1662121699709687040 +1662121699763688192 +1662121699814689280 +1662121699856690176 +1662121699898691072 +1662121699946692096 +1662121700003693312 +1662121700048694272 +1662121700096695296 +1662121700138696192 +1662121700177697024 +1662121700219697920 +1662121700267698944 +1662121700312699904 +1662121700357700864 +1662121700408701952 +1662121700453702912 +1662121700495703808 +1662121700546704896 +1662121700597705984 +1662121700642706944 +1662121700684707840 +1662121700729708800 +1662121700774709760 +1662121700816710656 +1662121700864711680 +1662121700906712576 +1662121700960713728 +1662121701011714816 +1662121701053715712 +1662121701095716608 +1662121701140717568 +1662121701191718656 +1662121701233719552 +1662121701278720512 +1662121701326721536 +1662121701371722496 +1662121701413723392 +1662121701461724416 +1662121701503725312 +1662121701545726208 +1662121701584727040 +1662121701629728000 +1662121701677729024 +1662121701722729984 +1662121701770731008 +1662121701812731904 +1662121701857732864 +1662121701902733824 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt new file mode 100644 index 0000000000..23ef73aa69 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt @@ -0,0 +1,2934 @@ +1662064490014331136 +1662064490059332096 +1662064490101332992 +1662064490140333824 +1662064490188334848 +1662064490233335808 +1662064490275336704 +1662064490323337728 +1662064490371338752 +1662064490419339776 +1662064490461340672 +1662064490506341632 +1662064490548342528 +1662064490590343424 +1662064490632344320 +1662064490671345152 +1662064490710345984 +1662064490749346816 +1662064490794347776 +1662064490836348672 +1662064490878349568 +1662064490920350464 +1662064490962351360 +1662064491007352320 +1662064491049353216 +1662064491088354048 +1662064491130354944 +1662064491175355904 +1662064491223356928 +1662064491265357824 +1662064491307358720 +1662064491352359680 +1662064491397360640 +1662064491439361536 +1662064491481362432 +1662064491523363328 +1662064491562364160 +1662064491601364992 +1662064491643365888 +1662064491685366784 +1662064491727367680 +1662064491778368768 +1662064491820369664 +1662064491862370560 +1662064491904371456 +1662064491946372352 +1662064491985373184 +1662064492030374144 +1662064492072375040 +1662064492117376000 +1662064492159376896 +1662064492201377792 +1662064492246378752 +1662064492288379648 +1662064492330380544 +1662064492372381440 +1662064492411382272 +1662064492456383232 +1662064492501384192 +1662064492543385088 +1662064492588386048 +1662064492630386944 +1662064492669387776 +1662064492714388736 +1662064492756389632 +1662064492801390592 +1662064492846391552 +1662064492885392384 +1662064492927393280 +1662064492975394304 +1662064493017395200 +1662064493065396224 +1662064493107397120 +1662064493149398016 +1662064493188398848 +1662064493236399872 +1662064493284400896 +1662064493329401856 +1662064493374402816 +1662064493419403776 +1662064493464404736 +1662064493506405632 +1662064493554406656 +1662064493596407552 +1662064493638408448 +1662064493680409344 +1662064493722410240 +1662064493767411200 +1662064493815412224 +1662064493857413120 +1662064493899414016 +1662064493938414848 +1662064493983415808 +1662064494028416768 +1662064494073417728 +1662064494115418624 +1662064494160419584 +1662064494205420544 +1662064494244421376 +1662064494289422336 +1662064494331423232 +1662064494379424256 +1662064494418425088 +1662064494463426048 +1662064494505426944 +1662064494547427840 +1662064494589428736 +1662064494631429632 +1662064494670430464 +1662064494721431552 +1662064494766432512 +1662064494811433472 +1662064494853434368 +1662064494895435264 +1662064494937436160 +1662064494976436992 +1662064495018437888 +1662064495063438848 +1662064495108439808 +1662064495147440640 +1662064495189441536 +1662064495231442432 +1662064495273443328 +1662064495321444352 +1662064495366445312 +1662064495408446208 +1662064495450447104 +1662064495486447872 +1662064495528448768 +1662064495570449664 +1662064495615450624 +1662064495654451456 +1662064495699452416 +1662064495738453248 +1662064495783454208 +1662064495819454976 +1662064495861455872 +1662064495903456768 +1662064495945457664 +1662064495987458560 +1662064496026459392 +1662064496071460352 +1662064496116461312 +1662064496161462272 +1662064496200463104 +1662064496242464000 +1662064496284464896 +1662064496326465792 +1662064496365466624 +1662064496407467520 +1662064496452468480 +1662064496494469376 +1662064496536470272 +1662064496578471168 +1662064496623472128 +1662064496668473088 +1662064496707473920 +1662064496752474880 +1662064496794475776 +1662064496833476608 +1662064496875477504 +1662064496917478400 +1662064496959479296 +1662064497004480256 +1662064497046481152 +1662064497091482112 +1662064497133483008 +1662064497175483904 +1662064497217484800 +1662064497256485632 +1662064497295486464 +1662064497334487296 +1662064497379488256 +1662064497424489216 +1662064497463490048 +1662064497505490944 +1662064497550491904 +1662064497589492736 +1662064497631493632 +1662064497676494592 +1662064497727495680 +1662064497769496576 +1662064497811497472 +1662064497853498368 +1662064497892499200 +1662064497934500096 +1662064497973500928 +1662064498012501760 +1662064498057502720 +1662064498102503680 +1662064498147504640 +1662064498189505536 +1662064498234506496 +1662064498276507392 +1662064498318508288 +1662064498363509248 +1662064498408510208 +1662064498450511104 +1662064498492512000 +1662064498534512896 +1662064498579513856 +1662064498615514624 +1662064498654515456 +1662064498696516352 +1662064498741517312 +1662064498777518080 +1662064498813518848 +1662064498855519744 +1662064498903520768 +1662064498948521728 +1662064498993522688 +1662064499035523584 +1662064499080524544 +1662064499122525440 +1662064499161526272 +1662064499206527232 +1662064499242528000 +1662064499284528896 +1662064499323529728 +1662064499365530624 +1662064499404531456 +1662064499446532352 +1662064499494533376 +1662064499542534400 +1662064499590535424 +1662064499629536256 +1662064499671537152 +1662064499716538112 +1662064499761539072 +1662064499800539904 +1662064499839540736 +1662064499884541696 +1662064499923542528 +1662064499968543488 +1662064500016544512 +1662064500064545536 +1662064500109546496 +1662064500148547328 +1662064500190548224 +1662064500235549184 +1662064500277550080 +1662064500322551040 +1662064500367552000 +1662064500409552896 +1662064500451553792 +1662064500496554752 +1662064500541555712 +1662064500583556608 +1662064500625557504 +1662064500670558464 +1662064500712559360 +1662064500757560320 +1662064500799561216 +1662064500841562112 +1662064500883563008 +1662064500925563904 +1662064500970564864 +1662064501015565824 +1662064501060566784 +1662064501102567680 +1662064501144568576 +1662064501192569600 +1662064501234570496 +1662064501276571392 +1662064501315572224 +1662064501354573056 +1662064501405574144 +1662064501447575040 +1662064501489575936 +1662064501534576896 +1662064501579577856 +1662064501621578752 +1662064501666579712 +1662064501714580736 +1662064501756581632 +1662064501798582528 +1662064501843583488 +1662064501885584384 +1662064501924585216 +1662064501969586176 +1662064502011587072 +1662064502053587968 +1662064502098588928 +1662064502143589888 +1662064502191590912 +1662064502236591872 +1662064502281592832 +1662064502320593664 +1662064502362594560 +1662064502398595328 +1662064502440596224 +1662064502485597184 +1662064502524598016 +1662064502566598912 +1662064502608599808 +1662064502653600768 +1662064502695601664 +1662064502737602560 +1662064502782603520 +1662064502827604480 +1662064502872605440 +1662064502917606400 +1662064502962607360 +1662064503007608320 +1662064503052609280 +1662064503100610304 +1662064503139611136 +1662064503178611968 +1662064503223612928 +1662064503268613888 +1662064503313614848 +1662064503355615744 +1662064503397616640 +1662064503442617600 +1662064503484618496 +1662064503526619392 +1662064503568620288 +1662064503610621184 +1662064503658622208 +1662064503703623168 +1662064503745624064 +1662064503790625024 +1662064503832625920 +1662064503874626816 +1662064503916627712 +1662064503958628608 +1662064504000629504 +1662064504042630400 +1662064504084631296 +1662064504126632192 +1662064504162632960 +1662064504204633856 +1662064504249634816 +1662064504294635776 +1662064504339636736 +1662064504381637632 +1662064504429638656 +1662064504468639488 +1662064504510640384 +1662064504558641408 +1662064504597642240 +1662064504645643264 +1662064504687644160 +1662064504729645056 +1662064504771645952 +1662064504813646848 +1662064504852647680 +1662064504897648640 +1662064504936649472 +1662064504975650304 +1662064505017651200 +1662064505059652096 +1662064505101652992 +1662064505143653888 +1662064505191654912 +1662064505236655872 +1662064505278656768 +1662064505320657664 +1662064505362658560 +1662064505407659520 +1662064505449660416 +1662064505497661440 +1662064505539662336 +1662064505578663168 +1662064505623664128 +1662064505668665088 +1662064505716666112 +1662064505758667008 +1662064505809668096 +1662064505848668928 +1662064505890669824 +1662064505938670848 +1662064505980671744 +1662064506022672640 +1662064506064673536 +1662064506106674432 +1662064506151675392 +1662064506196676352 +1662064506244677376 +1662064506289678336 +1662064506334679296 +1662064506376680192 +1662064506418681088 +1662064506454681856 +1662064506499682816 +1662064506544683776 +1662064506586684672 +1662064506631685632 +1662064506673686528 +1662064506715687424 +1662064506757688320 +1662064506796689152 +1662064506838690048 +1662064506880690944 +1662064506922691840 +1662064506970692864 +1662064507012693760 +1662064507057694720 +1662064507099695616 +1662064507141696512 +1662064507180697344 +1662064507219698176 +1662064507270699264 +1662064507315700224 +1662064507357701120 +1662064507405702144 +1662064507447703040 +1662064507486703872 +1662064507528704768 +1662064507570705664 +1662064507612706560 +1662064507654707456 +1662064507702708480 +1662064507747709440 +1662064507789710336 +1662064507834711296 +1662064507879712256 +1662064507930713344 +1662064507975714304 +1662064508014715136 +1662064508062716160 +1662064508107717120 +1662064508152718080 +1662064508194718976 +1662064508236719872 +1662064508281720832 +1662064508329721856 +1662064508362722560 +1662064508407723520 +1662064508455724544 +1662064508497725440 +1662064508539726336 +1662064508584727296 +1662064508623728128 +1662064508665729024 +1662064508710729984 +1662064508761731072 +1662064508806732032 +1662064508854733056 +1662064508899734016 +1662064508941734912 +1662064508983735808 +1662064509025736704 +1662064509070737664 +1662064509115738624 +1662064509151739392 +1662064509193740288 +1662064509235741184 +1662064509280742144 +1662064509325743104 +1662064509364743936 +1662064509406744832 +1662064509448745728 +1662064509490746624 +1662064509532747520 +1662064509574748416 +1662064509616749312 +1662064509661750272 +1662064509706751232 +1662064509751752192 +1662064509793753088 +1662064509835753984 +1662064509877754880 +1662064509922755840 +1662064509967756800 +1662064510009757696 +1662064510051758592 +1662064510099759616 +1662064510141760512 +1662064510183761408 +1662064510228762368 +1662064510273763328 +1662064510321764352 +1662064510363765248 +1662064510405766144 +1662064510453767168 +1662064510495768064 +1662064510540769024 +1662064510582769920 +1662064510621770752 +1662064510660771584 +1662064510702772480 +1662064510747773440 +1662064510789774336 +1662064510831775232 +1662064510870776064 +1662064510915777024 +1662064510957777920 +1662064510999778816 +1662064511041779712 +1662064511083780608 +1662064511122781440 +1662064511164782336 +1662064511206783232 +1662064511254784256 +1662064511296785152 +1662064511338786048 +1662064511383787008 +1662064511425787904 +1662064511473788928 +1662064511515789824 +1662064511557790720 +1662064511602791680 +1662064511644792576 +1662064511686793472 +1662064511725794304 +1662064511770795264 +1662064511809796096 +1662064511851796992 +1662064511896797952 +1662064511938798848 +1662064511980799744 +1662064512028800768 +1662064512070801664 +1662064512109802496 +1662064512151803392 +1662064512193804288 +1662064512235805184 +1662064512271805952 +1662064512322807040 +1662064512364807936 +1662064512406808832 +1662064512445809664 +1662064512484810496 +1662064512523811328 +1662064512568812288 +1662064512607813120 +1662064512646813952 +1662064512691814912 +1662064512733815808 +1662064512778816768 +1662064512820817664 +1662064512859818496 +1662064512904819456 +1662064512952820480 +1662064512997821440 +1662064513039822336 +1662064513081823232 +1662064513123824128 +1662064513165825024 +1662064513207825920 +1662064513252826880 +1662064513294827776 +1662064513339828736 +1662064513381829632 +1662064513423830528 +1662064513465831424 +1662064513507832320 +1662064513546833152 +1662064513588834048 +1662064513627834880 +1662064513672835840 +1662064513714836736 +1662064513756837632 +1662064513795838464 +1662064513834839296 +1662064513873840128 +1662064513915841024 +1662064513960841984 +1662064514008843008 +1662064514050843904 +1662064514095844864 +1662064514137845760 +1662064514179846656 +1662064514221847552 +1662064514266848512 +1662064514311849472 +1662064514350850304 +1662064514383851008 +1662064514425851904 +1662064514467852800 +1662064514512853760 +1662064514554854656 +1662064514596855552 +1662064514641856512 +1662064514683857408 +1662064514725858304 +1662064514767859200 +1662064514812860160 +1662064514854861056 +1662064514899862016 +1662064514944862976 +1662064514986863872 +1662064515028864768 +1662064515070865664 +1662064515112866560 +1662064515154867456 +1662064515205868544 +1662064515250869504 +1662064515295870464 +1662064515343871488 +1662064515388872448 +1662064515427873280 +1662064515472874240 +1662064515517875200 +1662064515556876032 +1662064515598876928 +1662064515637877760 +1662064515685878784 +1662064515727879680 +1662064515769880576 +1662064515817881600 +1662064515859882496 +1662064515898883328 +1662064515937884160 +1662064515985885184 +1662064516024886016 +1662064516063886848 +1662064516105887744 +1662064516144888576 +1662064516189889536 +1662064516228890368 +1662064516270891264 +1662064516315892224 +1662064516360893184 +1662064516402894080 +1662064516441894912 +1662064516483895808 +1662064516522896640 +1662064516558897408 +1662064516600898304 +1662064516639899136 +1662064516687900160 +1662064516729901056 +1662064516774902016 +1662064516819902976 +1662064516858903808 +1662064516900904704 +1662064516942905600 +1662064516984906496 +1662064517029907456 +1662064517071908352 +1662064517116909312 +1662064517158910208 +1662064517200911104 +1662064517254912256 +1662064517296913152 +1662064517338914048 +1662064517380914944 +1662064517419915776 +1662064517467916800 +1662064517512917760 +1662064517554918656 +1662064517605919744 +1662064517650920704 +1662064517692921600 +1662064517737922560 +1662064517779923456 +1662064517824924416 +1662064517863925248 +1662064517902926080 +1662064517947927040 +1662064517989927936 +1662064518028928768 +1662064518073929728 +1662064518118930688 +1662064518160931584 +1662064518199932416 +1662064518241933312 +1662064518280934144 +1662064518322935040 +1662064518361935872 +1662064518406936832 +1662064518448937728 +1662064518490938624 +1662064518532939520 +1662064518577940480 +1662064518622941440 +1662064518667942400 +1662064518709943296 +1662064518751944192 +1662064518793945088 +1662064518832945920 +1662064518874946816 +1662064518916947712 +1662064518964948736 +1662064519009949696 +1662064519048950528 +1662064519084951296 +1662064519126952192 +1662064519168953088 +1662064519210953984 +1662064519252954880 +1662064519288955648 +1662064519333956608 +1662064519378957568 +1662064519420958464 +1662064519462959360 +1662064519507960320 +1662064519546961152 +1662064519591962112 +1662064519639963136 +1662064519678963968 +1662064519717964800 +1662064519759965696 +1662064519804966656 +1662064519849967616 +1662064519888968448 +1662064519930969344 +1662064519975970304 +1662064520017971200 +1662064520062972160 +1662064520104973056 +1662064520149974016 +1662064520194974976 +1662064520239975936 +1662064520281976832 +1662064520323977728 +1662064520368978688 +1662064520416979712 +1662064520464980736 +1662064520506981632 +1662064520548982528 +1662064520593983488 +1662064520641984512 +1662064520683985408 +1662064520725986304 +1662064520767987200 +1662064520812988160 +1662064520854989056 +1662064520896989952 +1662064520938990848 +1662064520977991680 +1662064521022992640 +1662064521064993536 +1662064521106994432 +1662064521148995328 +1662064521187996160 +1662064521226996992 +1662064521268997888 +1662064521316998912 +1662064521361999872 +1662064521407000832 +1662064521449001728 +1662064521491002624 +1662064521536003584 +1662064521578004480 +1662064521620005376 +1662064521662006272 +1662064521707007232 +1662064521746008064 +1662064521788008960 +1662064521827009792 +1662064521869010688 +1662064521911011584 +1662064521950012416 +1662064521992013312 +1662064522034014208 +1662064522076015104 +1662064522118016000 +1662064522163016960 +1662064522205017856 +1662064522247018752 +1662064522286019584 +1662064522328020480 +1662064522370021376 +1662064522412022272 +1662064522457023232 +1662064522499024128 +1662064522538024960 +1662064522580025856 +1662064522625026816 +1662064522667027712 +1662064522709028608 +1662064522754029568 +1662064522793030400 +1662064522835031296 +1662064522877032192 +1662064522919033088 +1662064522961033984 +1662064523003034880 +1662064523045035776 +1662064523093036800 +1662064523138037760 +1662064523180038656 +1662064523225039616 +1662064523267040512 +1662064523312041472 +1662064523354042368 +1662064523396043264 +1662064523438044160 +1662064523480045056 +1662064523522045952 +1662064523561046784 +1662064523600047616 +1662064523645048576 +1662064523687049472 +1662064523735050496 +1662064523777051392 +1662064523819052288 +1662064523861053184 +1662064523903054080 +1662064523954055168 +1662064523996056064 +1662064524035056896 +1662064524083057920 +1662064524128058880 +1662064524170059776 +1662064524212060672 +1662064524254061568 +1662064524302062592 +1662064524344063488 +1662064524389064448 +1662064524431065344 +1662064524470066176 +1662064524512067072 +1662064524557068032 +1662064524596068864 +1662064524638069760 +1662064524677070592 +1662064524722071552 +1662064524761072384 +1662064524806073344 +1662064524851074304 +1662064524896075264 +1662064524932076032 +1662064524971076864 +1662064525013077760 +1662064525058078720 +1662064525106079744 +1662064525151080704 +1662064525196081664 +1662064525238082560 +1662064525280083456 +1662064525328084480 +1662064525367085312 +1662064525412086272 +1662064525454087168 +1662064525499088128 +1662064525544089088 +1662064525586089984 +1662064525628090880 +1662064525664091648 +1662064525712092672 +1662064525754093568 +1662064525802094592 +1662064525847095552 +1662064525889096448 +1662064525931097344 +1662064525982098432 +1662064526024099328 +1662064526066100224 +1662064526105101056 +1662064526147101952 +1662064526189102848 +1662064526231103744 +1662064526276104704 +1662064526324105728 +1662064526366106624 +1662064526405107456 +1662064526450108416 +1662064526492109312 +1662064526534110208 +1662064526579111168 +1662064526624112128 +1662064526666113024 +1662064526708113920 +1662064526753114880 +1662064526798115840 +1662064526840116736 +1662064526885117696 +1662064526927118592 +1662064526969119488 +1662064527020120576 +1662064527062121472 +1662064527104122368 +1662064527149123328 +1662064527185124096 +1662064527227124992 +1662064527269125888 +1662064527311126784 +1662064527353127680 +1662064527389128448 +1662064527431129344 +1662064527470130176 +1662064527512131072 +1662064527557132032 +1662064527602132992 +1662064527644133888 +1662064527692134912 +1662064527731135744 +1662064527776136704 +1662064527815137536 +1662064527863138560 +1662064527905139456 +1662064527950140416 +1662064527992141312 +1662064528037142272 +1662064528079143168 +1662064528124144128 +1662064528172145152 +1662064528214146048 +1662064528262147072 +1662064528304147968 +1662064528349148928 +1662064528391149824 +1662064528430150656 +1662064528472151552 +1662064528514152448 +1662064528556153344 +1662064528592154112 +1662064528628154880 +1662064528667155712 +1662064528712156672 +1662064528754157568 +1662064528796158464 +1662064528838159360 +1662064528883160320 +1662064528922161152 +1662064528964162048 +1662064529009163008 +1662064529048163840 +1662064529093164800 +1662064529138165760 +1662064529183166720 +1662064529225167616 +1662064529267168512 +1662064529309169408 +1662064529354170368 +1662064529396171264 +1662064529438172160 +1662064529480173056 +1662064529525174016 +1662064529564174848 +1662064529609175808 +1662064529654176768 +1662064529693177600 +1662064529738178560 +1662064529780179456 +1662064529822180352 +1662064529867181312 +1662064529915182336 +1662064529957183232 +1662064530002184192 +1662064530047185152 +1662064530092186112 +1662064530134187008 +1662064530182188032 +1662064530227188992 +1662064530269189888 +1662064530308190720 +1662064530350191616 +1662064530395192576 +1662064530437193472 +1662064530482194432 +1662064530521195264 +1662064530566196224 +1662064530611197184 +1662064530653198080 +1662064530695198976 +1662064530740199936 +1662064530788200960 +1662064530833201920 +1662064530872202752 +1662064530920203776 +1662064530962204672 +1662064531007205632 +1662064531049206528 +1662064531097207552 +1662064531142208512 +1662064531184209408 +1662064531223210240 +1662064531265211136 +1662064531310212096 +1662064531352212992 +1662064531394213888 +1662064531436214784 +1662064531478215680 +1662064531517216512 +1662064531556217344 +1662064531601218304 +1662064531646219264 +1662064531685220096 +1662064531727220992 +1662064531769221888 +1662064531808222720 +1662064531847223552 +1662064531892224512 +1662064531934225408 +1662064531982226432 +1662064532027227392 +1662064532069228288 +1662064532111229184 +1662064532159230208 +1662064532201231104 +1662064532246232064 +1662064532291233024 +1662064532330233856 +1662064532372234752 +1662064532417235712 +1662064532462236672 +1662064532504237568 +1662064532543238400 +1662064532585239296 +1662064532627240192 +1662064532672241152 +1662064532714242048 +1662064532756242944 +1662064532795243776 +1662064532837244672 +1662064532882245632 +1662064532927246592 +1662064532966247424 +1662064533008248320 +1662064533047249152 +1662064533089250048 +1662064533131250944 +1662064533173251840 +1662064533215252736 +1662064533257253632 +1662064533302254592 +1662064533344255488 +1662064533386256384 +1662064533428257280 +1662064533470258176 +1662064533512259072 +1662064533551259904 +1662064533593260800 +1662064533638261760 +1662064533680262656 +1662064533722263552 +1662064533767264512 +1662064533809265408 +1662064533851266304 +1662064533893267200 +1662064533935268096 +1662064533977268992 +1662064534022269952 +1662064534067270912 +1662064534109271808 +1662064534154272768 +1662064534193273600 +1662064534238274560 +1662064534280275456 +1662064534322276352 +1662064534367277312 +1662064534409278208 +1662064534451279104 +1662064534499280128 +1662064534544281088 +1662064534589282048 +1662064534634283008 +1662064534673283840 +1662064534712284672 +1662064534754285568 +1662064534799286528 +1662064534844287488 +1662064534892288512 +1662064534937289472 +1662064534979290368 +1662064535021291264 +1662064535060292096 +1662064535105293056 +1662064535156294144 +1662064535201295104 +1662064535249296128 +1662064535291297024 +1662064535336297984 +1662064535375298816 +1662064535417299712 +1662064535459300608 +1662064535501301504 +1662064535543302400 +1662064535585303296 +1662064535627304192 +1662064535669305088 +1662064535714306048 +1662064535753306880 +1662064535795307776 +1662064535837308672 +1662064535879309568 +1662064535921310464 +1662064535969311488 +1662064536014312448 +1662064536056313344 +1662064536104314368 +1662064536143315200 +1662064536185316096 +1662064536230317056 +1662064536275318016 +1662064536323319040 +1662064536365319936 +1662064536410320896 +1662064536452321792 +1662064536497322752 +1662064536545323776 +1662064536593324800 +1662064536635325696 +1662064536677326592 +1662064536719327488 +1662064536761328384 +1662064536806329344 +1662064536854330368 +1662064536905331456 +1662064536950332416 +1662064536992333312 +1662064537034334208 +1662064537079335168 +1662064537124336128 +1662064537163336960 +1662064537202337792 +1662064537244338688 +1662064537289339648 +1662064537331340544 +1662064537376341504 +1662064537421342464 +1662064537463343360 +1662064537505344256 +1662064537553345280 +1662064537595346176 +1662064537640347136 +1662064537688348160 +1662064537733349120 +1662064537775350016 +1662064537817350912 +1662064537856351744 +1662064537898352640 +1662064537940353536 +1662064537988354560 +1662064538033355520 +1662064538078356480 +1662064538123357440 +1662064538171358464 +1662064538213359360 +1662064538258360320 +1662064538297361152 +1662064538339362048 +1662064538384363008 +1662064538429363968 +1662064538471364864 +1662064538513365760 +1662064538555366656 +1662064538597367552 +1662064538639368448 +1662064538684369408 +1662064538726370304 +1662064538771371264 +1662064538810372096 +1662064538852372992 +1662064538891373824 +1662064538939374848 +1662064538984375808 +1662064539026376704 +1662064539071377664 +1662064539113378560 +1662064539158379520 +1662064539200380416 +1662064539242381312 +1662064539281382144 +1662064539326383104 +1662064539368384000 +1662064539410384896 +1662064539455385856 +1662064539497386752 +1662064539539387648 +1662064539581388544 +1662064539629389568 +1662064539671390464 +1662064539719391488 +1662064539764392448 +1662064539803393280 +1662064539845394176 +1662064539896395264 +1662064539938396160 +1662064539977396992 +1662064540022397952 +1662064540061398784 +1662064540103399680 +1662064540151400704 +1662064540187401472 +1662064540226402304 +1662064540271403264 +1662064540319404288 +1662064540361405184 +1662064540403406080 +1662064540445406976 +1662064540481407744 +1662064540523408640 +1662064540562409472 +1662064540607410432 +1662064540649411328 +1662064540694412288 +1662064540736413184 +1662064540781414144 +1662064540826415104 +1662064540868416000 +1662064540910416896 +1662064540949417728 +1662064540994418688 +1662064541039419648 +1662064541078420480 +1662064541117421312 +1662064541159422208 +1662064541198423040 +1662064541240423936 +1662064541282424832 +1662064541324425728 +1662064541366426624 +1662064541405427456 +1662064541444428288 +1662064541489429248 +1662064541534430208 +1662064541576431104 +1662064541621432064 +1662064541666433024 +1662064541705433856 +1662064541744434688 +1662064541789435648 +1662064541828436480 +1662064541870437376 +1662064541915438336 +1662064541957439232 +1662064541999440128 +1662064542044441088 +1662064542086441984 +1662064542131442944 +1662064542173443840 +1662064542215444736 +1662064542263445760 +1662064542308446720 +1662064542350447616 +1662064542395448576 +1662064542440449536 +1662064542482450432 +1662064542524451328 +1662064542569452288 +1662064542614453248 +1662064542659454208 +1662064542701455104 +1662064542743456000 +1662064542782456832 +1662064542827457792 +1662064542875458816 +1662064542920459776 +1662064542959460608 +1662064543004461568 +1662064543049462528 +1662064543091463424 +1662064543139464448 +1662064543184465408 +1662064543235466496 +1662064543280467456 +1662064543325468416 +1662064543367469312 +1662064543412470272 +1662064543454471168 +1662064543496472064 +1662064543541473024 +1662064543580473856 +1662064543625474816 +1662064543667475712 +1662064543706476544 +1662064543742477312 +1662064543784478208 +1662064543823479040 +1662064543877480192 +1662064543928481280 +1662064543973482240 +1662064544018483200 +1662064544057484032 +1662064544099484928 +1662064544144485888 +1662064544186486784 +1662064544228487680 +1662064544267488512 +1662064544309489408 +1662064544354490368 +1662064544396491264 +1662064544438492160 +1662064544477492992 +1662064544519493888 +1662064544564494848 +1662064544609495808 +1662064544651496704 +1662064544693497600 +1662064544735498496 +1662064544777499392 +1662064544819500288 +1662064544864501248 +1662064544909502208 +1662064544954503168 +1662064544993504000 +1662064545035504896 +1662064545080505856 +1662064545122506752 +1662064545164507648 +1662064545209508608 +1662064545257509632 +1662064545299510528 +1662064545344511488 +1662064545389512448 +1662064545431513344 +1662064545476514304 +1662064545518515200 +1662064545563516160 +1662064545617517312 +1662064545659518208 +1662064545707519232 +1662064545749520128 +1662064545794521088 +1662064545836521984 +1662064545881522944 +1662064545926523904 +1662064545971524864 +1662064546016525824 +1662064546061526784 +1662064546106527744 +1662064546148528640 +1662064546193529600 +1662064546232530432 +1662064546274531328 +1662064546316532224 +1662064546361533184 +1662064546406534144 +1662064546445534976 +1662064546484535808 +1662064546529536768 +1662064546574537728 +1662064546619538688 +1662064546658539520 +1662064546700540416 +1662064546739541248 +1662064546784542208 +1662064546826543104 +1662064546871544064 +1662064546913544960 +1662064546955545856 +1662064546997546752 +1662064547042547712 +1662064547087548672 +1662064547132549632 +1662064547177550592 +1662064547219551488 +1662064547264552448 +1662064547306553344 +1662064547348554240 +1662064547390555136 +1662064547432556032 +1662064547474556928 +1662064547522557952 +1662064547564558848 +1662064547606559744 +1662064547651560704 +1662064547699561728 +1662064547738562560 +1662064547780563456 +1662064547816564224 +1662064547855565056 +1662064547900566016 +1662064547942566912 +1662064547987567872 +1662064548029568768 +1662064548074569728 +1662064548116570624 +1662064548158571520 +1662064548197572352 +1662064548242573312 +1662064548284574208 +1662064548329575168 +1662064548368576000 +1662064548407576832 +1662064548452577792 +1662064548500578816 +1662064548545579776 +1662064548590580736 +1662064548629581568 +1662064548671582464 +1662064548713583360 +1662064548758584320 +1662064548803585280 +1662064548845586176 +1662064548884587008 +1662064548929587968 +1662064548974588928 +1662064549016589824 +1662064549061590784 +1662064549100591616 +1662064549148592640 +1662064549199593728 +1662064549241594624 +1662064549286595584 +1662064549328596480 +1662064549373597440 +1662064549418598400 +1662064549463599360 +1662064549505600256 +1662064549550601216 +1662064549592602112 +1662064549634603008 +1662064549676603904 +1662064549724604928 +1662064549766605824 +1662064549805606656 +1662064549847607552 +1662064549886608384 +1662064549931609344 +1662064549976610304 +1662064550021611264 +1662064550063612160 +1662064550108613120 +1662064550147613952 +1662064550189614848 +1662064550231615744 +1662064550276616704 +1662064550318617600 +1662064550357618432 +1662064550399619328 +1662064550444620288 +1662064550486621184 +1662064550528622080 +1662064550567622912 +1662064550609623808 +1662064550657624832 +1662064550702625792 +1662064550744626688 +1662064550786627584 +1662064550822628352 +1662064550861629184 +1662064550906630144 +1662064550951631104 +1662064550987631872 +1662064551029632768 +1662064551071633664 +1662064551116634624 +1662064551158635520 +1662064551200636416 +1662064551239637248 +1662064551281638144 +1662064551323639040 +1662064551365639936 +1662064551404640768 +1662064551449641728 +1662064551494642688 +1662064551539643648 +1662064551581644544 +1662064551623645440 +1662064551662646272 +1662064551707647232 +1662064551749648128 +1662064551794649088 +1662064551839650048 +1662064551881650944 +1662064551926651904 +1662064551971652864 +1662064552010653696 +1662064552049654528 +1662064552088655360 +1662064552133656320 +1662064552178657280 +1662064552220658176 +1662064552262659072 +1662064552310660096 +1662064552352660992 +1662064552394661888 +1662064552436662784 +1662064552478663680 +1662064552532664832 +1662064552577665792 +1662064552619666688 +1662064552661667584 +1662064552709668608 +1662064552757669632 +1662064552802670592 +1662064552844671488 +1662064552886672384 +1662064552928673280 +1662064552970674176 +1662064553018675200 +1662064553060676096 +1662064553093676800 +1662064553141677824 +1662064553180678656 +1662064553228679680 +1662064553273680640 +1662064553315681536 +1662064553354682368 +1662064553396683264 +1662064553438684160 +1662064553480685056 +1662064553525686016 +1662064553567686912 +1662064553612687872 +1662064553654688768 +1662064553699689728 +1662064553741690624 +1662064553780691456 +1662064553822692352 +1662064553864693248 +1662064553906694144 +1662064553948695040 +1662064553990695936 +1662064554035696896 +1662064554074697728 +1662064554116698624 +1662064554155699456 +1662064554200700416 +1662064554245701376 +1662064554287702272 +1662064554332703232 +1662064554371704064 +1662064554413704960 +1662064554452705792 +1662064554494706688 +1662064554536707584 +1662064554578708480 +1662064554620709376 +1662064554665710336 +1662064554707711232 +1662064554752712192 +1662064554797713152 +1662064554836713984 +1662064554878714880 +1662064554920715776 +1662064554962716672 +1662064555007717632 +1662064555049718528 +1662064555088719360 +1662064555130720256 +1662064555172721152 +1662064555214722048 +1662064555256722944 +1662064555301723904 +1662064555346724864 +1662064555391725824 +1662064555433726720 +1662064555475727616 +1662064555514728448 +1662064555571729664 +1662064555613730560 +1662064555655731456 +1662064555703732480 +1662064555748733440 +1662064555790734336 +1662064555832735232 +1662064555874736128 +1662064555919737088 +1662064555961737984 +1662064556006738944 +1662064556048739840 +1662064556093740800 +1662064556132741632 +1662064556174742528 +1662064556219743488 +1662064556264744448 +1662064556309745408 +1662064556357746432 +1662064556405747456 +1662064556450748416 +1662064556489749248 +1662064556534750208 +1662064556582751232 +1662064556627752192 +1662064556669753088 +1662064556711753984 +1662064556756754944 +1662064556798755840 +1662064556843756800 +1662064556885757696 +1662064556933758720 +1662064556969759488 +1662064557008760320 +1662064557047761152 +1662064557089762048 +1662064557131762944 +1662064557173763840 +1662064557212764672 +1662064557260765696 +1662064557305766656 +1662064557347767552 +1662064557383768320 +1662064557422769152 +1662064557467770112 +1662064557515771136 +1662064557557772032 +1662064557599772928 +1662064557638773760 +1662064557683774720 +1662064557728775680 +1662064557773776640 +1662064557818777600 +1662064557860778496 +1662064557902779392 +1662064557941780224 +1662064557983781120 +1662064558028782080 +1662064558067782912 +1662064558109783808 +1662064558148784640 +1662064558190785536 +1662064558232786432 +1662064558277787392 +1662064558322788352 +1662064558364789248 +1662064558409790208 +1662064558457791232 +1662064558499792128 +1662064558538792960 +1662064558583793920 +1662064558631794944 +1662064558673795840 +1662064558715796736 +1662064558757797632 +1662064558799798528 +1662064558847799552 +1662064558886800384 +1662064558928801280 +1662064558973802240 +1662064559018803200 +1662064559063804160 +1662064559108805120 +1662064559147805952 +1662064559189806848 +1662064559234807808 +1662064559276808704 +1662064559312809472 +1662064559354810368 +1662064559399811328 +1662064559441812224 +1662064559489813248 +1662064559534814208 +1662064559576815104 +1662064559618816000 +1662064559663816960 +1662064559705817856 +1662064559744818688 +1662064559786819584 +1662064559828820480 +1662064559867821312 +1662064559915822336 +1662064559957823232 +1662064559999824128 +1662064560044825088 +1662064560089826048 +1662064560134827008 +1662064560176827904 +1662064560218828800 +1662064560260829696 +1662064560299830528 +1662064560338831360 +1662064560377832192 +1662064560416833024 +1662064560458833920 +1662064560503834880 +1662064560545835776 +1662064560587836672 +1662064560632837632 +1662064560671838464 +1662064560716839424 +1662064560761840384 +1662064560803841280 +1662064560848842240 +1662064560893843200 +1662064560932844032 +1662064560968844800 +1662064561010845696 +1662064561055846656 +1662064561094847488 +1662064561136848384 +1662064561184849408 +1662064561220850176 +1662064561265851136 +1662064561310852096 +1662064561352852992 +1662064561397853952 +1662064561436854784 +1662064561478855680 +1662064561523856640 +1662064561568857600 +1662064561607858432 +1662064561652859392 +1662064561691860224 +1662064561733861120 +1662064561775862016 +1662064561817862912 +1662064561859863808 +1662064561901864704 +1662064561943865600 +1662064561988866560 +1662064562033867520 +1662064562075868416 +1662064562120869376 +1662064562162870272 +1662064562201871104 +1662064562243872000 +1662064562285872896 +1662064562327873792 +1662064562372874752 +1662064562417875712 +1662064562462876672 +1662064562510877696 +1662064562552878592 +1662064562594879488 +1662064562636880384 +1662064562681881344 +1662064562726882304 +1662064562768883200 +1662064562816884224 +1662064562861885184 +1662064562903886080 +1662064562948887040 +1662064562996888064 +1662064563038888960 +1662064563080889856 +1662064563122890752 +1662064563164891648 +1662064563209892608 +1662064563248893440 +1662064563290894336 +1662064563332895232 +1662064563374896128 +1662064563416897024 +1662064563461897984 +1662064563503898880 +1662064563545899776 +1662064563590900736 +1662064563632901632 +1662064563674902528 +1662064563719903488 +1662064563767904512 +1662064563806905344 +1662064563848906240 +1662064563887907072 +1662064563929907968 +1662064563971908864 +1662064564010909696 +1662064564052910592 +1662064564097911552 +1662064564139912448 +1662064564184913408 +1662064564226914304 +1662064564271915264 +1662064564313916160 +1662064564352916992 +1662064564397917952 +1662064564439918848 +1662064564484919808 +1662064564529920768 +1662064564571921664 +1662064564616922624 +1662064564658923520 +1662064564703924480 +1662064564745925376 +1662064564790926336 +1662064564832927232 +1662064564871928064 +1662064564913928960 +1662064564958929920 +1662064565000930816 +1662064565039931648 +1662064565081932544 +1662064565126933504 +1662064565171934464 +1662064565210935296 +1662064565255936256 +1662064565297937152 +1662064565339938048 +1662064565381938944 +1662064565426939904 +1662064565468940800 +1662064565510941696 +1662064565552942592 +1662064565594943488 +1662064565639944448 +1662064565681945344 +1662064565723946240 +1662064565768947200 +1662064565807948032 +1662064565849948928 +1662064565891949824 +1662064565933950720 +1662064565978951680 +1662064566020952576 +1662064566062953472 +1662064566104954368 +1662064566143955200 +1662064566188956160 +1662064566230957056 +1662064566263957760 +1662064566308958720 +1662064566353959680 +1662064566398960640 +1662064566440961536 +1662064566482962432 +1662064566527963392 +1662064566569964288 +1662064566617965312 +1662064566659966208 +1662064566701967104 +1662064566743968000 +1662064566785968896 +1662064566827969792 +1662064566872970752 +1662064566914971648 +1662064566959972608 +1662064567004973568 +1662064567046974464 +1662064567088975360 +1662064567133976320 +1662064567172977152 +1662064567214978048 +1662064567259979008 +1662064567298979840 +1662064567343980800 +1662064567388981760 +1662064567430982656 +1662064567472983552 +1662064567511984384 +1662064567556985344 +1662064567592986112 +1662064567634987008 +1662064567682988032 +1662064567721988864 +1662064567757989632 +1662064567799990528 +1662064567838991360 +1662064567880992256 +1662064567925993216 +1662064567964994048 +1662064568006994944 +1662064568051995904 +1662064568090996736 +1662064568132997632 +1662064568177998592 +1662064568222999552 +1662064568256000256 +1662064568301001216 +1662064568343002112 +1662064568385003008 +1662064568424003840 +1662064568466004736 +1662064568511005696 +1662064568553006592 +1662064568598007552 +1662064568640008448 +1662064568685009408 +1662064568724010240 +1662064568766011136 +1662064568811012096 +1662064568853012992 +1662064568898013952 +1662064568943014912 +1662064568988015872 +1662064569027016704 +1662064569069017600 +1662064569108018432 +1662064569150019328 +1662064569195020288 +1662064569234021120 +1662064569279022080 +1662064569324023040 +1662064569366023936 +1662064569411024896 +1662064569453025792 +1662064569498026752 +1662064569543027712 +1662064569582028544 +1662064569630029568 +1662064569672030464 +1662064569717031424 +1662064569759032320 +1662064569801033216 +1662064569837033984 +1662064569879034880 +1662064569927035904 +1662064569969036800 +1662064570011037696 +1662064570056038656 +1662064570101039616 +1662064570146040576 +1662064570188041472 +1662064570230042368 +1662064570275043328 +1662064570317044224 +1662064570359045120 +1662064570398045952 +1662064570443046912 +1662064570485047808 +1662064570527048704 +1662064570569049600 +1662064570614050560 +1662064570659051520 +1662064570701052416 +1662064570740053248 +1662064570782054144 +1662064570827055104 +1662064570869056000 +1662064570914056960 +1662064570959057920 +1662064571001058816 +1662064571043059712 +1662064571079060480 +1662064571124061440 +1662064571169062400 +1662064571211063296 +1662064571253064192 +1662064571298065152 +1662064571343066112 +1662064571394067200 +1662064571433068032 +1662064571478068992 +1662064571520069888 +1662064571565070848 +1662064571610071808 +1662064571652072704 +1662064571694073600 +1662064571736074496 +1662064571784075520 +1662064571829076480 +1662064571877077504 +1662064571919078400 +1662064571970079488 +1662064572012080384 +1662064572060081408 +1662064572102082304 +1662064572144083200 +1662064572186084096 +1662064572225084928 +1662064572267085824 +1662064572309086720 +1662064572357087744 +1662064572399088640 +1662064572444089600 +1662064572492090624 +1662064572540091648 +1662064572588092672 +1662064572630093568 +1662064572669094400 +1662064572714095360 +1662064572759096320 +1662064572801097216 +1662064572840098048 +1662064572882098944 +1662064572921099776 +1662064572966100736 +1662064573008101632 +1662064573050102528 +1662064573092103424 +1662064573134104320 +1662064573176105216 +1662064573215106048 +1662064573257106944 +1662064573299107840 +1662064573341108736 +1662064573383109632 +1662064573422110464 +1662064573464111360 +1662064573509112320 +1662064573545113088 +1662064573587113984 +1662064573629114880 +1662064573671115776 +1662064573710116608 +1662064573752117504 +1662064573794118400 +1662064573836119296 +1662064573878120192 +1662064573917121024 +1662064573959121920 +1662064574004122880 +1662064574049123840 +1662064574088124672 +1662064574133125632 +1662064574175126528 +1662064574220127488 +1662064574265128448 +1662064574304129280 +1662064574343130112 +1662064574388131072 +1662064574430131968 +1662064574475132928 +1662064574520133888 +1662064574556134656 +1662064574595135488 +1662064574637136384 +1662064574679137280 +1662064574721138176 +1662064574769139200 +1662064574811140096 +1662064574856141056 +1662064574898141952 +1662064574934142720 +1662064574970143488 +1662064575015144448 +1662064575057145344 +1662064575099146240 +1662064575144147200 +1662064575189148160 +1662064575231149056 +1662064575273149952 +1662064575318150912 +1662064575363151872 +1662064575408152832 +1662064575450153728 +1662064575489154560 +1662064575531155456 +1662064575579156480 +1662064575624157440 +1662064575663158272 +1662064575711159296 +1662064575756160256 +1662064575801161216 +1662064575840162048 +1662064575882162944 +1662064575924163840 +1662064575963164672 +1662064576008165632 +1662064576050166528 +1662064576095167488 +1662064576137168384 +1662064576182169344 +1662064576224170240 +1662064576263171072 +1662064576302171904 +1662064576347172864 +1662064576392173824 +1662064576434174720 +1662064576476175616 +1662064576518176512 +1662064576560177408 +1662064576608178432 +1662064576650179328 +1662064576701180416 +1662064576743181312 +1662064576782182144 +1662064576824183040 +1662064576866183936 +1662064576908184832 +1662064576950185728 +1662064576995186688 +1662064577034187520 +1662064577079188480 +1662064577118189312 +1662064577163190272 +1662064577205191168 +1662064577247192064 +1662064577289192960 +1662064577331193856 +1662064577373194752 +1662064577415195648 +1662064577460196608 +1662064577505197568 +1662064577547198464 +1662064577592199424 +1662064577634200320 +1662064577676201216 +1662064577718202112 +1662064577757202944 +1662064577799203840 +1662064577841204736 +1662064577886205696 +1662064577928206592 +1662064577973207552 +1662064578012208384 +1662064578051209216 +1662064578090210048 +1662064578132210944 +1662064578174211840 +1662064578219212800 +1662064578258213632 +1662064578306214656 +1662064578348215552 +1662064578393216512 +1662064578441217536 +1662064578489218560 +1662064578534219520 +1662064578576220416 +1662064578615221248 +1662064578657222144 +1662064578699223040 +1662064578741223936 +1662064578786224896 +1662064578828225792 +1662064578867226624 +1662064578912227584 +1662064578954228480 +1662064578996229376 +1662064579041230336 +1662064579080231168 +1662064579122232064 +1662064579161232896 +1662064579203233792 +1662064579248234752 +1662064579287235584 +1662064579329236480 +1662064579374237440 +1662064579422238464 +1662064579470239488 +1662064579515240448 +1662064579557241344 +1662064579599242240 +1662064579638243072 +1662064579680243968 +1662064579728244992 +1662064579773245952 +1662064579815246848 +1662064579860247808 +1662064579902248704 +1662064579944249600 +1662064579986250496 +1662064580028251392 +1662064580067252224 +1662064580112253184 +1662064580151254016 +1662064580190254848 +1662064580229255680 +1662064580271256576 +1662064580310257408 +1662064580352258304 +1662064580394259200 +1662064580442260224 +1662064580484261120 +1662064580526262016 +1662064580568262912 +1662064580610263808 +1662064580655264768 +1662064580697265664 +1662064580739266560 +1662064580781267456 +1662064580823268352 +1662064580868269312 +1662064580916270336 +1662064580955271168 +1662064581000272128 +1662064581045273088 +1662064581087273984 +1662064581135275008 +1662064581177275904 +1662064581222276864 +1662064581267277824 +1662064581312278784 +1662064581357279744 +1662064581399280640 +1662064581441281536 +1662064581489282560 +1662064581531283456 +1662064581564284160 +1662064581606285056 +1662064581651286016 +1662064581690286848 +1662064581732287744 +1662064581777288704 +1662064581816289536 +1662064581861290496 +1662064581903291392 +1662064581945292288 +1662064581987293184 +1662064582032294144 +1662064582068294912 +1662064582113295872 +1662064582152296704 +1662064582194297600 +1662064582239298560 +1662064582278299392 +1662064582320300288 +1662064582365301248 +1662064582404302080 +1662064582446302976 +1662064582485303808 +1662064582536304896 +1662064582578305792 +1662064582620306688 +1662064582665307648 +1662064582707308544 +1662064582752309504 +1662064582794310400 +1662064582839311360 +1662064582881312256 +1662064582923313152 +1662064582965314048 +1662064583007314944 +1662064583058316032 +1662064583100316928 +1662064583145317888 +1662064583187318784 +1662064583229319680 +1662064583274320640 +1662064583319321600 +1662064583364322560 +1662064583409323520 +1662064583454324480 +1662064583499325440 +1662064583544326400 +1662064583589327360 +1662064583631328256 +1662064583676329216 +1662064583715330048 +1662064583760331008 +1662064583802331904 +1662064583847332864 +1662064583886333696 +1662064583928334592 +1662064583973335552 +1662064584018336512 +1662064584063337472 +1662064584102338304 +1662064584141339136 +1662064584183340032 +1662064584222340864 +1662064584264341760 +1662064584309342720 +1662064584351343616 +1662064584393344512 +1662064584435345408 +1662064584477346304 +1662064584519347200 +1662064584561348096 +1662064584600348928 +1662064584645349888 +1662064584690350848 +1662064584729351680 +1662064584774352640 +1662064584816353536 +1662064584861354496 +1662064584903355392 +1662064584945356288 +1662064584990357248 +1662064585032358144 +1662064585074359040 +1662064585116359936 +1662064585164360960 +1662064585206361856 +1662064585248362752 +1662064585293363712 +1662064585332364544 +1662064585377365504 +1662064585419366400 +1662064585464367360 +1662064585509368320 +1662064585557369344 +1662064585599370240 +1662064585641371136 +1662064585686372096 +1662064585731373056 +1662064585779374080 +1662064585824375040 +1662064585866375936 +1662064585914376960 +1662064585953377792 +1662064586001378816 +1662064586043379712 +1662064586088380672 +1662064586133381632 +1662064586175382528 +1662064586217383424 +1662064586262384384 +1662064586307385344 +1662064586352386304 +1662064586394387200 +1662064586442388224 +1662064586484389120 +1662064586526390016 +1662064586574391040 +1662064586619392000 +1662064586664392960 +1662064586706393856 +1662064586748394752 +1662064586790395648 +1662064586835396608 +1662064586874397440 +1662064586919398400 +1662064586964399360 +1662064587006400256 +1662064587048401152 +1662064587093402112 +1662064587135403008 +1662064587180403968 +1662064587225404928 +1662064587267405824 +1662064587312406784 +1662064587357407744 +1662064587396408576 +1662064587441409536 +1662064587483410432 +1662064587531411456 +1662064587576412416 +1662064587621413376 +1662064587666414336 +1662064587708415232 +1662064587750416128 +1662064587798417152 +1662064587840418048 +1662064587882418944 +1662064587921419776 +1662064587963420672 +1662064588005421568 +1662064588041422336 +1662064588083423232 +1662064588122424064 +1662064588173425152 +1662064588212425984 +1662064588257426944 +1662064588299427840 +1662064588341428736 +1662064588386429696 +1662064588431430656 +1662064588476431616 +1662064588521432576 +1662064588563433472 +1662064588608434432 +1662064588647435264 +1662064588689436160 +1662064588734437120 +1662064588776438016 +1662064588815438848 +1662064588860439808 +1662064588902440704 +1662064588938441472 +1662064588983442432 +1662064589025443328 +1662064589067444224 +1662064589112445184 +1662064589154446080 +1662064589196446976 +1662064589244448000 +1662064589280448768 +1662064589322449664 +1662064589364450560 +1662064589406451456 +1662064589445452288 +1662064589487453184 +1662064589532454144 +1662064589571454976 +1662064589613455872 +1662064589658456832 +1662064589697457664 +1662064589742458624 +1662064589781459456 +1662064589823460352 +1662064589865461248 +1662064589907462144 +1662064589949463040 +1662064589994464000 +1662064590036464896 +1662064590081465856 +1662064590123466752 +1662064590168467712 +1662064590210468608 +1662064590255469568 +1662064590300470528 +1662064590348471552 +1662064590390472448 +1662064590435473408 +1662064590477474304 +1662064590516475136 +1662064590552475904 +1662064590594476800 +1662064590639477760 +1662064590687478784 +1662064590723479552 +1662064590762480384 +1662064590810481408 +1662064590849482240 +1662064590894483200 +1662064590939484160 +1662064590981485056 +1662064591023485952 +1662064591065486848 +1662064591107487744 +1662064591158488832 +1662064591206489856 +1662064591254490880 +1662064591296491776 +1662064591344492800 +1662064591389493760 +1662064591431494656 +1662064591479495680 +1662064591524496640 +1662064591569497600 +1662064591611498496 +1662064591650499328 +1662064591689500160 +1662064591734501120 +1662064591776502016 +1662064591821502976 +1662064591863503872 +1662064591905504768 +1662064591950505728 +1662064591992506624 +1662064592037507584 +1662064592079508480 +1662064592124509440 +1662064592163510272 +1662064592202511104 +1662064592247512064 +1662064592289512960 +1662064592328513792 +1662064592370514688 +1662064592412515584 +1662064592451516416 +1662064592490517248 +1662064592532518144 +1662064592577519104 +1662064592622520064 +1662064592661520896 +1662064592706521856 +1662064592748522752 +1662064592790523648 +1662064592829524480 +1662064592871525376 +1662064592913526272 +1662064592955527168 +1662064593000528128 +1662064593045529088 +1662064593087529984 +1662064593129530880 +1662064593168531712 +1662064593210532608 +1662064593252533504 +1662064593297534464 +1662064593342535424 +1662064593384536320 +1662064593429537280 +1662064593468538112 +1662064593510539008 +1662064593555539968 +1662064593600540928 +1662064593648541952 +1662064593687542784 +1662064593732543744 +1662064593771544576 +1662064593816545536 +1662064593861546496 +1662064593903547392 +1662064593942548224 +1662064593984549120 +1662064594026550016 +1662064594071550976 +1662064594113551872 +1662064594161552896 +1662064594206553856 +1662064594248554752 +1662064594287555584 +1662064594326556416 +1662064594371557376 +1662064594416558336 +1662064594452559104 +1662064594494560000 +1662064594533560832 +1662064594578561792 +1662064594623562752 +1662064594665563648 +1662064594704564480 +1662064594746565376 +1662064594788566272 +1662064594830567168 +1662064594869568000 +1662064594908568832 +1662064594950569728 +1662064594995570688 +1662064595037571584 +1662064595076572416 +1662064595115573248 +1662064595157574144 +1662064595199575040 +1662064595244576000 +1662064595286576896 +1662064595331577856 +1662064595373578752 +1662064595415579648 +1662064595460580608 +1662064595502581504 +1662064595550582528 +1662064595592583424 +1662064595637584384 +1662064595676585216 +1662064595718586112 +1662064595757586944 +1662064595802587904 +1662064595847588864 +1662064595886589696 +1662064595925590528 +1662064595967591424 +1662064596012592384 +1662064596057593344 +1662064596099594240 +1662064596141595136 +1662064596183596032 +1662064596228596992 +1662064596273597952 +1662064596312598784 +1662064596357599744 +1662064596402600704 +1662064596441601536 +1662064596483602432 +1662064596525603328 +1662064596567604224 +1662064596606605056 +1662064596648605952 +1662064596687606784 +1662064596729607680 +1662064596771608576 +1662064596816609536 +1662064596858610432 +1662064596900611328 +1662064596939612160 +1662064596975612928 +1662064597020613888 +1662064597068614912 +1662064597110615808 +1662064597155616768 +1662064597197617664 +1662064597239618560 +1662064597284619520 +1662064597326620416 +1662064597368621312 +1662064597410622208 +1662064597452623104 +1662064597497624064 +1662064597542625024 +1662064597584625920 +1662064597626626816 +1662064597668627712 +1662064597707628544 +1662064597749629440 +1662064597788630272 +1662064597836631296 +1662064597878632192 +1662064597920633088 +1662064597962633984 +1662064598010635008 +1662064598052635904 +1662064598097636864 +1662064598139637760 +1662064598175638528 +1662064598220639488 +1662064598259640320 +1662064598301641216 +1662064598346642176 +1662064598391643136 +1662064598433644032 +1662064598481645056 +1662064598520645888 +1662064598559646720 +1662064598601647616 +1662064598643648512 +1662064598685649408 +1662064598727650304 +1662064598772651264 +1662064598814652160 +1662064598859653120 +1662064598901654016 +1662064598943654912 +1662064598985655808 +1662064599027656704 +1662064599069657600 +1662064599114658560 +1662064599156659456 +1662064599201660416 +1662064599243661312 +1662064599288662272 +1662064599330663168 +1662064599372664064 +1662064599420665088 +1662064599465666048 +1662064599510667008 +1662064599552667904 +1662064599591668736 +1662064599639669760 +1662064599681670656 +1662064599723671552 +1662064599771672576 +1662064599810673408 +1662064599852674304 +1662064599900675328 +1662064599939676160 +1662064599981677056 +1662064600026678016 +1662064600071678976 +1662064600113679872 +1662064600158680832 +1662064600200681728 +1662064600245682688 +1662064600287683584 +1662064600329684480 +1662064600371685376 +1662064600416686336 +1662064600458687232 +1662064600497688064 +1662064600539688960 +1662064600581689856 +1662064600623690752 +1662064600668691712 +1662064600713692672 +1662064600761693696 +1662064600806694656 +1662064600851695616 +1662064600899696640 +1662064600947697664 +1662064600989698560 +1662064601031699456 +1662064601079700480 +1662064601124701440 +1662064601172702464 +1662064601217703424 +1662064601262704384 +1662064601307705344 +1662064601349706240 +1662064601388707072 +1662064601424707840 +1662064601466708736 +1662064601511709696 +1662064601550710528 +1662064601595711488 +1662064601640712448 +1662064601685713408 +1662064601727714304 +1662064601769715200 +1662064601811716096 +1662064601853716992 +1662064601901718016 +1662064601943718912 +1662064601988719872 +1662064602036720896 +1662064602078721792 +1662064602120722688 +1662064602168723712 +1662064602210724608 +1662064602249725440 +1662064602294726400 +1662064602333727232 +1662064602375728128 +1662064602414728960 +1662064602456729856 +1662064602495730688 +1662064602546731776 +1662064602591732736 +1662064602633733632 +1662064602675734528 +1662064602714735360 +1662064602762736384 +1662064602807737344 +1662064602846738176 +1662064602888739072 +1662064602930739968 +1662064602972740864 +1662064603017741824 +1662064603056742656 +1662064603095743488 +1662064603140744448 +1662064603182745344 +1662064603218746112 +1662064603269747200 +1662064603308748032 +1662064603347748864 +1662064603389749760 +1662064603434750720 +1662064603479751680 +1662064603521752576 +1662064603563753472 +1662064603605754368 +1662064603650755328 +1662064603689756160 +1662064603740757248 +1662064603782758144 +1662064603827759104 +1662064603869760000 +1662064603914760960 +1662064603950761728 +1662064603992762624 +1662064604034763520 +1662064604076764416 +1662064604118765312 +1662064604160766208 +1662064604208767232 +1662064604247768064 +1662064604289768960 +1662064604337769984 +1662064604379770880 +1662064604421771776 +1662064604463772672 +1662064604508773632 +1662064604550774528 +1662064604595775488 +1662064604640776448 +1662064604682777344 +1662064604724778240 +1662064604769779200 +1662064604814780160 +1662064604853780992 +1662064604901782016 +1662064604943782912 +1662064604985783808 +1662064605027784704 +1662064605072785664 +1662064605114786560 +1662064605156787456 +1662064605198788352 +1662064605240789248 +1662064605282790144 +1662064605324791040 +1662064605366791936 +1662064605411792896 +1662064605462793984 +1662064605510795008 +1662064605552795904 +1662064605591796736 +1662064605630797568 +1662064605672798464 +1662064605714799360 +1662064605765800448 +1662064605810801408 +1662064605852802304 +1662064605897803264 +1662064605936804096 +1662064605978804992 +1662064606020805888 +1662064606065806848 +1662064606110807808 +1662064606155808768 +1662064606197809664 +1662064606242810624 +1662064606287811584 +1662064606329812480 +1662064606368813312 +1662064606413814272 +1662064606452815104 +1662064606491815936 +1662064606533816832 +1662064606578817792 +1662064606620818688 +1662064606668819712 +1662064606710820608 +1662064606752821504 +1662064606794822400 +1662064606836823296 +1662064606881824256 +1662064606923825152 +1662064606968826112 +1662064607010827008 +1662064607055827968 +1662064607100828928 +1662064607142829824 +1662064607187830784 +1662064607229831680 +1662064607271832576 +1662064607316833536 +1662064607358834432 +1662064607406835456 +1662064607448836352 +1662064607493837312 +1662064607535838208 +1662064607577839104 +1662064607619840000 +1662064607664840960 +1662064607709841920 +1662064607751842816 +1662064607790843648 +1662064607829844480 +1662064607871845376 +1662064607910846208 +1662064607958847232 +1662064608003848192 +1662064608048849152 +1662064608090850048 +1662064608135851008 +1662064608177851904 +1662064608219852800 +1662064608267853824 +1662064608312854784 +1662064608354855680 +1662064608396856576 +1662064608441857536 +1662064608486858496 +1662064608528859392 +1662064608570860288 +1662064608615861248 +1662064608657862144 +1662064608699863040 +1662064608744864000 +1662064608786864896 +1662064608828865792 +1662064608870866688 +1662064608915867648 +1662064608957868544 +1662064608999869440 +1662064609038870272 +1662064609083871232 +1662064609128872192 +1662064609170873088 +1662064609212873984 +1662064609254874880 +1662064609299875840 +1662064609341876736 +1662064609386877696 +1662064609428878592 +1662064609470879488 +1662064609515880448 +1662064609560881408 +1662064609605882368 +1662064609653883392 +1662064609698884352 +1662064609740885248 +1662064609785886208 +1662064609827887104 +1662064609869888000 +1662064609917889024 +1662064609956889856 +1662064610001890816 +1662064610043891712 +1662064610082892544 +1662064610124893440 +1662064610166894336 +1662064610208895232 +1662064610250896128 +1662064610292897024 +1662064610334897920 +1662064610376898816 +1662064610418899712 +1662064610463900672 +1662064610505901568 +1662064610547902464 +1662064610589903360 +1662064610634904320 +1662064610676905216 +1662064610715906048 +1662064610760907008 +1662064610805907968 +1662064610850908928 +1662064610889909760 +1662064610931910656 +1662064610976911616 +1662064611021912576 +1662064611066913536 +1662064611111914496 +1662064611153915392 +1662064611198916352 +1662064611240917248 +1662064611282918144 +1662064611321918976 +1662064611363919872 +1662064611402920704 +1662064611447921664 +1662064611495922688 +1662064611537923584 +1662064611579924480 +1662064611627925504 +1662064611666926336 +1662064611708927232 +1662064611753928192 +1662064611795929088 +1662064611843930112 +1662064611885931008 +1662064611924931840 +1662064611969932800 +1662064612017933824 +1662064612059934720 +1662064612104935680 +1662064612149936640 +1662064612194937600 +1662064612233938432 +1662064612278939392 +1662064612326940416 +1662064612371941376 +1662064612410942208 +1662064612452943104 +1662064612491943936 +1662064612530944768 +1662064612569945600 +1662064612614946560 +1662064612659947520 +1662064612704948480 +1662064612749949440 +1662064612788950272 +1662064612833951232 +1662064612875952128 +1662064612917953024 +1662064612956953856 +1662064613001954816 +1662064613040955648 +1662064613085956608 +1662064613130957568 +1662064613178958592 +1662064613220959488 +1662064613262960384 +1662064613304961280 +1662064613346962176 +1662064613385963008 +1662064613430963968 +1662064613469964800 +1662064613511965696 +1662064613553966592 +1662064613595967488 +1662064613634968320 +1662064613673969152 +1662064613715970048 +1662064613757970944 +1662064613805971968 +1662064613847972864 +1662064613886973696 +1662064613925974528 +1662064613976975616 +1662064614015976448 +1662064614057977344 +1662064614102978304 +1662064614144979200 +1662064614186980096 +1662064614228980992 +1662064614267981824 +1662064614318982912 +1662064614360983808 +1662064614405984768 +1662064614447985664 +1662064614489986560 +1662064614531987456 +1662064614570988288 +1662064614609989120 +1662064614654990080 +1662064614696990976 +1662064614741991936 +1662064614783992832 +1662064614828993792 +1662064614870994688 +1662064614915995648 +1662064614960996608 +1662064615002997504 +1662064615044998400 +1662064615086999296 +1662064615132000256 +1662064615177001216 +1662064615219002112 +1662064615261003008 +1662064615303003904 +1662064615345004800 +1662064615384005632 +1662064615423006464 +1662064615462007296 +1662064615498008064 +1662064615546009088 +1662064615588009984 +1662064615630010880 +1662064615675011840 +1662064615714012672 +1662064615756013568 +1662064615798014464 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt new file mode 100644 index 0000000000..51983432b0 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt @@ -0,0 +1,2076 @@ +1662125073430662912 +1662125073472663808 +1662125073511664640 +1662125073553665536 +1662125073598666496 +1662125073643667456 +1662125073688668416 +1662125073733669376 +1662125073781670400 +1662125073823671296 +1662125073865672192 +1662125073907673088 +1662125073952674048 +1662125073997675008 +1662125074042675968 +1662125074087676928 +1662125074132677888 +1662125074174678784 +1662125074216679680 +1662125074258680576 +1662125074303681536 +1662125074345682432 +1662125074387683328 +1662125074429684224 +1662125074474685184 +1662125074519686144 +1662125074564687104 +1662125074606688000 +1662125074651688960 +1662125074696689920 +1662125074741690880 +1662125074789691904 +1662125074831692800 +1662125074879693824 +1662125074918694656 +1662125074960695552 +1662125074999696384 +1662125075044697344 +1662125075086698240 +1662125075131699200 +1662125075176700160 +1662125075224701184 +1662125075269702144 +1662125075308702976 +1662125075347703808 +1662125075389704704 +1662125075440705792 +1662125075482706688 +1662125075524707584 +1662125075569708544 +1662125075617709568 +1662125075659710464 +1662125075701711360 +1662125075746712320 +1662125075788713216 +1662125075830714112 +1662125075872715008 +1662125075917715968 +1662125075956716800 +1662125076001717760 +1662125076046718720 +1662125076091719680 +1662125076139720704 +1662125076181721600 +1662125076223722496 +1662125076265723392 +1662125076307724288 +1662125076358725376 +1662125076400726272 +1662125076445727232 +1662125076490728192 +1662125076538729216 +1662125076580730112 +1662125076625731072 +1662125076670732032 +1662125076712732928 +1662125076754733824 +1662125076796734720 +1662125076847735808 +1662125076889736704 +1662125076934737664 +1662125076976738560 +1662125077024739584 +1662125077072740608 +1662125077114741504 +1662125077156742400 +1662125077195743232 +1662125077237744128 +1662125077279745024 +1662125077327746048 +1662125077366746880 +1662125077411747840 +1662125077453748736 +1662125077498749696 +1662125077540750592 +1662125077582751488 +1662125077627752448 +1662125077669753344 +1662125077711754240 +1662125077753755136 +1662125077795756032 +1662125077837756928 +1662125077879757824 +1662125077924758784 +1662125077969759744 +1662125078011760640 +1662125078056761600 +1662125078098762496 +1662125078143763456 +1662125078188764416 +1662125078227765248 +1662125078272766208 +1662125078314767104 +1662125078359768064 +1662125078401768960 +1662125078446769920 +1662125078494770944 +1662125078539771904 +1662125078587772928 +1662125078635773952 +1662125078677774848 +1662125078725775872 +1662125078767776768 +1662125078809777664 +1662125078848778496 +1662125078896779520 +1662125078938780416 +1662125078986781440 +1662125079025782272 +1662125079070783232 +1662125079112784128 +1662125079157785088 +1662125079199785984 +1662125079244786944 +1662125079289787904 +1662125079331788800 +1662125079373789696 +1662125079412790528 +1662125079457791488 +1662125079502792448 +1662125079541793280 +1662125079589794304 +1662125079625795072 +1662125079676796160 +1662125079715796992 +1662125079760797952 +1662125079802798848 +1662125079847799808 +1662125079892800768 +1662125079934801664 +1662125079976802560 +1662125080024803584 +1662125080066804480 +1662125080114805504 +1662125080162806528 +1662125080204807424 +1662125080246808320 +1662125080291809280 +1662125080336810240 +1662125080381811200 +1662125080423812096 +1662125080468813056 +1662125080510813952 +1662125080552814848 +1662125080597815808 +1662125080639816704 +1662125080684817664 +1662125080729818624 +1662125080771819520 +1662125080819820544 +1662125080861821440 +1662125080900822272 +1662125080948823296 +1662125080990824192 +1662125081032825088 +1662125081080826112 +1662125081122827008 +1662125081164827904 +1662125081206828800 +1662125081248829696 +1662125081296830720 +1662125081338831616 +1662125081380832512 +1662125081425833472 +1662125081467834368 +1662125081515835392 +1662125081557836288 +1662125081605837312 +1662125081653838336 +1662125081698839296 +1662125081743840256 +1662125081788841216 +1662125081833842176 +1662125081872843008 +1662125081923844096 +1662125081965844992 +1662125082010845952 +1662125082055846912 +1662125082097847808 +1662125082136848640 +1662125082178849536 +1662125082217850368 +1662125082256851200 +1662125082298852096 +1662125082346853120 +1662125082388854016 +1662125082433854976 +1662125082475855872 +1662125082520856832 +1662125082565857792 +1662125082610858752 +1662125082652859648 +1662125082697860608 +1662125082742861568 +1662125082781862400 +1662125082820863232 +1662125082859864064 +1662125082901864960 +1662125082943865856 +1662125082982866688 +1662125083024867584 +1662125083066868480 +1662125083111869440 +1662125083159870464 +1662125083207871488 +1662125083249872384 +1662125083294873344 +1662125083336874240 +1662125083378875136 +1662125083420876032 +1662125083462876928 +1662125083510877952 +1662125083555878912 +1662125083597879808 +1662125083639880704 +1662125083684881664 +1662125083726882560 +1662125083774883584 +1662125083813884416 +1662125083855885312 +1662125083900886272 +1662125083942887168 +1662125083984888064 +1662125084026888960 +1662125084068889856 +1662125084113890816 +1662125084155891712 +1662125084200892672 +1662125084242893568 +1662125084284894464 +1662125084326895360 +1662125084371896320 +1662125084416897280 +1662125084464898304 +1662125084509899264 +1662125084557900288 +1662125084605901312 +1662125084653902336 +1662125084695903232 +1662125084737904128 +1662125084776904960 +1662125084818905856 +1662125084857906688 +1662125084899907584 +1662125084944908544 +1662125084989909504 +1662125085031910400 +1662125085076911360 +1662125085127912448 +1662125085169913344 +1662125085214914304 +1662125085259915264 +1662125085301916160 +1662125085346917120 +1662125085388918016 +1662125085439919104 +1662125085481920000 +1662125085523920896 +1662125085565921792 +1662125085604922624 +1662125085649923584 +1662125085694924544 +1662125085739925504 +1662125085781926400 +1662125085826927360 +1662125085868928256 +1662125085913929216 +1662125085955930112 +1662125086000931072 +1662125086045932032 +1662125086087932928 +1662125086126933760 +1662125086168934656 +1662125086210935552 +1662125086249936384 +1662125086291937280 +1662125086333938176 +1662125086378939136 +1662125086423940096 +1662125086468941056 +1662125086519942144 +1662125086558942976 +1662125086603943936 +1662125086648944896 +1662125086693945856 +1662125086744946944 +1662125086783947776 +1662125086825948672 +1662125086870949632 +1662125086909950464 +1662125086951951360 +1662125086993952256 +1662125087038953216 +1662125087083954176 +1662125087125955072 +1662125087170956032 +1662125087215956992 +1662125087257957888 +1662125087299958784 +1662125087341959680 +1662125087386960640 +1662125087428961536 +1662125087473962496 +1662125087515963392 +1662125087557964288 +1662125087599965184 +1662125087644966144 +1662125087686967040 +1662125087731968000 +1662125087773968896 +1662125087812969728 +1662125087857970688 +1662125087896971520 +1662125087938972416 +1662125087977973248 +1662125088016974080 +1662125088061975040 +1662125088100975872 +1662125088151976960 +1662125088196977920 +1662125088241978880 +1662125088283979776 +1662125088334980864 +1662125088376981760 +1662125088418982656 +1662125088466983680 +1662125088511984640 +1662125088553985536 +1662125088601986560 +1662125088643987456 +1662125088685988352 +1662125088727989248 +1662125088766990080 +1662125088811991040 +1662125088856992000 +1662125088898992896 +1662125088943993856 +1662125088982994688 +1662125089018995456 +1662125089063996416 +1662125089108997376 +1662125089150998272 +1662125089189999104 +1662125089232000000 +1662125089277000960 +1662125089322001920 +1662125089373003008 +1662125089415003904 +1662125089457004800 +1662125089499005696 +1662125089550006784 +1662125089598007808 +1662125089640008704 +1662125089682009600 +1662125089727010560 +1662125089772011520 +1662125089814012416 +1662125089856013312 +1662125089898014208 +1662125089946015232 +1662125089991016192 +1662125090033017088 +1662125090075017984 +1662125090123019008 +1662125090165019904 +1662125090204020736 +1662125090243021568 +1662125090282022400 +1662125090327023360 +1662125090366024192 +1662125090402024960 +1662125090447025920 +1662125090489026816 +1662125090528027648 +1662125090573028608 +1662125090618029568 +1662125090660030464 +1662125090705031424 +1662125090747032320 +1662125090789033216 +1662125090834034176 +1662125090879035136 +1662125090930036224 +1662125090975037184 +1662125091020038144 +1662125091065039104 +1662125091110040064 +1662125091155041024 +1662125091197041920 +1662125091239042816 +1662125091284043776 +1662125091326044672 +1662125091368045568 +1662125091419046656 +1662125091461047552 +1662125091506048512 +1662125091548049408 +1662125091593050368 +1662125091635051264 +1662125091677052160 +1662125091719053056 +1662125091761053952 +1662125091806054912 +1662125091845055744 +1662125091887056640 +1662125091929057536 +1662125091977058560 +1662125092022059520 +1662125092067060480 +1662125092106061312 +1662125092148062208 +1662125092193063168 +1662125092235064064 +1662125092277064960 +1662125092319065856 +1662125092361066752 +1662125092406067712 +1662125092451068672 +1662125092496069632 +1662125092535070464 +1662125092580071424 +1662125092622072320 +1662125092667073280 +1662125092709074176 +1662125092751075072 +1662125092796076032 +1662125092838076928 +1662125092883077888 +1662125092925078784 +1662125092967079680 +1662125093012080640 +1662125093054081536 +1662125093102082560 +1662125093141083392 +1662125093183084288 +1662125093219085056 +1662125093261085952 +1662125093303086848 +1662125093348087808 +1662125093393088768 +1662125093435089664 +1662125093477090560 +1662125093522091520 +1662125093564092416 +1662125093606093312 +1662125093648094208 +1662125093690095104 +1662125093732096000 +1662125093771096832 +1662125093816097792 +1662125093858098688 +1662125093900099584 +1662125093942100480 +1662125093981101312 +1662125094023102208 +1662125094065103104 +1662125094110104064 +1662125094152104960 +1662125094194105856 +1662125094239106816 +1662125094284107776 +1662125094329108736 +1662125094377109760 +1662125094422110720 +1662125094467111680 +1662125094506112512 +1662125094548113408 +1662125094590114304 +1662125094638115328 +1662125094680116224 +1662125094722117120 +1662125094770118144 +1662125094815119104 +1662125094860120064 +1662125094908121088 +1662125094950121984 +1662125094995122944 +1662125095040123904 +1662125095085124864 +1662125095127125760 +1662125095169126656 +1662125095214127616 +1662125095253128448 +1662125095298129408 +1662125095340130304 +1662125095382131200 +1662125095424132096 +1662125095475133184 +1662125095517134080 +1662125095568135168 +1662125095613136128 +1662125095649136896 +1662125095685137664 +1662125095727138560 +1662125095772139520 +1662125095817140480 +1662125095856141312 +1662125095901142272 +1662125095940143104 +1662125095985144064 +1662125096024144896 +1662125096069145856 +1662125096114146816 +1662125096159147776 +1662125096201148672 +1662125096246149632 +1662125096291150592 +1662125096336151552 +1662125096381152512 +1662125096423153408 +1662125096465154304 +1662125096510155264 +1662125096555156224 +1662125096600157184 +1662125096648158208 +1662125096693159168 +1662125096732160000 +1662125096780161024 +1662125096819161856 +1662125096870162944 +1662125096909163776 +1662125096951164672 +1662125096993165568 +1662125097035166464 +1662125097080167424 +1662125097125168384 +1662125097170169344 +1662125097212170240 +1662125097251171072 +1662125097296172032 +1662125097338172928 +1662125097383173888 +1662125097428174848 +1662125097467175680 +1662125097512176640 +1662125097554177536 +1662125097596178432 +1662125097638179328 +1662125097680180224 +1662125097722181120 +1662125097764182016 +1662125097806182912 +1662125097848183808 +1662125097899184896 +1662125097944185856 +1662125097992186880 +1662125098034187776 +1662125098076188672 +1662125098118189568 +1662125098160190464 +1662125098205191424 +1662125098247192320 +1662125098289193216 +1662125098328194048 +1662125098373195008 +1662125098415195904 +1662125098457196800 +1662125098502197760 +1662125098544198656 +1662125098586199552 +1662125098637200640 +1662125098682201600 +1662125098724202496 +1662125098772203520 +1662125098814204416 +1662125098850205184 +1662125098892206080 +1662125098937207040 +1662125098985208064 +1662125099027208960 +1662125099072209920 +1662125099114210816 +1662125099153211648 +1662125099195212544 +1662125099240213504 +1662125099282214400 +1662125099330215424 +1662125099378216448 +1662125099423217408 +1662125099468218368 +1662125099510219264 +1662125099555220224 +1662125099600221184 +1662125099645222144 +1662125099687223040 +1662125099732224000 +1662125099774224896 +1662125099816225792 +1662125099861226752 +1662125099906227712 +1662125099951228672 +1662125099996229632 +1662125100041230592 +1662125100083231488 +1662125100122232320 +1662125100161233152 +1662125100209234176 +1662125100251235072 +1662125100296236032 +1662125100338236928 +1662125100383237888 +1662125100428238848 +1662125100470239744 +1662125100515240704 +1662125100551241472 +1662125100596242432 +1662125100635243264 +1662125100680244224 +1662125100722245120 +1662125100764246016 +1662125100806246912 +1662125100845247744 +1662125100890248704 +1662125100932249600 +1662125100977250560 +1662125101016251392 +1662125101061252352 +1662125101103253248 +1662125101145254144 +1662125101187255040 +1662125101229255936 +1662125101271256832 +1662125101316257792 +1662125101364258816 +1662125101412259840 +1662125101457260800 +1662125101499261696 +1662125101541262592 +1662125101580263424 +1662125101625264384 +1662125101673265408 +1662125101715266304 +1662125101760267264 +1662125101802268160 +1662125101844269056 +1662125101892270080 +1662125101934270976 +1662125101979271936 +1662125102027272960 +1662125102072273920 +1662125102114274816 +1662125102162275840 +1662125102204276736 +1662125102240277504 +1662125102279278336 +1662125102318279168 +1662125102363280128 +1662125102405281024 +1662125102441281792 +1662125102480282624 +1662125102522283520 +1662125102567284480 +1662125102612285440 +1662125102654286336 +1662125102696287232 +1662125102735288064 +1662125102777288960 +1662125102828290048 +1662125102870290944 +1662125102918291968 +1662125102963292928 +1662125103008293888 +1662125103050294784 +1662125103092295680 +1662125103137296640 +1662125103179297536 +1662125103221298432 +1662125103269299456 +1662125103308300288 +1662125103356301312 +1662125103401302272 +1662125103446303232 +1662125103485304064 +1662125103524304896 +1662125103563305728 +1662125103602306560 +1662125103644307456 +1662125103686308352 +1662125103728309248 +1662125103770310144 +1662125103812311040 +1662125103854311936 +1662125103896312832 +1662125103938313728 +1662125103980314624 +1662125104022315520 +1662125104064316416 +1662125104109317376 +1662125104151318272 +1662125104196319232 +1662125104241320192 +1662125104286321152 +1662125104328322048 +1662125104370322944 +1662125104412323840 +1662125104457324800 +1662125104496325632 +1662125104541326592 +1662125104592327680 +1662125104637328640 +1662125104682329600 +1662125104724330496 +1662125104769331456 +1662125104814332416 +1662125104859333376 +1662125104901334272 +1662125104952335360 +1662125104994336256 +1662125105036337152 +1662125105078338048 +1662125105126339072 +1662125105168339968 +1662125105210340864 +1662125105252341760 +1662125105294342656 +1662125105336343552 +1662125105381344512 +1662125105423345408 +1662125105468346368 +1662125105510347264 +1662125105552348160 +1662125105603349248 +1662125105648350208 +1662125105690351104 +1662125105729351936 +1662125105774352896 +1662125105819353856 +1662125105861354752 +1662125105906355712 +1662125105957356800 +1662125106002357760 +1662125106044358656 +1662125106089359616 +1662125106137360640 +1662125106176361472 +1662125106218362368 +1662125106260363264 +1662125106305364224 +1662125106350365184 +1662125106395366144 +1662125106440367104 +1662125106485368064 +1662125106527368960 +1662125106566369792 +1662125106611370752 +1662125106656371712 +1662125106701372672 +1662125106743373568 +1662125106791374592 +1662125106833375488 +1662125106878376448 +1662125106917377280 +1662125106959378176 +1662125107004379136 +1662125107046380032 +1662125107085380864 +1662125107133381888 +1662125107172382720 +1662125107208383488 +1662125107253384448 +1662125107298385408 +1662125107346386432 +1662125107388387328 +1662125107430388224 +1662125107472389120 +1662125107514390016 +1662125107553390848 +1662125107595391744 +1662125107637392640 +1662125107679393536 +1662125107718394368 +1662125107760395264 +1662125107802396160 +1662125107850397184 +1662125107895398144 +1662125107937399040 +1662125107982400000 +1662125108027400960 +1662125108069401856 +1662125108111402752 +1662125108156403712 +1662125108198404608 +1662125108240405504 +1662125108285406464 +1662125108333407488 +1662125108378408448 +1662125108423409408 +1662125108468410368 +1662125108507411200 +1662125108549412096 +1662125108588412928 +1662125108633413888 +1662125108672414720 +1662125108723415808 +1662125108765416704 +1662125108804417536 +1662125108849418496 +1662125108888419328 +1662125108933420288 +1662125108978421248 +1662125109017422080 +1662125109059422976 +1662125109101423872 +1662125109140424704 +1662125109185425664 +1662125109227426560 +1662125109269427456 +1662125109314428416 +1662125109359429376 +1662125109395430144 +1662125109437431040 +1662125109479431936 +1662125109521432832 +1662125109560433664 +1662125109602434560 +1662125109641435392 +1662125109689436416 +1662125109731437312 +1662125109776438272 +1662125109821439232 +1662125109860440064 +1662125109902440960 +1662125109944441856 +1662125109989442816 +1662125110028443648 +1662125110073444608 +1662125110121445632 +1662125110160446464 +1662125110202447360 +1662125110244448256 +1662125110286449152 +1662125110331450112 +1662125110370450944 +1662125110412451840 +1662125110457452800 +1662125110499453696 +1662125110544454656 +1662125110589455616 +1662125110631456512 +1662125110673457408 +1662125110715458304 +1662125110760459264 +1662125110808460288 +1662125110850461184 +1662125110889462016 +1662125110937463040 +1662125110988464128 +1662125111030465024 +1662125111078466048 +1662125111120466944 +1662125111162467840 +1662125111201468672 +1662125111243469568 +1662125111288470528 +1662125111330471424 +1662125111375472384 +1662125111414473216 +1662125111459474176 +1662125111501475072 +1662125111543475968 +1662125111585476864 +1662125111627477760 +1662125111672478720 +1662125111714479616 +1662125111759480576 +1662125111801481472 +1662125111843482368 +1662125111888483328 +1662125111930484224 +1662125111972485120 +1662125112017486080 +1662125112062487040 +1662125112107488000 +1662125112155489024 +1662125112197489920 +1662125112236490752 +1662125112278491648 +1662125112323492608 +1662125112368493568 +1662125112410494464 +1662125112452495360 +1662125112500496384 +1662125112539497216 +1662125112581498112 +1662125112623499008 +1662125112665499904 +1662125112704500736 +1662125112755501824 +1662125112794502656 +1662125112836503552 +1662125112881504512 +1662125112929505536 +1662125112977506560 +1662125113019507456 +1662125113064508416 +1662125113106509312 +1662125113151510272 +1662125113196511232 +1662125113238512128 +1662125113283513088 +1662125113322513920 +1662125113367514880 +1662125113415515904 +1662125113454516736 +1662125113496517632 +1662125113538518528 +1662125113583519488 +1662125113628520448 +1662125113670521344 +1662125113718522368 +1662125113763523328 +1662125113811524352 +1662125113853525248 +1662125113895526144 +1662125113940527104 +1662125113982528000 +1662125114021528832 +1662125114060529664 +1662125114099530496 +1662125114141531392 +1662125114183532288 +1662125114222533120 +1662125114267534080 +1662125114312535040 +1662125114357536000 +1662125114399536896 +1662125114441537792 +1662125114483538688 +1662125114531539712 +1662125114582540800 +1662125114624541696 +1662125114666542592 +1662125114708543488 +1662125114750544384 +1662125114792545280 +1662125114834546176 +1662125114876547072 +1662125114924548096 +1662125114969549056 +1662125115020550144 +1662125115065551104 +1662125115104551936 +1662125115146552832 +1662125115188553728 +1662125115233554688 +1662125115278555648 +1662125115323556608 +1662125115368557568 +1662125115410558464 +1662125115455559424 +1662125115497560320 +1662125115542561280 +1662125115581562112 +1662125115620562944 +1662125115662563840 +1662125115701564672 +1662125115746565632 +1662125115788566528 +1662125115833567488 +1662125115878568448 +1662125115923569408 +1662125115965570304 +1662125116007571200 +1662125116049572096 +1662125116094573056 +1662125116130573824 +1662125116175574784 +1662125116220575744 +1662125116268576768 +1662125116310577664 +1662125116349578496 +1662125116391579392 +1662125116436580352 +1662125116481581312 +1662125116526582272 +1662125116571583232 +1662125116607584000 +1662125116649584896 +1662125116691585792 +1662125116736586752 +1662125116781587712 +1662125116823588608 +1662125116862589440 +1662125116904590336 +1662125116943591168 +1662125116982592000 +1662125117027592960 +1662125117072593920 +1662125117117594880 +1662125117156595712 +1662125117201596672 +1662125117237597440 +1662125117276598272 +1662125117321599232 +1662125117363600128 +1662125117405601024 +1662125117447601920 +1662125117492602880 +1662125117537603840 +1662125117579604736 +1662125117618605568 +1662125117663606528 +1662125117705607424 +1662125117744608256 +1662125117789609216 +1662125117828610048 +1662125117870610944 +1662125117918611968 +1662125117963612928 +1662125118005613824 +1662125118047614720 +1662125118089615616 +1662125118131616512 +1662125118173617408 +1662125118215618304 +1662125118260619264 +1662125118299620096 +1662125118341620992 +1662125118386621952 +1662125118425622784 +1662125118470623744 +1662125118509624576 +1662125118554625536 +1662125118599626496 +1662125118641627392 +1662125118683628288 +1662125118725629184 +1662125118767630080 +1662125118809630976 +1662125118854631936 +1662125118896632832 +1662125118941633792 +1662125118980634624 +1662125119022635520 +1662125119070636544 +1662125119115637504 +1662125119154638336 +1662125119196639232 +1662125119238640128 +1662125119277640960 +1662125119322641920 +1662125119370642944 +1662125119415643904 +1662125119460644864 +1662125119505645824 +1662125119547646720 +1662125119580647424 +1662125119625648384 +1662125119670649344 +1662125119712650240 +1662125119754651136 +1662125119802652160 +1662125119844653056 +1662125119886653952 +1662125119928654848 +1662125119970655744 +1662125120012656640 +1662125120057657600 +1662125120102658560 +1662125120150659584 +1662125120195660544 +1662125120240661504 +1662125120282662400 +1662125120324663296 +1662125120369664256 +1662125120417665280 +1662125120459666176 +1662125120507667200 +1662125120555668224 +1662125120597669120 +1662125120639670016 +1662125120681670912 +1662125120723671808 +1662125120765672704 +1662125120804673536 +1662125120846674432 +1662125120885675264 +1662125120927676160 +1662125120969677056 +1662125121011677952 +1662125121053678848 +1662125121095679744 +1662125121137680640 +1662125121185681664 +1662125121230682624 +1662125121269683456 +1662125121311684352 +1662125121353685248 +1662125121398686208 +1662125121437687040 +1662125121488688128 +1662125121530689024 +1662125121575689984 +1662125121617690880 +1662125121662691840 +1662125121704692736 +1662125121749693696 +1662125121791694592 +1662125121833695488 +1662125121875696384 +1662125121920697344 +1662125121962698240 +1662125122007699200 +1662125122049700096 +1662125122091700992 +1662125122133701888 +1662125122175702784 +1662125122217703680 +1662125122259704576 +1662125122301705472 +1662125122340706304 +1662125122385707264 +1662125122430708224 +1662125122469709056 +1662125122511709952 +1662125122556710912 +1662125122601711872 +1662125122643712768 +1662125122685713664 +1662125122736714752 +1662125122778715648 +1662125122820716544 +1662125122868717568 +1662125122910718464 +1662125122952719360 +1662125122991720192 +1662125123033721088 +1662125123075721984 +1662125123120722944 +1662125123162723840 +1662125123201724672 +1662125123243725568 +1662125123285726464 +1662125123324727296 +1662125123366728192 +1662125123408729088 +1662125123453730048 +1662125123501731072 +1662125123543731968 +1662125123585732864 +1662125123627733760 +1662125123669734656 +1662125123717735680 +1662125123762736640 +1662125123804737536 +1662125123852738560 +1662125123891739392 +1662125123936740352 +1662125123975741184 +1662125124020742144 +1662125124059742976 +1662125124104743936 +1662125124146744832 +1662125124194745856 +1662125124239746816 +1662125124281747712 +1662125124329748736 +1662125124368749568 +1662125124410750464 +1662125124452751360 +1662125124494752256 +1662125124536753152 +1662125124578754048 +1662125124620754944 +1662125124665755904 +1662125124707756800 +1662125124746757632 +1662125124791758592 +1662125124833759488 +1662125124869760256 +1662125124911761152 +1662125124956762112 +1662125124998763008 +1662125125040763904 +1662125125085764864 +1662125125127765760 +1662125125172766720 +1662125125214767616 +1662125125262768640 +1662125125304769536 +1662125125346770432 +1662125125385771264 +1662125125427772160 +1662125125472773120 +1662125125514774016 +1662125125559774976 +1662125125601775872 +1662125125652776960 +1662125125700777984 +1662125125742778880 +1662125125790779904 +1662125125841780992 +1662125125883781888 +1662125125925782784 +1662125125976783872 +1662125126021784832 +1662125126066785792 +1662125126111786752 +1662125126153787648 +1662125126192788480 +1662125126231789312 +1662125126279790336 +1662125126321791232 +1662125126366792192 +1662125126408793088 +1662125126447793920 +1662125126495794944 +1662125126537795840 +1662125126582796800 +1662125126627797760 +1662125126669798656 +1662125126714799616 +1662125126753800448 +1662125126798801408 +1662125126831802112 +1662125126873803008 +1662125126915803904 +1662125126957804800 +1662125127002805760 +1662125127041806592 +1662125127089807616 +1662125127131808512 +1662125127170809344 +1662125127212810240 +1662125127254811136 +1662125127293811968 +1662125127335812864 +1662125127377813760 +1662125127419814656 +1662125127464815616 +1662125127503816448 +1662125127545817344 +1662125127584818176 +1662125127629819136 +1662125127677820160 +1662125127719821056 +1662125127761821952 +1662125127800822784 +1662125127842823680 +1662125127881824512 +1662125127926825472 +1662125127968826368 +1662125128007827200 +1662125128046828032 +1662125128088828928 +1662125128130829824 +1662125128175830784 +1662125128217831680 +1662125128259832576 +1662125128304833536 +1662125128340834304 +1662125128382835200 +1662125128424836096 +1662125128463836928 +1662125128508837888 +1662125128562839040 +1662125128610840064 +1662125128652840960 +1662125128697841920 +1662125128739842816 +1662125128781843712 +1662125128829844736 +1662125128871845632 +1662125128919846656 +1662125128958847488 +1662125129003848448 +1662125129045849344 +1662125129087850240 +1662125129126851072 +1662125129174852096 +1662125129219853056 +1662125129264854016 +1662125129306854912 +1662125129345855744 +1662125129390856704 +1662125129435857664 +1662125129480858624 +1662125129522859520 +1662125129567860480 +1662125129609861376 +1662125129651862272 +1662125129696863232 +1662125129738864128 +1662125129783865088 +1662125129825865984 +1662125129867866880 +1662125129912867840 +1662125129951868672 +1662125129993869568 +1662125130038870528 +1662125130083871488 +1662125130128872448 +1662125130167873280 +1662125130206874112 +1662125130248875008 +1662125130296876032 +1662125130338876928 +1662125130380877824 +1662125130422878720 +1662125130464879616 +1662125130506880512 +1662125130548881408 +1662125130593882368 +1662125130638883328 +1662125130680884224 +1662125130728885248 +1662125130767886080 +1662125130809886976 +1662125130854887936 +1662125130899888896 +1662125130941889792 +1662125130983890688 +1662125131025891584 +1662125131064892416 +1662125131109893376 +1662125131154894336 +1662125131196895232 +1662125131238896128 +1662125131283897088 +1662125131325897984 +1662125131367898880 +1662125131415899904 +1662125131457900800 +1662125131496901632 +1662125131541902592 +1662125131583903488 +1662125131625904384 +1662125131670905344 +1662125131712906240 +1662125131760907264 +1662125131805908224 +1662125131847909120 +1662125131892910080 +1662125131943911168 +1662125131988912128 +1662125132027912960 +1662125132066913792 +1662125132108914688 +1662125132153915648 +1662125132198916608 +1662125132243917568 +1662125132288918528 +1662125132330919424 +1662125132372920320 +1662125132417921280 +1662125132459922176 +1662125132504923136 +1662125132549924096 +1662125132594925056 +1662125132636925952 +1662125132675926784 +1662125132720927744 +1662125132759928576 +1662125132804929536 +1662125132849930496 +1662125132891931392 +1662125132933932288 +1662125132975933184 +1662125133020934144 +1662125133065935104 +1662125133107936000 +1662125133149936896 +1662125133191937792 +1662125133236938752 +1662125133278939648 +1662125133323940608 +1662125133365941504 +1662125133410942464 +1662125133452943360 +1662125133494944256 +1662125133536945152 +1662125133578946048 +1662125133626947072 +1662125133668947968 +1662125133710948864 +1662125133752949760 +1662125133791950592 +1662125133833951488 +1662125133878952448 +1662125133920953344 +1662125133962954240 +1662125134010955264 +1662125134055956224 +1662125134100957184 +1662125134148958208 +1662125134187959040 +1662125134229959936 +1662125134271960832 +1662125134313961728 +1662125134358962688 +1662125134403963648 +1662125134445964544 +1662125134490965504 +1662125134532966400 +1662125134577967360 +1662125134625968384 +1662125134670969344 +1662125134715970304 +1662125134757971200 +1662125134799972096 +1662125134847973120 +1662125134892974080 +1662125134937975040 +1662125134973975808 +1662125135018976768 +1662125135057977600 +1662125135102978560 +1662125135144979456 +1662125135192980480 +1662125135237981440 +1662125135279982336 +1662125135330983424 +1662125135378984448 +1662125135420985344 +1662125135465986304 +1662125135510987264 +1662125135549988096 +1662125135594989056 +1662125135639990016 +1662125135681990912 +1662125135726991872 +1662125135768992768 +1662125135807993600 +1662125135855994624 +1662125135903995648 +1662125135945996544 +1662125135987997440 +1662125136029998336 +1662125136071999232 +1662125136120000256 +1662125136165001216 +1662125136204002048 +1662125136243002880 +1662125136285003776 +1662125136330004736 +1662125136372005632 +1662125136414006528 +1662125136456007424 +1662125136501008384 +1662125136540009216 +1662125136585010176 +1662125136627011072 +1662125136663011840 +1662125136705012736 +1662125136750013696 +1662125136792014592 +1662125136834015488 +1662125136876016384 +1662125136921017344 +1662125136960018176 +1662125136999019008 +1662125137041019904 +1662125137083020800 +1662125137122021632 +1662125137164022528 +1662125137209023488 +1662125137251024384 +1662125137290025216 +1662125137329026048 +1662125137371026944 +1662125137416027904 +1662125137464028928 +1662125137509029888 +1662125137551030784 +1662125137593031680 +1662125137635032576 +1662125137677033472 +1662125137719034368 +1662125137770035456 +1662125137809036288 +1662125137851037184 +1662125137890038016 +1662125137932038912 +1662125137977039872 +1662125138016040704 +1662125138058041600 +1662125138100042496 +1662125138142043392 +1662125138181044224 +1662125138223045120 +1662125138268046080 +1662125138313047040 +1662125138358048000 +1662125138406049024 +1662125138457050112 +1662125138499051008 +1662125138547052032 +1662125138589052928 +1662125138634053888 +1662125138676054784 +1662125138721055744 +1662125138763056640 +1662125138811057664 +1662125138853058560 +1662125138895059456 +1662125138937060352 +1662125138979061248 +1662125139021062144 +1662125139063063040 +1662125139102063872 +1662125139144064768 +1662125139192065792 +1662125139237066752 +1662125139279067648 +1662125139318068480 +1662125139366069504 +1662125139408070400 +1662125139450071296 +1662125139492072192 +1662125139534073088 +1662125139585074176 +1662125139630075136 +1662125139675076096 +1662125139720077056 +1662125139762077952 +1662125139801078784 +1662125139843079680 +1662125139882080512 +1662125139924081408 +1662125139963082240 +1662125140005083136 +1662125140047084032 +1662125140089084928 +1662125140128085760 +1662125140173086720 +1662125140218087680 +1662125140263088640 +1662125140305089536 +1662125140347090432 +1662125140386091264 +1662125140428092160 +1662125140470093056 +1662125140518094080 +1662125140560094976 +1662125140602095872 +1662125140644096768 +1662125140689097728 +1662125140731098624 +1662125140779099648 +1662125140830100736 +1662125140872101632 +1662125140914102528 +1662125140959103488 +1662125141001104384 +1662125141040105216 +1662125141082106112 +1662125141124107008 +1662125141166107904 +1662125141211108864 +1662125141253109760 +1662125141298110720 +1662125141343111680 +1662125141382112512 +1662125141424113408 +1662125141466114304 +1662125141511115264 +1662125141553116160 +1662125141595117056 +1662125141640118016 +1662125141682118912 +1662125141724119808 +1662125141769120768 +1662125141817121792 +1662125141859122688 +1662125141904123648 +1662125141949124608 +1662125141994125568 +1662125142036126464 +1662125142075127296 +1662125142117128192 +1662125142159129088 +1662125142207130112 +1662125142252131072 +1662125142294131968 +1662125142336132864 +1662125142375133696 +1662125142420134656 +1662125142465135616 +1662125142507136512 +1662125142555137536 +1662125142600138496 +1662125142642139392 +1662125142681140224 +1662125142723141120 +1662125142765142016 +1662125142807142912 +1662125142849143808 +1662125142891144704 +1662125142936145664 +1662125142978146560 +1662125143026147584 +1662125143071148544 +1662125143113149440 +1662125143158150400 +1662125143197151232 +1662125143242152192 +1662125143290153216 +1662125143332154112 +1662125143377155072 +1662125143419155968 +1662125143473157120 +1662125143515158016 +1662125143560158976 +1662125143602159872 +1662125143641160704 +1662125143686161664 +1662125143725162496 +1662125143773163520 +1662125143818164480 +1662125143860165376 +1662125143911166464 +1662125143953167360 +1662125143992168192 +1662125144037169152 +1662125144085170176 +1662125144127171072 +1662125144172172032 +1662125144220173056 +1662125144268174080 +1662125144316175104 +1662125144355175936 +1662125144397176832 +1662125144442177792 +1662125144484178688 +1662125144526179584 +1662125144568180480 +1662125144610181376 +1662125144655182336 +1662125144703183360 +1662125144748184320 +1662125144793185280 +1662125144835186176 +1662125144883187200 +1662125144925188096 +1662125144970189056 +1662125145021190144 +1662125145072191232 +1662125145114192128 +1662125145156193024 +1662125145198193920 +1662125145240194816 +1662125145285195776 +1662125145333196800 +1662125145381197824 +1662125145426198784 +1662125145471199744 +1662125145513200640 +1662125145564201728 +1662125145600202496 +1662125145639203328 +1662125145684204288 +1662125145726205184 +1662125145762205952 +1662125145807206912 +1662125145849207808 +1662125145897208832 +1662125145939209728 +1662125145981210624 +1662125146029211648 +1662125146074212608 +1662125146119213568 +1662125146161214464 +1662125146203215360 +1662125146245216256 +1662125146290217216 +1662125146335218176 +1662125146380219136 +1662125146422220032 +1662125146464220928 +1662125146506221824 +1662125146545222656 +1662125146596223744 +1662125146638224640 +1662125146680225536 +1662125146722226432 +1662125146764227328 +1662125146809228288 +1662125146851229184 +1662125146893230080 +1662125146938231040 +1662125146977231872 +1662125147019232768 +1662125147061233664 +1662125147106234624 +1662125147151235584 +1662125147193236480 +1662125147235237376 +1662125147280238336 +1662125147325239296 +1662125147370240256 +1662125147415241216 +1662125147457242112 +1662125147499243008 +1662125147541243904 +1662125147583244800 +1662125147628245760 +1662125147673246720 +1662125147715247616 +1662125147757248512 +1662125147796249344 +1662125147841250304 +1662125147883251200 +1662125147931252224 +1662125147973253120 +1662125148012253952 +1662125148057254912 +1662125148099255808 +1662125148138256640 +1662125148186257664 +1662125148228258560 +1662125148270259456 +1662125148312260352 +1662125148354261248 +1662125148399262208 +1662125148441263104 +1662125148483264000 +1662125148528264960 +1662125148567265792 +1662125148618266880 +1662125148657267712 +1662125148702268672 +1662125148744269568 +1662125148786270464 +1662125148834271488 +1662125148879272448 +1662125148927273472 +1662125148975274496 +1662125149020275456 +1662125149062276352 +1662125149104277248 +1662125149146278144 +1662125149197279232 +1662125149242280192 +1662125149284281088 +1662125149329282048 +1662125149377283072 +1662125149419283968 +1662125149458284800 +1662125149494285568 +1662125149530286336 +1662125149572287232 +1662125149617288192 +1662125149659289088 +1662125149698289920 +1662125149743290880 +1662125149788291840 +1662125149830292736 +1662125149875293696 +1662125149920294656 +1662125149962295552 +1662125150007296512 +1662125150049297408 +1662125150091298304 +1662125150133299200 +1662125150184300288 +1662125150229301248 +1662125150271302144 +1662125150313303040 +1662125150358304000 +1662125150400304896 +1662125150445305856 +1662125150484306688 +1662125150526307584 +1662125150577308672 +1662125150622309632 +1662125150667310592 +1662125150709311488 +1662125150754312448 +1662125150796313344 +1662125150841314304 +1662125150883315200 +1662125150928316160 +1662125150973317120 +1662125151015318016 +1662125151054318848 +1662125151093319680 +1662125151135320576 +1662125151174321408 +1662125151213322240 +1662125151258323200 +1662125151300324096 +1662125151345325056 +1662125151393326080 +1662125151435326976 +1662125151477327872 +1662125151522328832 +1662125151561329664 +1662125151606330624 +1662125151651331584 +1662125151696332544 +1662125151738333440 +1662125151780334336 +1662125151825335296 +1662125151870336256 +1662125151912337152 +1662125151960338176 +1662125152002339072 +1662125152044339968 +1662125152086340864 +1662125152131341824 +1662125152173342720 +1662125152215343616 +1662125152254344448 +1662125152296345344 +1662125152344346368 +1662125152389347328 +1662125152428348160 +1662125152473349120 +1662125152518350080 +1662125152563351040 +1662125152611352064 +1662125152653352960 +1662125152698353920 +1662125152743354880 +1662125152782355712 +1662125152824356608 +1662125152869357568 +1662125152914358528 +1662125152956359424 +1662125152992360192 +1662125153031361024 +1662125153067361792 +1662125153109362688 +1662125153154363648 +1662125153199364608 +1662125153241365504 +1662125153283366400 +1662125153325367296 +1662125153367368192 +1662125153412369152 +1662125153454370048 +1662125153490370816 +1662125153535371776 +1662125153580372736 +1662125153622373632 +1662125153664374528 +1662125153706375424 +1662125153748376320 +1662125153790377216 +1662125153835378176 +1662125153874379008 +1662125153916379904 +1662125153958380800 +1662125154000381696 +1662125154045382656 +1662125154093383680 +1662125154135384576 +1662125154180385536 +1662125154228386560 +1662125154270387456 +1662125154312388352 +1662125154354389248 +1662125154402390272 +1662125154447391232 +1662125154492392192 +1662125154534393088 +1662125154576393984 +1662125154618394880 +1662125154660395776 +1662125154699396608 +1662125154741397504 +1662125154783398400 +1662125154831399424 +1662125154873400320 +1662125154915401216 +1662125154957402112 +1662125154996402944 +1662125155038403840 +1662125155080404736 +1662125155119405568 +1662125155167406592 +1662125155206407424 +1662125155245408256 +1662125155287409152 +1662125155332410112 +1662125155377411072 +1662125155419411968 +1662125155464412928 +1662125155503413760 +1662125155548414720 +1662125155593415680 +1662125155632416512 +1662125155671417344 +1662125155713418240 +1662125155755419136 +1662125155797420032 +1662125155842420992 +1662125155887421952 +1662125155929422848 +1662125155971423744 +1662125156013424640 +1662125156052425472 +1662125156094426368 +1662125156136427264 +1662125156181428224 +1662125156223429120 +1662125156265430016 +1662125156316431104 +1662125156355431936 +1662125156397432832 +1662125156436433664 +1662125156481434624 +1662125156523435520 +1662125156568436480 +1662125156610437376 +1662125156652438272 +1662125156697439232 +1662125156739440128 +1662125156778440960 +1662125156823441920 +1662125156865442816 +1662125156916443904 +1662125156958444800 +1662125157003445760 +1662125157051446784 +1662125157093447680 +1662125157138448640 +1662125157183449600 +1662125157228450560 +1662125157276451584 +1662125157321452544 +1662125157366453504 +1662125157414454528 +1662125157456455424 +1662125157498456320 +1662125157540457216 +1662125157582458112 +1662125157627459072 +1662125157672460032 +1662125157714460928 +1662125157759461888 +1662125157804462848 +1662125157846463744 +1662125157891464704 +1662125157933465600 +1662125157978466560 +1662125158026467584 +1662125158074468608 +1662125158116469504 +1662125158158470400 +1662125158200471296 +1662125158242472192 +1662125158284473088 +1662125158326473984 +1662125158368474880 +1662125158407475712 +1662125158449476608 +1662125158491477504 +1662125158536478464 +1662125158578479360 +1662125158626480384 +1662125158671481344 +1662125158713482240 +1662125158755483136 +1662125158800484096 +1662125158842484992 +1662125158890486016 +1662125158935486976 +1662125158980487936 +1662125159025488896 +1662125159067489792 +1662125159109490688 +1662125159151491584 +1662125159193492480 +1662125159235493376 +1662125159277494272 +1662125159319495168 +1662125159361496064 +1662125159406497024 +1662125159448497920 +1662125159490498816 +1662125159535499776 +1662125159583500800 +1662125159625501696 +1662125159667502592 +1662125159706503424 +1662125159742504192 +1662125159781505024 +1662125159823505920 +1662125159865506816 +1662125159913507840 +1662125159961508864 +1662125160003509760 +1662125160045510656 +1662125160090511616 +1662125160138512640 +1662125160180513536 +1662125160222514432 +1662125160261515264 +1662125160303516160 +1662125160348517120 +1662125160387517952 +1662125160432518912 +1662125160474519808 +1662125160519520768 +1662125160558521600 +1662125160597522432 +1662125160645523456 +1662125160687524352 +1662125160729525248 +1662125160771526144 +1662125160813527040 +1662125160855527936 +1662125160900528896 +1662125160942529792 +1662125160990530816 +1662125161038531840 +1662125161080532736 +1662125161128533760 +1662125161176534784 +1662125161218535680 +1662125161266536704 +1662125161314537728 +1662125161359538688 +1662125161401539584 +1662125161443540480 +1662125161491541504 +1662125161533542400 +1662125161578543360 +1662125161620544256 +1662125161662545152 +1662125161701545984 +1662125161749547008 +1662125161791547904 +1662125161833548800 +1662125161875549696 +1662125161923550720 +1662125161971551744 +1662125162013552640 +1662125162055553536 +1662125162100554496 +1662125162145555456 +1662125162187556352 +1662125162229557248 +1662125162271558144 +1662125162319559168 +1662125162355559936 +1662125162397560832 +1662125162442561792 +1662125162484562688 +1662125162532563712 +1662125162574564608 +1662125162616565504 +1662125162661566464 +1662125162703567360 +1662125162748568320 +1662125162793569280 +1662125162832570112 +1662125162877571072 +1662125162919571968 +1662125162961572864 +1662125163006573824 +1662125163048574720 +1662125163093575680 +1662125163138576640 +1662125163183577600 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt new file mode 100644 index 0000000000..7283c7fd50 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt @@ -0,0 +1,2489 @@ +1662120285510217728 +1662120285552218624 +1662120285594219520 +1662120285636220416 +1662120285681221376 +1662120285723222272 +1662120285768223232 +1662120285810224128 +1662120285858225152 +1662120285897225984 +1662120285936226816 +1662120285981227776 +1662120286023228672 +1662120286065229568 +1662120286107230464 +1662120286149231360 +1662120286191232256 +1662120286233233152 +1662120286281234176 +1662120286323235072 +1662120286371236096 +1662120286413236992 +1662120286455237888 +1662120286497238784 +1662120286539239680 +1662120286581240576 +1662120286620241408 +1662120286662242304 +1662120286701243136 +1662120286740243968 +1662120286782244864 +1662120286827245824 +1662120286875246848 +1662120286920247808 +1662120286968248832 +1662120287010249728 +1662120287052250624 +1662120287097251584 +1662120287139252480 +1662120287181253376 +1662120287220254208 +1662120287265255168 +1662120287307256064 +1662120287352257024 +1662120287397257984 +1662120287436258816 +1662120287475259648 +1662120287517260544 +1662120287559261440 +1662120287601262336 +1662120287646263296 +1662120287688264192 +1662120287733265152 +1662120287772265984 +1662120287814266880 +1662120287862267904 +1662120287907268864 +1662120287952269824 +1662120288000270848 +1662120288039271680 +1662120288087272704 +1662120288135273728 +1662120288177274624 +1662120288225275648 +1662120288267276544 +1662120288309277440 +1662120288354278400 +1662120288396279296 +1662120288438280192 +1662120288483281152 +1662120288528282112 +1662120288576283136 +1662120288624284160 +1662120288666285056 +1662120288708285952 +1662120288747286784 +1662120288792287744 +1662120288834288640 +1662120288873289472 +1662120288918290432 +1662120288963291392 +1662120289008292352 +1662120289050293248 +1662120289092294144 +1662120289131294976 +1662120289176295936 +1662120289218296832 +1662120289260297728 +1662120289311298816 +1662120289356299776 +1662120289398300672 +1662120289440301568 +1662120289485302528 +1662120289527303424 +1662120289569304320 +1662120289608305152 +1662120289653306112 +1662120289695307008 +1662120289734307840 +1662120289773308672 +1662120289812309504 +1662120289854310400 +1662120289896311296 +1662120289938312192 +1662120289983313152 +1662120290025314048 +1662120290067314944 +1662120290115315968 +1662120290157316864 +1662120290202317824 +1662120290247318784 +1662120290292319744 +1662120290340320768 +1662120290385321728 +1662120290430322688 +1662120290478323712 +1662120290526324736 +1662120290568325632 +1662120290613326592 +1662120290652327424 +1662120290694328320 +1662120290730329088 +1662120290772329984 +1662120290814330880 +1662120290853331712 +1662120290898332672 +1662120290937333504 +1662120290979334400 +1662120291021335296 +1662120291060336128 +1662120291108337152 +1662120291150338048 +1662120291195339008 +1662120291240339968 +1662120291291341056 +1662120291336342016 +1662120291381342976 +1662120291423343872 +1662120291477345024 +1662120291519345920 +1662120291567346944 +1662120291606347776 +1662120291648348672 +1662120291690349568 +1662120291735350528 +1662120291777351424 +1662120291825352448 +1662120291870353408 +1662120291912354304 +1662120291954355200 +1662120291996356096 +1662120292041357056 +1662120292080357888 +1662120292119358720 +1662120292167359744 +1662120292209360640 +1662120292251361536 +1662120292293362432 +1662120292335363328 +1662120292377364224 +1662120292419365120 +1662120292470366208 +1662120292512367104 +1662120292560368128 +1662120292602369024 +1662120292647369984 +1662120292692370944 +1662120292734371840 +1662120292776372736 +1662120292818373632 +1662120292860374528 +1662120292902375424 +1662120292947376384 +1662120292989377280 +1662120293031378176 +1662120293076379136 +1662120293118380032 +1662120293160380928 +1662120293202381824 +1662120293244382720 +1662120293289383680 +1662120293331384576 +1662120293376385536 +1662120293418386432 +1662120293463387392 +1662120293505388288 +1662120293547389184 +1662120293592390144 +1662120293634391040 +1662120293679392000 +1662120293724392960 +1662120293766393856 +1662120293811394816 +1662120293856395776 +1662120293895396608 +1662120293940397568 +1662120293988398592 +1662120294033399552 +1662120294078400512 +1662120294123401472 +1662120294168402432 +1662120294213403392 +1662120294249404160 +1662120294291405056 +1662120294330405888 +1662120294372406784 +1662120294420407808 +1662120294462408704 +1662120294507409664 +1662120294546410496 +1662120294588411392 +1662120294633412352 +1662120294684413440 +1662120294729414400 +1662120294774415360 +1662120294816416256 +1662120294861417216 +1662120294903418112 +1662120294951419136 +1662120294996420096 +1662120295044421120 +1662120295083421952 +1662120295128422912 +1662120295170423808 +1662120295218424832 +1662120295263425792 +1662120295305426688 +1662120295347427584 +1662120295389428480 +1662120295434429440 +1662120295476430336 +1662120295521431296 +1662120295566432256 +1662120295605433088 +1662120295647433984 +1662120295692434944 +1662120295734435840 +1662120295776436736 +1662120295818437632 +1662120295866438656 +1662120295911439616 +1662120295953440512 +1662120295995441408 +1662120296037442304 +1662120296082443264 +1662120296130444288 +1662120296169445120 +1662120296208445952 +1662120296250446848 +1662120296295447808 +1662120296337448704 +1662120296379449600 +1662120296421450496 +1662120296457451264 +1662120296499452160 +1662120296541453056 +1662120296589454080 +1662120296637455104 +1662120296682456064 +1662120296724456960 +1662120296766457856 +1662120296808458752 +1662120296850459648 +1662120296892460544 +1662120296937461504 +1662120296979462400 +1662120297021463296 +1662120297066464256 +1662120297111465216 +1662120297153466112 +1662120297201467136 +1662120297246468096 +1662120297288468992 +1662120297327469824 +1662120297372470784 +1662120297414471680 +1662120297459472640 +1662120297504473600 +1662120297552474624 +1662120297597475584 +1662120297639476480 +1662120297684477440 +1662120297726478336 +1662120297765479168 +1662120297804480000 +1662120297843480832 +1662120297885481728 +1662120297927482624 +1662120297972483584 +1662120298005484288 +1662120298053485312 +1662120298095486208 +1662120298137487104 +1662120298179488000 +1662120298227489024 +1662120298269489920 +1662120298311490816 +1662120298350491648 +1662120298395492608 +1662120298446493696 +1662120298491494656 +1662120298533495552 +1662120298575496448 +1662120298617497344 +1662120298662498304 +1662120298713499392 +1662120298755500288 +1662120298800501248 +1662120298842502144 +1662120298884503040 +1662120298926503936 +1662120298968504832 +1662120299010505728 +1662120299052506624 +1662120299094507520 +1662120299136508416 +1662120299178509312 +1662120299220510208 +1662120299262511104 +1662120299307512064 +1662120299352513024 +1662120299391513856 +1662120299433514752 +1662120299481515776 +1662120299523516672 +1662120299568517632 +1662120299613518592 +1662120299658519552 +1662120299700520448 +1662120299742521344 +1662120299787522304 +1662120299832523264 +1662120299874524160 +1662120299916525056 +1662120299961526016 +1662120300006526976 +1662120300048527872 +1662120300084528640 +1662120300126529536 +1662120300171530496 +1662120300216531456 +1662120300261532416 +1662120300303533312 +1662120300348534272 +1662120300390535168 +1662120300432536064 +1662120300474536960 +1662120300516537856 +1662120300564538880 +1662120300609539840 +1662120300651540736 +1662120300693541632 +1662120300735542528 +1662120300777543424 +1662120300822544384 +1662120300864545280 +1662120300915546368 +1662120300960547328 +1662120301002548224 +1662120301044549120 +1662120301086550016 +1662120301128550912 +1662120301176551936 +1662120301221552896 +1662120301260553728 +1662120301308554752 +1662120301353555712 +1662120301401556736 +1662120301443557632 +1662120301485558528 +1662120301527559424 +1662120301572560384 +1662120301614561280 +1662120301662562304 +1662120301704563200 +1662120301746564096 +1662120301785564928 +1662120301827565824 +1662120301869566720 +1662120301911567616 +1662120301950568448 +1662120301995569408 +1662120302037570304 +1662120302085571328 +1662120302130572288 +1662120302175573248 +1662120302220574208 +1662120302265575168 +1662120302307576064 +1662120302346576896 +1662120302391577856 +1662120302439578880 +1662120302484579840 +1662120302532580864 +1662120302574581760 +1662120302616582656 +1662120302658583552 +1662120302697584384 +1662120302742585344 +1662120302787586304 +1662120302829587200 +1662120302871588096 +1662120302916589056 +1662120302958589952 +1662120303000590848 +1662120303051591936 +1662120303099592960 +1662120303141593856 +1662120303183594752 +1662120303231595776 +1662120303279596800 +1662120303321597696 +1662120303360598528 +1662120303399599360 +1662120303450600448 +1662120303495601408 +1662120303537602304 +1662120303576603136 +1662120303618604032 +1662120303657604864 +1662120303702605824 +1662120303750606848 +1662120303792607744 +1662120303837608704 +1662120303879609600 +1662120303930610688 +1662120303975611648 +1662120304017612544 +1662120304059613440 +1662120304104614400 +1662120304149615360 +1662120304191616256 +1662120304236617216 +1662120304278618112 +1662120304320619008 +1662120304362619904 +1662120304401620736 +1662120304443621632 +1662120304485622528 +1662120304530623488 +1662120304578624512 +1662120304623625472 +1662120304665626368 +1662120304710627328 +1662120304755628288 +1662120304800629248 +1662120304848630272 +1662120304893631232 +1662120304938632192 +1662120304980633088 +1662120305022633984 +1662120305067634944 +1662120305112635904 +1662120305148636672 +1662120305196637696 +1662120305235638528 +1662120305274639360 +1662120305319640320 +1662120305364641280 +1662120305403642112 +1662120305445643008 +1662120305490643968 +1662120305535644928 +1662120305577645824 +1662120305619646720 +1662120305664647680 +1662120305703648512 +1662120305745649408 +1662120305790650368 +1662120305838651392 +1662120305883652352 +1662120305928653312 +1662120305970654208 +1662120306012655104 +1662120306054656000 +1662120306102657024 +1662120306150658048 +1662120306192658944 +1662120306237659904 +1662120306282660864 +1662120306324661760 +1662120306369662720 +1662120306417663744 +1662120306462664704 +1662120306507665664 +1662120306549666560 +1662120306591667456 +1662120306633668352 +1662120306678669312 +1662120306723670272 +1662120306765671168 +1662120306810672128 +1662120306855673088 +1662120306897673984 +1662120306939674880 +1662120306978675712 +1662120307017676544 +1662120307065677568 +1662120307104678400 +1662120307149679360 +1662120307191680256 +1662120307236681216 +1662120307281682176 +1662120307323683072 +1662120307365683968 +1662120307407684864 +1662120307449685760 +1662120307491686656 +1662120307527687424 +1662120307572688384 +1662120307614689280 +1662120307656690176 +1662120307707691264 +1662120307752692224 +1662120307794693120 +1662120307836694016 +1662120307878694912 +1662120307923695872 +1662120307971696896 +1662120308016697856 +1662120308058698752 +1662120308100699648 +1662120308142700544 +1662120308181701376 +1662120308226702336 +1662120308271703296 +1662120308313704192 +1662120308355705088 +1662120308403706112 +1662120308451707136 +1662120308496708096 +1662120308538708992 +1662120308580709888 +1662120308622710784 +1662120308661711616 +1662120308709712640 +1662120308751713536 +1662120308790714368 +1662120308835715328 +1662120308880716288 +1662120308922717184 +1662120308964718080 +1662120309003718912 +1662120309045719808 +1662120309090720768 +1662120309135721728 +1662120309177722624 +1662120309216723456 +1662120309258724352 +1662120309300725248 +1662120309345726208 +1662120309390727168 +1662120309435728128 +1662120309474728960 +1662120309516729856 +1662120309561730816 +1662120309603731712 +1662120309645732608 +1662120309690733568 +1662120309729734400 +1662120309777735424 +1662120309819736320 +1662120309864737280 +1662120309915738368 +1662120309957739264 +1662120310002740224 +1662120310044741120 +1662120310092742144 +1662120310134743040 +1662120310179744000 +1662120310224744960 +1662120310266745856 +1662120310311746816 +1662120310353747712 +1662120310395748608 +1662120310440749568 +1662120310482750464 +1662120310527751424 +1662120310572752384 +1662120310611753216 +1662120310662754304 +1662120310704755200 +1662120310746756096 +1662120310788756992 +1662120310839758080 +1662120310881758976 +1662120310923759872 +1662120310971760896 +1662120311016761856 +1662120311061762816 +1662120311109763840 +1662120311151764736 +1662120311190765568 +1662120311241766656 +1662120311283767552 +1662120311325768448 +1662120311367769344 +1662120311412770304 +1662120311454771200 +1662120311505772288 +1662120311547773184 +1662120311592774144 +1662120311634775040 +1662120311676775936 +1662120311721776896 +1662120311763777792 +1662120311808778752 +1662120311850779648 +1662120311892780544 +1662120311937781504 +1662120311982782464 +1662120312027783424 +1662120312063784192 +1662120312108785152 +1662120312150786048 +1662120312195787008 +1662120312234787840 +1662120312279788800 +1662120312327789824 +1662120312369790720 +1662120312411791616 +1662120312453792512 +1662120312495793408 +1662120312540794368 +1662120312588795392 +1662120312636796416 +1662120312678797312 +1662120312723798272 +1662120312765799168 +1662120312804800000 +1662120312849800960 +1662120312894801920 +1662120312939802880 +1662120312981803776 +1662120313026804736 +1662120313068805632 +1662120313110806528 +1662120313152807424 +1662120313197808384 +1662120313242809344 +1662120313284810240 +1662120313326811136 +1662120313371812096 +1662120313413812992 +1662120313455813888 +1662120313497814784 +1662120313545815808 +1662120313584816640 +1662120313626817536 +1662120313668818432 +1662120313713819392 +1662120313755820288 +1662120313797821184 +1662120313839822080 +1662120313884823040 +1662120313929824000 +1662120313977825024 +1662120314031826176 +1662120314073827072 +1662120314115827968 +1662120314160828928 +1662120314202829824 +1662120314247830784 +1662120314295831808 +1662120314340832768 +1662120314379833600 +1662120314421834496 +1662120314466835456 +1662120314508836352 +1662120314553837312 +1662120314598838272 +1662120314637839104 +1662120314682840064 +1662120314724840960 +1662120314772841984 +1662120314811842816 +1662120314856843776 +1662120314898844672 +1662120314940845568 +1662120314988846592 +1662120315033847552 +1662120315078848512 +1662120315123849472 +1662120315168850432 +1662120315210851328 +1662120315252852224 +1662120315294853120 +1662120315345854208 +1662120315390855168 +1662120315435856128 +1662120315489857280 +1662120315537858304 +1662120315582859264 +1662120315630860288 +1662120315675861248 +1662120315717862144 +1662120315762863104 +1662120315807864064 +1662120315849864960 +1662120315891865856 +1662120315933866752 +1662120315975867648 +1662120316017868544 +1662120316062869504 +1662120316104870400 +1662120316149871360 +1662120316191872256 +1662120316230873088 +1662120316275874048 +1662120316317874944 +1662120316362875904 +1662120316404876800 +1662120316449877760 +1662120316494878720 +1662120316539879680 +1662120316581880576 +1662120316620881408 +1662120316665882368 +1662120316704883200 +1662120316746884096 +1662120316791885056 +1662120316836886016 +1662120316878886912 +1662120316917887744 +1662120316962888704 +1662120317001889536 +1662120317049890560 +1662120317100891648 +1662120317142892544 +1662120317187893504 +1662120317232894464 +1662120317277895424 +1662120317322896384 +1662120317367897344 +1662120317409898240 +1662120317454899200 +1662120317496900096 +1662120317544901120 +1662120317586902016 +1662120317628902912 +1662120317673903872 +1662120317715904768 +1662120317757905664 +1662120317802906624 +1662120317844907520 +1662120317886908416 +1662120317934909440 +1662120317976910336 +1662120318018911232 +1662120318060912128 +1662120318102913024 +1662120318147913984 +1662120318192914944 +1662120318231915776 +1662120318270916608 +1662120318315917568 +1662120318357918464 +1662120318399919360 +1662120318447920384 +1662120318492921344 +1662120318534922240 +1662120318576923136 +1662120318618924032 +1662120318663924992 +1662120318708925952 +1662120318753926912 +1662120318798927872 +1662120318843928832 +1662120318891929856 +1662120318936930816 +1662120318978931712 +1662120319017932544 +1662120319062933504 +1662120319104934400 +1662120319149935360 +1662120319191936256 +1662120319236937216 +1662120319278938112 +1662120319323939072 +1662120319365939968 +1662120319413940992 +1662120319455941888 +1662120319500942848 +1662120319542943744 +1662120319587944704 +1662120319632945664 +1662120319680946688 +1662120319725947648 +1662120319770948608 +1662120319812949504 +1662120319854950400 +1662120319899951360 +1662120319941952256 +1662120319986953216 +1662120320028954112 +1662120320073955072 +1662120320115955968 +1662120320160956928 +1662120320202957824 +1662120320247958784 +1662120320295959808 +1662120320340960768 +1662120320379961600 +1662120320424962560 +1662120320469963520 +1662120320511964416 +1662120320556965376 +1662120320601966336 +1662120320646967296 +1662120320688968192 +1662120320727969024 +1662120320769969920 +1662120320814970880 +1662120320862971904 +1662120320904972800 +1662120320946973696 +1662120320988974592 +1662120321033975552 +1662120321075976448 +1662120321120977408 +1662120321162978304 +1662120321210979328 +1662120321255980288 +1662120321306981376 +1662120321348982272 +1662120321393983232 +1662120321438984192 +1662120321477985024 +1662120321522985984 +1662120321561986816 +1662120321603987712 +1662120321651988736 +1662120321693989632 +1662120321732990464 +1662120321780991488 +1662120321822992384 +1662120321858993152 +1662120321900994048 +1662120321942994944 +1662120321987995904 +1662120322026996736 +1662120322068997632 +1662120322110998528 +1662120322149999360 +1662120322195000320 +1662120322237001216 +1662120322285002240 +1662120322330003200 +1662120322372004096 +1662120322417005056 +1662120322459005952 +1662120322501006848 +1662120322543007744 +1662120322585008640 +1662120322624009472 +1662120322666010368 +1662120322708011264 +1662120322750012160 +1662120322789012992 +1662120322828013824 +1662120322882014976 +1662120322924015872 +1662120322975016960 +1662120323014017792 +1662120323056018688 +1662120323101019648 +1662120323146020608 +1662120323185021440 +1662120323227022336 +1662120323272023296 +1662120323317024256 +1662120323359025152 +1662120323401026048 +1662120323443026944 +1662120323488027904 +1662120323530028800 +1662120323575029760 +1662120323620030720 +1662120323668031744 +1662120323710032640 +1662120323749033472 +1662120323794034432 +1662120323836035328 +1662120323875036160 +1662120323920037120 +1662120323959037952 +1662120324004038912 +1662120324046039808 +1662120324091040768 +1662120324139041792 +1662120324178042624 +1662120324223043584 +1662120324265044480 +1662120324304045312 +1662120324343046144 +1662120324385047040 +1662120324427047936 +1662120324469048832 +1662120324517049856 +1662120324559050752 +1662120324601051648 +1662120324640052480 +1662120324682053376 +1662120324724054272 +1662120324766055168 +1662120324808056064 +1662120324853057024 +1662120324901058048 +1662120324943058944 +1662120324988059904 +1662120325036060928 +1662120325078061824 +1662120325120062720 +1662120325159063552 +1662120325204064512 +1662120325255065600 +1662120325300066560 +1662120325342067456 +1662120325384068352 +1662120325429069312 +1662120325468070144 +1662120325510071040 +1662120325549071872 +1662120325603073024 +1662120325642073856 +1662120325687074816 +1662120325726075648 +1662120325768076544 +1662120325810077440 +1662120325852078336 +1662120325894079232 +1662120325939080192 +1662120325984081152 +1662120326026082048 +1662120326074083072 +1662120326119084032 +1662120326164084992 +1662120326209085952 +1662120326257086976 +1662120326302087936 +1662120326344088832 +1662120326386089728 +1662120326428090624 +1662120326470091520 +1662120326512092416 +1662120326554093312 +1662120326596094208 +1662120326638095104 +1662120326683096064 +1662120326725096960 +1662120326767097856 +1662120326809098752 +1662120326857099776 +1662120326902100736 +1662120326947101696 +1662120326995102720 +1662120327040103680 +1662120327088104704 +1662120327133105664 +1662120327175106560 +1662120327220107520 +1662120327268108544 +1662120327310109440 +1662120327355110400 +1662120327394111232 +1662120327436112128 +1662120327490113280 +1662120327532114176 +1662120327574115072 +1662120327619116032 +1662120327661116928 +1662120327706117888 +1662120327748118784 +1662120327793119744 +1662120327832120576 +1662120327874121472 +1662120327919122432 +1662120327964123392 +1662120328009124352 +1662120328054125312 +1662120328099126272 +1662120328144127232 +1662120328189128192 +1662120328231129088 +1662120328273129984 +1662120328312130816 +1662120328354131712 +1662120328396132608 +1662120328441133568 +1662120328486134528 +1662120328531135488 +1662120328573136384 +1662120328612137216 +1662120328660138240 +1662120328705139200 +1662120328747140096 +1662120328795141120 +1662120328837142016 +1662120328879142912 +1662120328921143808 +1662120328963144704 +1662120329005145600 +1662120329047146496 +1662120329089147392 +1662120329137148416 +1662120329182149376 +1662120329227150336 +1662120329272151296 +1662120329317152256 +1662120329362153216 +1662120329410154240 +1662120329455155200 +1662120329497156096 +1662120329536156928 +1662120329581157888 +1662120329623158784 +1662120329668159744 +1662120329713160704 +1662120329758161664 +1662120329800162560 +1662120329842163456 +1662120329884164352 +1662120329926165248 +1662120329971166208 +1662120330010167040 +1662120330052167936 +1662120330100168960 +1662120330145169920 +1662120330190170880 +1662120330235171840 +1662120330277172736 +1662120330316173568 +1662120330364174592 +1662120330406175488 +1662120330448176384 +1662120330487177216 +1662120330526178048 +1662120330571179008 +1662120330613179904 +1662120330658180864 +1662120330703181824 +1662120330748182784 +1662120330793183744 +1662120330838184704 +1662120330877185536 +1662120330928186624 +1662120330967187456 +1662120331006188288 +1662120331051189248 +1662120331090190080 +1662120331132190976 +1662120331174191872 +1662120331219192832 +1662120331261193728 +1662120331306194688 +1662120331354195712 +1662120331393196544 +1662120331435197440 +1662120331477198336 +1662120331513199104 +1662120331561200128 +1662120331609201152 +1662120331648201984 +1662120331690202880 +1662120331735203840 +1662120331780204800 +1662120331825205760 +1662120331864206592 +1662120331906207488 +1662120331951208448 +1662120331996209408 +1662120332038210304 +1662120332080211200 +1662120332125212160 +1662120332164212992 +1662120332206213888 +1662120332251214848 +1662120332293215744 +1662120332335216640 +1662120332374217472 +1662120332416218368 +1662120332458219264 +1662120332500220160 +1662120332545221120 +1662120332584221952 +1662120332629222912 +1662120332674223872 +1662120332719224832 +1662120332761225728 +1662120332806226688 +1662120332848227584 +1662120332890228480 +1662120332932229376 +1662120332974230272 +1662120333019231232 +1662120333064232192 +1662120333106233088 +1662120333154234112 +1662120333199235072 +1662120333238235904 +1662120333286236928 +1662120333328237824 +1662120333367238656 +1662120333409239552 +1662120333448240384 +1662120333490241280 +1662120333529242112 +1662120333571243008 +1662120333610243840 +1662120333649244672 +1662120333691245568 +1662120333736246528 +1662120333781247488 +1662120333826248448 +1662120333868249344 +1662120333913250304 +1662120333958251264 +1662120334003252224 +1662120334048253184 +1662120334090254080 +1662120334132254976 +1662120334171255808 +1662120334213256704 +1662120334258257664 +1662120334303258624 +1662120334348259584 +1662120334393260544 +1662120334438261504 +1662120334480262400 +1662120334525263360 +1662120334570264320 +1662120334612265216 +1662120334657266176 +1662120334702267136 +1662120334744268032 +1662120334795269120 +1662120334837270016 +1662120334882270976 +1662120334918271744 +1662120334960272640 +1662120335002273536 +1662120335047274496 +1662120335095275520 +1662120335137276416 +1662120335185277440 +1662120335230278400 +1662120335272279296 +1662120335314280192 +1662120335362281216 +1662120335404282112 +1662120335449283072 +1662120335485283840 +1662120335530284800 +1662120335572285696 +1662120335614286592 +1662120335656287488 +1662120335701288448 +1662120335746289408 +1662120335788290304 +1662120335833291264 +1662120335878292224 +1662120335923293184 +1662120335962294016 +1662120336010295040 +1662120336052295936 +1662120336088296704 +1662120336127297536 +1662120336172298496 +1662120336214299392 +1662120336250300160 +1662120336292301056 +1662120336334301952 +1662120336376302848 +1662120336427303936 +1662120336475304960 +1662120336517305856 +1662120336562306816 +1662120336601307648 +1662120336637308416 +1662120336679309312 +1662120336724310272 +1662120336763311104 +1662120336799311872 +1662120336838312704 +1662120336883313664 +1662120336922314496 +1662120336970315520 +1662120337015316480 +1662120337057317376 +1662120337102318336 +1662120337141319168 +1662120337186320128 +1662120337231321088 +1662120337276322048 +1662120337324323072 +1662120337369324032 +1662120337414324992 +1662120337459325952 +1662120337504326912 +1662120337546327808 +1662120337591328768 +1662120337636329728 +1662120337675330560 +1662120337711331328 +1662120337756332288 +1662120337801333248 +1662120337843334144 +1662120337882334976 +1662120337924335872 +1662120337969336832 +1662120338014337792 +1662120338059338752 +1662120338104339712 +1662120338146340608 +1662120338191341568 +1662120338233342464 +1662120338275343360 +1662120338323344384 +1662120338368345344 +1662120338416346368 +1662120338461347328 +1662120338503348224 +1662120338548349184 +1662120338590350080 +1662120338632350976 +1662120338674351872 +1662120338713352704 +1662120338752353536 +1662120338797354496 +1662120338842355456 +1662120338890356480 +1662120338932357376 +1662120338974358272 +1662120339016359168 +1662120339055360000 +1662120339100360960 +1662120339145361920 +1662120339190362880 +1662120339241363968 +1662120339286364928 +1662120339334365952 +1662120339382366976 +1662120339427367936 +1662120339466368768 +1662120339502369536 +1662120339544370432 +1662120339586371328 +1662120339625372160 +1662120339667373056 +1662120339706373888 +1662120339748374784 +1662120339793375744 +1662120339832376576 +1662120339874377472 +1662120339916378368 +1662120339958379264 +1662120340000380160 +1662120340042381056 +1662120340084381952 +1662120340126382848 +1662120340171383808 +1662120340216384768 +1662120340258385664 +1662120340306386688 +1662120340351387648 +1662120340393388544 +1662120340432389376 +1662120340480390400 +1662120340522391296 +1662120340564392192 +1662120340609393152 +1662120340651394048 +1662120340696395008 +1662120340738395904 +1662120340780396800 +1662120340825397760 +1662120340873398784 +1662120340912399616 +1662120340957400576 +1662120341002401536 +1662120341044402432 +1662120341089403392 +1662120341131404288 +1662120341176405248 +1662120341215406080 +1662120341263407104 +1662120341305408000 +1662120341344408832 +1662120341383409664 +1662120341428410624 +1662120341470411520 +1662120341512412416 +1662120341560413440 +1662120341605414400 +1662120341650415360 +1662120341692416256 +1662120341734417152 +1662120341773417984 +1662120341815418880 +1662120341857419776 +1662120341899420672 +1662120341938421504 +1662120341980422400 +1662120342025423360 +1662120342067424256 +1662120342112425216 +1662120342160426240 +1662120342202427136 +1662120342244428032 +1662120342286428928 +1662120342328429824 +1662120342373430784 +1662120342418431744 +1662120342466432768 +1662120342514433792 +1662120342556434688 +1662120342595435520 +1662120342637436416 +1662120342676437248 +1662120342718438144 +1662120342760439040 +1662120342799439872 +1662120342838440704 +1662120342877441536 +1662120342925442560 +1662120342964443392 +1662120343009444352 +1662120343048445184 +1662120343090446080 +1662120343135447040 +1662120343177447936 +1662120343222448896 +1662120343264449792 +1662120343309450752 +1662120343351451648 +1662120343402452736 +1662120343447453696 +1662120343489454592 +1662120343534455552 +1662120343579456512 +1662120343618457344 +1662120343663458304 +1662120343711459328 +1662120343762460416 +1662120343801461248 +1662120343849462272 +1662120343891463168 +1662120343936464128 +1662120343978465024 +1662120344023465984 +1662120344062466816 +1662120344107467776 +1662120344146468608 +1662120344188469504 +1662120344230470400 +1662120344275471360 +1662120344314472192 +1662120344356473088 +1662120344401474048 +1662120344443474944 +1662120344491475968 +1662120344533476864 +1662120344581477888 +1662120344620478720 +1662120344665479680 +1662120344713480704 +1662120344758481664 +1662120344800482560 +1662120344842483456 +1662120344884484352 +1662120344926485248 +1662120344968486144 +1662120345010487040 +1662120345055488000 +1662120345100488960 +1662120345145489920 +1662120345187490816 +1662120345229491712 +1662120345268492544 +1662120345310493440 +1662120345358494464 +1662120345397495296 +1662120345439496192 +1662120345484497152 +1662120345526498048 +1662120345568498944 +1662120345613499904 +1662120345655500800 +1662120345697501696 +1662120345736502528 +1662120345781503488 +1662120345826504448 +1662120345874505472 +1662120345919506432 +1662120345961507328 +1662120346006508288 +1662120346051509248 +1662120346096510208 +1662120346138511104 +1662120346180512000 +1662120346219512832 +1662120346264513792 +1662120346309514752 +1662120346354515712 +1662120346399516672 +1662120346441517568 +1662120346486518528 +1662120346528519424 +1662120346573520384 +1662120346618521344 +1662120346660522240 +1662120346702523136 +1662120346744524032 +1662120346786524928 +1662120346828525824 +1662120346876526848 +1662120346915527680 +1662120346957528576 +1662120347005529600 +1662120347047530496 +1662120347086531328 +1662120347128532224 +1662120347170533120 +1662120347212534016 +1662120347257534976 +1662120347299535872 +1662120347344536832 +1662120347389537792 +1662120347431538688 +1662120347476539648 +1662120347518540544 +1662120347560541440 +1662120347608542464 +1662120347653543424 +1662120347695544320 +1662120347737545216 +1662120347779546112 +1662120347824547072 +1662120347863547904 +1662120347905548800 +1662120347947549696 +1662120347986550528 +1662120348031551488 +1662120348073552384 +1662120348118553344 +1662120348157554176 +1662120348202555136 +1662120348244556032 +1662120348289556992 +1662120348331557888 +1662120348376558848 +1662120348421559808 +1662120348460560640 +1662120348502561536 +1662120348544562432 +1662120348589563392 +1662120348637564416 +1662120348679565312 +1662120348718566144 +1662120348760567040 +1662120348802567936 +1662120348841568768 +1662120348880569600 +1662120348922570496 +1662120348964571392 +1662120349009572352 +1662120349057573376 +1662120349102574336 +1662120349144575232 +1662120349186576128 +1662120349231577088 +1662120349273577984 +1662120349318578944 +1662120349363579904 +1662120349402580736 +1662120349444581632 +1662120349489582592 +1662120349531583488 +1662120349573584384 +1662120349612585216 +1662120349651586048 +1662120349696587008 +1662120349738587904 +1662120349780588800 +1662120349822589696 +1662120349864590592 +1662120349906591488 +1662120349948592384 +1662120349990593280 +1662120350032594176 +1662120350077595136 +1662120350122596096 +1662120350164596992 +1662120350209597952 +1662120350251598848 +1662120350293599744 +1662120350338600704 +1662120350380601600 +1662120350425602560 +1662120350467603456 +1662120350509604352 +1662120350551605248 +1662120350596606208 +1662120350638607104 +1662120350683608064 +1662120350728609024 +1662120350770609920 +1662120350812610816 +1662120350857611776 +1662120350902612736 +1662120350944613632 +1662120350986614528 +1662120351028615424 +1662120351067616256 +1662120351109617152 +1662120351151618048 +1662120351193618944 +1662120351235619840 +1662120351280620800 +1662120351325621760 +1662120351367622656 +1662120351409623552 +1662120351451624448 +1662120351496625408 +1662120351547626496 +1662120351589627392 +1662120351637628416 +1662120351679629312 +1662120351721630208 +1662120351766631168 +1662120351811632128 +1662120351856633088 +1662120351898633984 +1662120351940634880 +1662120351985635840 +1662120352027636736 +1662120352069637632 +1662120352111638528 +1662120352153639424 +1662120352195640320 +1662120352240641280 +1662120352285642240 +1662120352324643072 +1662120352366643968 +1662120352408644864 +1662120352447645696 +1662120352489646592 +1662120352534647552 +1662120352573648384 +1662120352621649408 +1662120352663650304 +1662120352705651200 +1662120352750652160 +1662120352795653120 +1662120352837654016 +1662120352882654976 +1662120352924655872 +1662120352972656896 +1662120353011657728 +1662120353053658624 +1662120353098659584 +1662120353143660544 +1662120353185661440 +1662120353227662336 +1662120353272663296 +1662120353320664320 +1662120353365665280 +1662120353410666240 +1662120353452667136 +1662120353494668032 +1662120353539668992 +1662120353581669888 +1662120353632670976 +1662120353683672064 +1662120353725672960 +1662120353767673856 +1662120353812674816 +1662120353854675712 +1662120353902676736 +1662120353947677696 +1662120353992678656 +1662120354037679616 +1662120354079680512 +1662120354121681408 +1662120354166682368 +1662120354208683264 +1662120354250684160 +1662120354292685056 +1662120354334685952 +1662120354376686848 +1662120354418687744 +1662120354463688704 +1662120354505689600 +1662120354547690496 +1662120354592691456 +1662120354637692416 +1662120354682693376 +1662120354727694336 +1662120354775695360 +1662120354817696256 +1662120354859697152 +1662120354901698048 +1662120354940698880 +1662120354982699776 +1662120355024700672 +1662120355066701568 +1662120355114702592 +1662120355162703616 +1662120355210704640 +1662120355249705472 +1662120355297706496 +1662120355336707328 +1662120355378708224 +1662120355420709120 +1662120355459709952 +1662120355504710912 +1662120355555712000 +1662120355600712960 +1662120355648713984 +1662120355690714880 +1662120355732715776 +1662120355777716736 +1662120355819717632 +1662120355861718528 +1662120355903719424 +1662120355945720320 +1662120355987721216 +1662120356029722112 +1662120356077723136 +1662120356122724096 +1662120356161724928 +1662120356203725824 +1662120356245726720 +1662120356290727680 +1662120356338728704 +1662120356383729664 +1662120356428730624 +1662120356470731520 +1662120356518732544 +1662120356560733440 +1662120356605734400 +1662120356647735296 +1662120356689736192 +1662120356731737088 +1662120356773737984 +1662120356815738880 +1662120356857739776 +1662120356896740608 +1662120356944741632 +1662120356986742528 +1662120357025743360 +1662120357070744320 +1662120357109745152 +1662120357154746112 +1662120357196747008 +1662120357241747968 +1662120357277748736 +1662120357319749632 +1662120357361750528 +1662120357406751488 +1662120357454752512 +1662120357499753472 +1662120357541754368 +1662120357586755328 +1662120357625756160 +1662120357664756992 +1662120357712758016 +1662120357754758912 +1662120357793759744 +1662120357835760640 +1662120357880761600 +1662120357925762560 +1662120357973763584 +1662120358015764480 +1662120358060765440 +1662120358102766336 +1662120358147767296 +1662120358195768320 +1662120358237769216 +1662120358285770240 +1662120358327771136 +1662120358375772160 +1662120358417773056 +1662120358459773952 +1662120358501774848 +1662120358543775744 +1662120358591776768 +1662120358636777728 +1662120358678778624 +1662120358726779648 +1662120358771780608 +1662120358813781504 +1662120358852782336 +1662120358894783232 +1662120358933784064 +1662120358975784960 +1662120359020785920 +1662120359065786880 +1662120359107787776 +1662120359158788864 +1662120359200789760 +1662120359242790656 +1662120359284791552 +1662120359326792448 +1662120359368793344 +1662120359407794176 +1662120359452795136 +1662120359494796032 +1662120359539796992 +1662120359581797888 +1662120359623798784 +1662120359671799808 +1662120359713800704 +1662120359755801600 +1662120359803802624 +1662120359845803520 +1662120359887804416 +1662120359926805248 +1662120359971806208 +1662120360013807104 +1662120360064808192 +1662120360106809088 +1662120360148809984 +1662120360190810880 +1662120360232811776 +1662120360274812672 +1662120360316813568 +1662120360361814528 +1662120360403815424 +1662120360445816320 +1662120360487817216 +1662120360529818112 +1662120360571819008 +1662120360613819904 +1662120360658820864 +1662120360703821824 +1662120360748822784 +1662120360787823616 +1662120360829824512 +1662120360877825536 +1662120360919826432 +1662120360964827392 +1662120361009828352 +1662120361054829312 +1662120361105830400 +1662120361150831360 +1662120361189832192 +1662120361231833088 +1662120361276834048 +1662120361318834944 +1662120361360835840 +1662120361408836864 +1662120361450837760 +1662120361489838592 +1662120361531839488 +1662120361573840384 +1662120361615841280 +1662120361660842240 +1662120361702843136 +1662120361747844096 +1662120361786844928 +1662120361831845888 +1662120361876846848 +1662120361918847744 +1662120361963848704 +1662120362008849664 +1662120362053850624 +1662120362092851456 +1662120362137852416 +1662120362179853312 +1662120362224854272 +1662120362266855168 +1662120362308856064 +1662120362347856896 +1662120362389857792 +1662120362428858624 +1662120362470859520 +1662120362515860480 +1662120362554861312 +1662120362596862208 +1662120362641863168 +1662120362680864000 +1662120362725864960 +1662120362767865856 +1662120362815866880 +1662120362857867776 +1662120362905868800 +1662120362947869696 +1662120362995870720 +1662120363037871616 +1662120363082872576 +1662120363124873472 +1662120363166874368 +1662120363208875264 +1662120363247876096 +1662120363289876992 +1662120363331877888 +1662120363373878784 +1662120363415879680 +1662120363454880512 +1662120363499881472 +1662120363544882432 +1662120363589883392 +1662120363634884352 +1662120363676885248 +1662120363718886144 +1662120363760887040 +1662120363802887936 +1662120363847888896 +1662120363886889728 +1662120363928890624 +1662120363973891584 +1662120364018892544 +1662120364060893440 +1662120364102894336 +1662120364147895296 +1662120364192896256 +1662120364231897088 +1662120364273897984 +1662120364315898880 +1662120364360899840 +1662120364405900800 +1662120364447901696 +1662120364489902592 +1662120364531903488 +1662120364573904384 +1662120364618905344 +1662120364666906368 +1662120364708907264 +1662120364756908288 +1662120364798909184 +1662120364843910144 +1662120364888911104 +1662120364930912000 +1662120364975912960 +1662120365020913920 +1662120365065914880 +1662120365110915840 +1662120365158916864 +1662120365200917760 +1662120365242918656 +1662120365284919552 +1662120365323920384 +1662120365365921280 +1662120365407922176 +1662120365449923072 +1662120365488923904 +1662120365527924736 +1662120365566925568 +1662120365611926528 +1662120365653927424 +1662120365698928384 +1662120365743929344 +1662120365788930304 +1662120365830931200 +1662120365872932096 +1662120365917933056 +1662120365959933952 +1662120365998934784 +1662120366040935680 +1662120366082936576 +1662120366124937472 +1662120366166938368 +1662120366211939328 +1662120366253940224 +1662120366301941248 +1662120366343942144 +1662120366397943296 +1662120366442944256 +1662120366484945152 +1662120366529946112 +1662120366574947072 +1662120366619948032 +1662120366661948928 +1662120366706949888 +1662120366748950784 +1662120366790951680 +1662120366835952640 +1662120366874953472 +1662120366916954368 +1662120366955955200 +1662120366994956032 +1662120367039956992 +1662120367081957888 +1662120367126958848 +1662120367168959744 +1662120367210960640 +1662120367249961472 +1662120367294962432 +1662120367336963328 +1662120367375964160 +1662120367420965120 +1662120367465966080 +1662120367507966976 +1662120367546967808 +1662120367591968768 +1662120367636969728 +1662120367675970560 +1662120367714971392 +1662120367759972352 +1662120367801973248 +1662120367846974208 +1662120367888975104 +1662120367933976064 +1662120367975976960 +1662120368020977920 +1662120368065978880 +1662120368110979840 +1662120368152980736 +1662120368194981632 +1662120368236982528 +1662120368275983360 +1662120368320984320 +1662120368359985152 +1662120368404986112 +1662120368446987008 +1662120368485987840 +1662120368530988800 +1662120368575989760 +1662120368617990656 +1662120368662991616 +1662120368704992512 +1662120368746993408 +1662120368791994368 +1662120368833995264 +1662120368875996160 +1662120368920997120 +1662120368965998080 +1662120369010999040 +1662120369056000000 +1662120369101000960 +1662120369146001920 +1662120369188002816 +1662120369230003712 +1662120369272004608 +1662120369317005568 +1662120369359006464 +1662120369404007424 +1662120369449008384 +1662120369500009472 +1662120369542010368 +1662120369584011264 +1662120369623012096 +1662120369665012992 +1662120369704013824 +1662120369749014784 +1662120369794015744 +1662120369836016640 +1662120369878017536 +1662120369923018496 +1662120369965019392 +1662120370007020288 +1662120370046021120 +1662120370088022016 +1662120370130022912 +1662120370175023872 +1662120370217024768 +1662120370259025664 +1662120370298026496 +1662120370340027392 +1662120370385028352 +1662120370427029248 +1662120370469030144 +1662120370511031040 +1662120370556032000 +1662120370604033024 +1662120370652034048 +1662120370697035008 +1662120370739035904 +1662120370781036800 +1662120370826037760 +1662120370877038848 +1662120370919039744 +1662120370961040640 +1662120371000041472 +1662120371045042432 +1662120371087043328 +1662120371126044160 +1662120371162044928 +1662120371207045888 +1662120371252046848 +1662120371294047744 +1662120371336048640 +1662120371381049600 +1662120371423050496 +1662120371468051456 +1662120371510052352 +1662120371552053248 +1662120371597054208 +1662120371642055168 +1662120371690056192 +1662120371735057152 +1662120371786058240 +1662120371828059136 +1662120371867059968 +1662120371912060928 +1662120371960061952 +1662120372005062912 +1662120372053063936 +1662120372098064896 +1662120372143065856 +1662120372185066752 +1662120372227067648 +1662120372272068608 +1662120372317069568 +1662120372362070528 +1662120372407071488 +1662120372452072448 +1662120372494073344 +1662120372536074240 +1662120372578075136 +1662120372623076096 +1662120372668077056 +1662120372713078016 +1662120372755078912 +1662120372800079872 +1662120372839080704 +1662120372881081600 +1662120372923082496 +1662120372968083456 +1662120373016084480 +1662120373055085312 +1662120373097086208 +1662120373139087104 +1662120373178087936 +1662120373220088832 +1662120373262089728 +1662120373307090688 +1662120373355091712 +1662120373394092544 +1662120373436093440 +1662120373481094400 +1662120373523095296 +1662120373565096192 +1662120373604097024 +1662120373652098048 +1662120373697099008 +1662120373748100096 +1662120373790100992 +1662120373832101888 +1662120373874102784 +1662120373919103744 +1662120373961104640 +1662120374000105472 +1662120374045106432 +1662120374090107392 +1662120374138108416 +1662120374183109376 +1662120374225110272 +1662120374270111232 +1662120374312112128 +1662120374354113024 +1662120374396113920 +1662120374438114816 +1662120374480115712 +1662120374525116672 +1662120374564117504 +1662120374609118464 +1662120374651119360 +1662120374699120384 +1662120374741121280 +1662120374786122240 +1662120374831123200 +1662120374873124096 +1662120374918125056 +1662120374966126080 +1662120375008126976 +1662120375056128000 +1662120375101128960 +1662120375146129920 +1662120375188130816 +1662120375236131840 +1662120375278132736 +1662120375323133696 +1662120375365134592 +1662120375413135616 +1662120375455136512 +1662120375497137408 +1662120375539138304 +1662120375581139200 +1662120375626140160 +1662120375668141056 +1662120375707141888 +1662120375752142848 +1662120375794143744 +1662120375839144704 +1662120375884145664 +1662120375929146624 +1662120375968147456 +1662120376010148352 +1662120376052149248 +1662120376094150144 +1662120376136151040 +1662120376175151872 +1662120376226152960 +1662120376268153856 +1662120376310154752 +1662120376355155712 +1662120376394156544 +1662120376436157440 +1662120376481158400 +1662120376523159296 +1662120376562160128 +1662120376604161024 +1662120376646161920 +1662120376688162816 +1662120376730163712 +1662120376775164672 +1662120376817165568 +1662120376859166464 +1662120376907167488 +1662120376952168448 +1662120376991169280 +1662120377036170240 +1662120377081171200 +1662120377123172096 +1662120377165172992 +1662120377204173824 +1662120377246174720 +1662120377288175616 +1662120377330176512 +1662120377372177408 +1662120377414178304 +1662120377456179200 +1662120377495180032 +1662120377537180928 +1662120377579181824 +1662120377621182720 +1662120377666183680 +1662120377711184640 +1662120377759185664 +1662120377801186560 +1662120377843187456 +1662120377882188288 +1662120377927189248 +1662120377966190080 +1662120378011191040 +1662120378053191936 +1662120378098192896 +1662120378140193792 +1662120378185194752 +1662120378224195584 +1662120378266196480 +1662120378308197376 +1662120378350198272 +1662120378392199168 +1662120378440200192 +1662120378482201088 +1662120378527202048 +1662120378569202944 +1662120378611203840 +1662120378656204800 +1662120378701205760 +1662120378746206720 +1662120378791207680 +1662120378833208576 +1662120378875209472 +1662120378917210368 +1662120378959211264 +1662120378998212096 +1662120379040212992 +1662120379082213888 +1662120379121214720 +1662120379160215552 +1662120379202216448 +1662120379247217408 +1662120379289218304 +1662120379331219200 +1662120379373220096 +1662120379418221056 +1662120379460221952 +1662120379505222912 +1662120379547223808 +1662120379604225024 +1662120379652226048 +1662120379691226880 +1662120379733227776 +1662120379775228672 +1662120379820229632 +1662120379868230656 +1662120379913231616 +1662120379955232512 +1662120379997233408 +1662120380042234368 +1662120380078235136 +1662120380123236096 +1662120380165236992 +1662120380216238080 +1662120380258238976 +1662120380300239872 +1662120380339240704 +1662120380384241664 +1662120380426242560 +1662120380468243456 +1662120380513244416 +1662120380564245504 +1662120380609246464 +1662120380654247424 +1662120380693248256 +1662120380735249152 +1662120380777250048 +1662120380816250880 +1662120380858251776 +1662120380906252800 +1662120380954253824 +1662120380999254784 +1662120381041255680 +1662120381083256576 +1662120381128257536 +1662120381170258432 +1662120381212259328 +1662120381251260160 +1662120381293261056 +1662120381335261952 +1662120381377262848 +1662120381428263936 +1662120381473264896 +1662120381512265728 +1662120381557266688 +1662120381599267584 +1662120381641268480 +1662120381686269440 +1662120381734270464 +1662120381776271360 +1662120381815272192 +1662120381857273088 +1662120381902274048 +1662120381950275072 +1662120381995276032 +1662120382037276928 +1662120382082277888 +1662120382127278848 +1662120382169279744 +1662120382214280704 +1662120382256281600 +1662120382301282560 +1662120382343283456 +1662120382385284352 +1662120382424285184 +1662120382463286016 +1662120382508286976 +1662120382547287808 +1662120382589288704 +1662120382631289600 +1662120382676290560 +1662120382721291520 +1662120382763292416 +1662120382808293376 +1662120382850294272 +1662120382898295296 +1662120382937296128 +1662120382976296960 +1662120383018297856 +1662120383063298816 +1662120383105299712 +1662120383147300608 +1662120383192301568 +1662120383234302464 +1662120383279303424 +1662120383321304320 +1662120383366305280 +1662120383417306368 +1662120383462307328 +1662120383504308224 +1662120383552309248 +1662120383594310144 +1662120383636311040 +1662120383678311936 +1662120383720312832 +1662120383768313856 +1662120383813314816 +1662120383858315776 +1662120383903316736 +1662120383945317632 +1662120383987318528 +1662120384032319488 +1662120384071320320 +1662120384113321216 +1662120384155322112 +1662120384200323072 +1662120384242323968 +1662120384287324928 +1662120384329325824 +1662120384371326720 +1662120384413327616 +1662120384455328512 +1662120384500329472 +1662120384542330368 +1662120384587331328 +1662120384632332288 +1662120384674333184 +1662120384719334144 +1662120384761335040 +1662120384803335936 +1662120384845336832 +1662120384890337792 +1662120384935338752 +1662120384974339584 +1662120385025340672 +1662120385070341632 +1662120385112342528 +1662120385160343552 +1662120385202344448 +1662120385241345280 +1662120385283346176 +1662120385325347072 +1662120385370348032 +1662120385418349056 +1662120385463350016 +1662120385514351104 +1662120385556352000 +1662120385598352896 +1662120385637353728 +1662120385679354624 +1662120385721355520 +1662120385766356480 +1662120385805357312 +1662120385847358208 +1662120385889359104 +1662120385934360064 +1662120385976360960 +1662120386021361920 +1662120386066362880 +1662120386108363776 +1662120386147364608 +1662120386186365440 +1662120386231366400 +1662120386270367232 +1662120386315368192 +1662120386360369152 +1662120386405370112 +1662120386447371008 +1662120386486371840 +1662120386531372800 +1662120386576373760 +1662120386615374592 +1662120386660375552 +1662120386699376384 +1662120386738377216 +1662120386783378176 +1662120386822379008 +1662120386870380032 +1662120386912380928 +1662120386951381760 +1662120386993382656 +1662120387032383488 +1662120387083384576 +1662120387122385408 +1662120387164386304 +1662120387206387200 +1662120387248388096 +1662120387293389056 +1662120387335389952 +1662120387371390720 +1662120387416391680 +1662120387461392640 +1662120387503393536 +1662120387548394496 +1662120387590395392 +1662120387629396224 +1662120387668397056 +1662120387713398016 +1662120387755398912 +1662120387800399872 +1662120387842400768 +1662120387887401728 +1662120387929402624 +1662120387971403520 +1662120388016404480 +1662120388055405312 +1662120388097406208 +1662120388142407168 +1662120388184408064 +1662120388223408896 +1662120388265409792 +1662120388304410624 +1662120388346411520 +1662120388388412416 +1662120388430413312 +1662120388472414208 +1662120388520415232 +1662120388565416192 +1662120388607417088 +1662120388649417984 +1662120388688418816 +1662120388733419776 +1662120388778420736 +1662120388823421696 +1662120388862422528 +1662120388904423424 +1662120388946424320 +1662120388991425280 +1662120389036426240 +1662120389078427136 +1662120389123428096 +1662120389165428992 +1662120389204429824 +1662120389252430848 +1662120389291431680 +1662120389333432576 +1662120389375433472 +1662120389414434304 +1662120389456435200 +1662120389498436096 +1662120389540436992 +1662120389585437952 +1662120389627438848 +1662120389669439744 +1662120389711440640 +1662120389756441600 +1662120389798442496 +1662120389846443520 +1662120389888444416 +1662120389933445376 +1662120389972446208 +1662120390014447104 +1662120390056448000 +1662120390101448960 +1662120390143449856 +1662120390185450752 +1662120390233451776 +1662120390278452736 +1662120390323453696 +1662120390365454592 +1662120390410455552 +1662120390455456512 +1662120390497457408 +1662120390533458176 +1662120390575459072 +1662120390617459968 +1662120390659460864 +1662120390704461824 +1662120390749462784 +1662120390791463680 +1662120390836464640 +1662120390878465536 +1662120390923466496 +1662120390974467584 +1662120391013468416 +1662120391055469312 +1662120391097470208 +1662120391145471232 +1662120391187472128 +1662120391229473024 +1662120391271473920 +1662120391319474944 +1662120391358475776 +1662120391403476736 +1662120391445477632 +1662120391487478528 +1662120391529479424 +1662120391571480320 +1662120391613481216 +1662120391655482112 +1662120391700483072 +1662120391739483904 +1662120391784484864 +1662120391835485952 +1662120391883486976 +1662120391925487872 +1662120391967488768 +1662120392012489728 +1662120392057490688 +1662120392099491584 +1662120392144492544 +1662120392186493440 +1662120392231494400 +1662120392273495296 +1662120392312496128 +1662120392357497088 +1662120392399497984 +1662120392444498944 +1662120392492499968 +1662120392543501056 +1662120392585501952 +1662120392630502912 +1662120392669503744 +1662120392711504640 +1662120392753505536 +1662120392801506560 +1662120392846507520 +1662120392891508480 +1662120392933509376 +1662120392981510400 +1662120393026511360 +1662120393068512256 +1662120393113513216 +1662120393158514176 +1662120393200515072 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track0.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track0.txt new file mode 100644 index 0000000000..d40335079d --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track0.txt @@ -0,0 +1,2847 @@ +1661868173547958016 +1661868173589958912 +1661868173628959744 +1661868173676960768 +1661868173715961600 +1661868173760962560 +1661868173802963456 +1661868173844964352 +1661868173886965248 +1661868173931966208 +1661868173973967104 +1661868174021968128 +1661868174063969024 +1661868174105969920 +1661868174147970816 +1661868174183971584 +1661868174225972480 +1661868174264973312 +1661868174306974208 +1661868174354975232 +1661868174399976192 +1661868174441977088 +1661868174483977984 +1661868174525978880 +1661868174564979712 +1661868174603980544 +1661868174645981440 +1661868174693982464 +1661868174735983360 +1661868174780984320 +1661868174828985344 +1661868174870986240 +1661868174912987136 +1661868174960988160 +1661868175002989056 +1661868175044989952 +1661868175086990848 +1661868175128991744 +1661868175170992640 +1661868175209993472 +1661868175251994368 +1661868175302995456 +1661868175341996288 +1661868175383997184 +1661868175425998080 +1661868175470999040 +1661868175509999872 +1661868175549000704 +1661868175591001600 +1661868175639002624 +1661868175681003520 +1661868175723004416 +1661868175765005312 +1661868175810006272 +1661868175849007104 +1661868175897008128 +1661868175939009024 +1661868175981009920 +1661868176029010944 +1661868176071011840 +1661868176113012736 +1661868176152013568 +1661868176197014528 +1661868176242015488 +1661868176284016384 +1661868176323017216 +1661868176368018176 +1661868176410019072 +1661868176452019968 +1661868176497020928 +1661868176536021760 +1661868176578022656 +1661868176617023488 +1661868176659024384 +1661868176701025280 +1661868176743026176 +1661868176785027072 +1661868176824027904 +1661868176869028864 +1661868176914029824 +1661868176953030656 +1661868176992031488 +1661868177034032384 +1661868177076033280 +1661868177118034176 +1661868177163035136 +1661868177208036096 +1661868177244036864 +1661868177283037696 +1661868177325038592 +1661868177367039488 +1661868177409040384 +1661868177451041280 +1661868177493042176 +1661868177535043072 +1661868177580044032 +1661868177625044992 +1661868177670045952 +1661868177712046848 +1661868177748047616 +1661868177793048576 +1661868177838049536 +1661868177877050368 +1661868177916051200 +1661868177958052096 +1661868178003053056 +1661868178048054016 +1661868178090054912 +1661868178132055808 +1661868178171056640 +1661868178207057408 +1661868178249058304 +1661868178297059328 +1661868178339060224 +1661868178384061184 +1661868178426062080 +1661868178468062976 +1661868178510063872 +1661868178546064640 +1661868178588065536 +1661868178630066432 +1661868178669067264 +1661868178711068160 +1661868178759069184 +1661868178804070144 +1661868178846071040 +1661868178888071936 +1661868178930072832 +1661868178972073728 +1661868179014074624 +1661868179059075584 +1661868179107076608 +1661868179152077568 +1661868179191078400 +1661868179233079296 +1661868179278080256 +1661868179320081152 +1661868179362082048 +1661868179407083008 +1661868179452083968 +1661868179494084864 +1661868179539085824 +1661868179581086720 +1661868179623087616 +1661868179665088512 +1661868179713089536 +1661868179758090496 +1661868179803091456 +1661868179845092352 +1661868179887093248 +1661868179926094080 +1661868179968094976 +1661868180010095872 +1661868180049096704 +1661868180088097536 +1661868180130098432 +1661868180175099392 +1661868180217100288 +1661868180256101120 +1661868180298102016 +1661868180340102912 +1661868180385103872 +1661868180427104768 +1661868180466105600 +1661868180508106496 +1661868180550107392 +1661868180589108224 +1661868180628109056 +1661868180670109952 +1661868180715110912 +1661868180760111872 +1661868180802112768 +1661868180844113664 +1661868180886114560 +1661868180922115328 +1661868180967116288 +1661868181009117184 +1661868181051118080 +1661868181090118912 +1661868181132119808 +1661868181174120704 +1661868181216121600 +1661868181258122496 +1661868181303123456 +1661868181348124416 +1661868181387125248 +1661868181432126208 +1661868181474127104 +1661868181516128000 +1661868181558128896 +1661868181597129728 +1661868181636130560 +1661868181678131456 +1661868181720132352 +1661868181762133248 +1661868181804134144 +1661868181846135040 +1661868181885135872 +1661868181927136768 +1661868181966137600 +1661868182008138496 +1661868182050139392 +1661868182095140352 +1661868182140141312 +1661868182182142208 +1661868182221143040 +1661868182263143936 +1661868182302144768 +1661868182344145664 +1661868182386146560 +1661868182428147456 +1661868182464148224 +1661868182506149120 +1661868182551150080 +1661868182590150912 +1661868182635151872 +1661868182677152768 +1661868182716153600 +1661868182758154496 +1661868182800155392 +1661868182839156224 +1661868182884157184 +1661868182926158080 +1661868182971159040 +1661868183010159872 +1661868183049160704 +1661868183091161600 +1661868183130162432 +1661868183172163328 +1661868183214164224 +1661868183256165120 +1661868183298166016 +1661868183340166912 +1661868183382167808 +1661868183427168768 +1661868183469169664 +1661868183511170560 +1661868183550171392 +1661868183595172352 +1661868183637173248 +1661868183679174144 +1661868183718174976 +1661868183769176064 +1661868183811176960 +1661868183850177792 +1661868183892178688 +1661868183931179520 +1661868183973180416 +1661868184018181376 +1661868184060182272 +1661868184102183168 +1661868184147184128 +1661868184192185088 +1661868184240186112 +1661868184282187008 +1661868184324187904 +1661868184366188800 +1661868184411189760 +1661868184447190528 +1661868184486191360 +1661868184528192256 +1661868184573193216 +1661868184618194176 +1661868184660195072 +1661868184705196032 +1661868184747196928 +1661868184786197760 +1661868184831198720 +1661868184873199616 +1661868184921200640 +1661868184960201472 +1661868185005202432 +1661868185047203328 +1661868185086204160 +1661868185125204992 +1661868185170205952 +1661868185215206912 +1661868185257207808 +1661868185299208704 +1661868185341209600 +1661868185383210496 +1661868185422211328 +1661868185464212224 +1661868185506213120 +1661868185545213952 +1661868185590214912 +1661868185632215808 +1661868185671216640 +1661868185707217408 +1661868185752218368 +1661868185794219264 +1661868185839220224 +1661868185875220992 +1661868185914221824 +1661868185962222848 +1661868186004223744 +1661868186046224640 +1661868186091225600 +1661868186130226432 +1661868186175227392 +1661868186220228352 +1661868186262229248 +1661868186307230208 +1661868186349231104 +1661868186391232000 +1661868186433232896 +1661868186478233856 +1661868186520234752 +1661868186562235648 +1661868186601236480 +1661868186643237376 +1661868186679238144 +1661868186718238976 +1661868186760239872 +1661868186805240832 +1661868186844241664 +1661868186883242496 +1661868186925243392 +1661868186964244224 +1661868187006245120 +1661868187048246016 +1661868187090246912 +1661868187129247744 +1661868187174248704 +1661868187216249600 +1661868187255250432 +1661868187297251328 +1661868187339252224 +1661868187381253120 +1661868187423254016 +1661868187465254912 +1661868187507255808 +1661868187549256704 +1661868187597257728 +1661868187639258624 +1661868187681259520 +1661868187726260480 +1661868187768261376 +1661868187807262208 +1661868187846263040 +1661868187888263936 +1661868187930264832 +1661868187978265856 +1661868188020266752 +1661868188062267648 +1661868188101268480 +1661868188143269376 +1661868188185270272 +1661868188224271104 +1661868188263271936 +1661868188302272768 +1661868188341273600 +1661868188380274432 +1661868188419275264 +1661868188464276224 +1661868188509277184 +1661868188551278080 +1661868188596279040 +1661868188641280000 +1661868188686280960 +1661868188728281856 +1661868188776282880 +1661868188824283904 +1661868188869284864 +1661868188911285760 +1661868188950286592 +1661868188992287488 +1661868189034288384 +1661868189079289344 +1661868189121290240 +1661868189163291136 +1661868189205292032 +1661868189247292928 +1661868189292293888 +1661868189328294656 +1661868189370295552 +1661868189412296448 +1661868189457297408 +1661868189502298368 +1661868189541299200 +1661868189580300032 +1661868189616300800 +1661868189661301760 +1661868189703302656 +1661868189742303488 +1661868189784304384 +1661868189832305408 +1661868189871306240 +1661868189913307136 +1661868189949307904 +1661868189988308736 +1661868190030309632 +1661868190072310528 +1661868190114311424 +1661868190156312320 +1661868190195313152 +1661868190237314048 +1661868190276314880 +1661868190321315840 +1661868190363316736 +1661868190405317632 +1661868190441318400 +1661868190486319360 +1661868190528320256 +1661868190570321152 +1661868190609321984 +1661868190654322944 +1661868190699323904 +1661868190741324800 +1661868190780325632 +1661868190822326528 +1661868190864327424 +1661868190906328320 +1661868190945329152 +1661868190990330112 +1661868191041331200 +1661868191086332160 +1661868191128333056 +1661868191170333952 +1661868191212334848 +1661868191254335744 +1661868191296336640 +1661868191338337536 +1661868191377338368 +1661868191425339392 +1661868191464340224 +1661868191509341184 +1661868191554342144 +1661868191596343040 +1661868191638343936 +1661868191683344896 +1661868191722345728 +1661868191776346880 +1661868191818347776 +1661868191857348608 +1661868191902349568 +1661868191941350400 +1661868191983351296 +1661868192028352256 +1661868192070353152 +1661868192112354048 +1661868192151354880 +1661868192193355776 +1661868192235356672 +1661868192277357568 +1661868192319358464 +1661868192361359360 +1661868192400360192 +1661868192442361088 +1661868192484361984 +1661868192526362880 +1661868192568363776 +1661868192613364736 +1661868192655365632 +1661868192700366592 +1661868192739367424 +1661868192781368320 +1661868192823369216 +1661868192862370048 +1661868192907371008 +1661868192946371840 +1661868192988372736 +1661868193027373568 +1661868193066374400 +1661868193105375232 +1661868193147376128 +1661868193192377088 +1661868193234377984 +1661868193276378880 +1661868193318379776 +1661868193354380544 +1661868193396381440 +1661868193441382400 +1661868193489383424 +1661868193531384320 +1661868193570385152 +1661868193609385984 +1661868193651386880 +1661868193693387776 +1661868193735388672 +1661868193789389824 +1661868193828390656 +1661868193870391552 +1661868193909392384 +1661868193951393280 +1661868193993394176 +1661868194038395136 +1661868194074395904 +1661868194119396864 +1661868194161397760 +1661868194203398656 +1661868194245399552 +1661868194287400448 +1661868194329401344 +1661868194371402240 +1661868194413403136 +1661868194455404032 +1661868194497404928 +1661868194539405824 +1661868194581406720 +1661868194620407552 +1661868194662408448 +1661868194707409408 +1661868194752410368 +1661868194791411200 +1661868194830412032 +1661868194869412864 +1661868194914413824 +1661868194956414720 +1661868194998415616 +1661868195040416512 +1661868195079417344 +1661868195121418240 +1661868195163419136 +1661868195205420032 +1661868195244420864 +1661868195286421760 +1661868195331422720 +1661868195376423680 +1661868195418424576 +1661868195460425472 +1661868195508426496 +1661868195550427392 +1661868195592428288 +1661868195640429312 +1661868195682430208 +1661868195724431104 +1661868195769432064 +1661868195811432960 +1661868195853433856 +1661868195895434752 +1661868195931435520 +1661868195973436416 +1661868196015437312 +1661868196060438272 +1661868196102439168 +1661868196147440128 +1661868196195441152 +1661868196237442048 +1661868196285443072 +1661868196330444032 +1661868196375444992 +1661868196414445824 +1661868196453446656 +1661868196495447552 +1661868196537448448 +1661868196579449344 +1661868196624450304 +1661868196666451200 +1661868196711452160 +1661868196747452928 +1661868196789453824 +1661868196831454720 +1661868196873455616 +1661868196921456640 +1661868196969457664 +1661868197020458752 +1661868197059459584 +1661868197098460416 +1661868197140461312 +1661868197182462208 +1661868197221463040 +1661868197263463936 +1661868197302464768 +1661868197344465664 +1661868197386466560 +1661868197428467456 +1661868197470468352 +1661868197509469184 +1661868197554470144 +1661868197593470976 +1661868197635471872 +1661868197677472768 +1661868197716473600 +1661868197758474496 +1661868197800475392 +1661868197848476416 +1661868197890477312 +1661868197932478208 +1661868197971479040 +1661868198010479872 +1661868198052480768 +1661868198100481792 +1661868198139482624 +1661868198181483520 +1661868198220484352 +1661868198262485248 +1661868198304486144 +1661868198349487104 +1661868198394488064 +1661868198439489024 +1661868198481489920 +1661868198523490816 +1661868198559491584 +1661868198604492544 +1661868198646493440 +1661868198685494272 +1661868198730495232 +1661868198775496192 +1661868198817497088 +1661868198862498048 +1661868198904498944 +1661868198946499840 +1661868198988500736 +1661868199030501632 +1661868199072502528 +1661868199114503424 +1661868199156504320 +1661868199198505216 +1661868199243506176 +1661868199285507072 +1661868199333508096 +1661868199375508992 +1661868199420509952 +1661868199462510848 +1661868199504511744 +1661868199546512640 +1661868199588513536 +1661868199630514432 +1661868199672515328 +1661868199714516224 +1661868199753517056 +1661868199795517952 +1661868199834518784 +1661868199876519680 +1661868199915520512 +1661868199954521344 +1661868199996522240 +1661868200038523136 +1661868200080524032 +1661868200119524864 +1661868200158525696 +1661868200200526592 +1661868200242527488 +1661868200284528384 +1661868200329529344 +1661868200365530112 +1661868200410531072 +1661868200452531968 +1661868200491532800 +1661868200533533696 +1661868200572534528 +1661868200614535424 +1661868200662536448 +1661868200710537472 +1661868200755538432 +1661868200797539328 +1661868200836540160 +1661868200872540928 +1661868200914541824 +1661868200956542720 +1661868200998543616 +1661868201037544448 +1661868201076545280 +1661868201118546176 +1661868201154546944 +1661868201193547776 +1661868201235548672 +1661868201280549632 +1661868201319550464 +1661868201364551424 +1661868201406552320 +1661868201451553280 +1661868201493554176 +1661868201532555008 +1661868201574555904 +1661868201616556800 +1661868201658557696 +1661868201700558592 +1661868201739559424 +1661868201778560256 +1661868201820561152 +1661868201862562048 +1661868201913563136 +1661868201955564032 +1661868202000564992 +1661868202042565888 +1661868202084566784 +1661868202129567744 +1661868202168568576 +1661868202210569472 +1661868202252570368 +1661868202288571136 +1661868202330572032 +1661868202372572928 +1661868202414573824 +1661868202462574848 +1661868202504575744 +1661868202546576640 +1661868202588577536 +1661868202630578432 +1661868202675579392 +1661868202717580288 +1661868202756581120 +1661868202801582080 +1661868202846583040 +1661868202885583872 +1661868202927584768 +1661868202972585728 +1661868203011586560 +1661868203056587520 +1661868203101588480 +1661868203140589312 +1661868203182590208 +1661868203230591232 +1661868203272592128 +1661868203314593024 +1661868203359593984 +1661868203401594880 +1661868203443595776 +1661868203485596672 +1661868203527597568 +1661868203569598464 +1661868203611599360 +1661868203653600256 +1661868203695601152 +1661868203737602048 +1661868203779602944 +1661868203824603904 +1661868203863604736 +1661868203905605632 +1661868203947606528 +1661868203989607424 +1661868204034608384 +1661868204079609344 +1661868204121610240 +1661868204163611136 +1661868204205612032 +1661868204247612928 +1661868204289613824 +1661868204328614656 +1661868204367615488 +1661868204400616192 +1661868204442617088 +1661868204490618112 +1661868204532619008 +1661868204574619904 +1661868204616620800 +1661868204658621696 +1661868204697622528 +1661868204733623296 +1661868204775624192 +1661868204820625152 +1661868204856625920 +1661868204898626816 +1661868204943627776 +1661868204988628736 +1661868205033629696 +1661868205075630592 +1661868205114631424 +1661868205156632320 +1661868205204633344 +1661868205249634304 +1661868205288635136 +1661868205330636032 +1661868205372636928 +1661868205414637824 +1661868205456638720 +1661868205498639616 +1661868205537640448 +1661868205579641344 +1661868205621642240 +1661868205654642944 +1661868205696643840 +1661868205738644736 +1661868205789645824 +1661868205828646656 +1661868205870647552 +1661868205915648512 +1661868205960649472 +1661868206002650368 +1661868206044651264 +1661868206083652096 +1661868206125652992 +1661868206170653952 +1661868206212654848 +1661868206254655744 +1661868206299656704 +1661868206341657600 +1661868206380658432 +1661868206422659328 +1661868206467660288 +1661868206509661184 +1661868206548662016 +1661868206590662912 +1661868206638663936 +1661868206677664768 +1661868206722665728 +1661868206767666688 +1661868206809667584 +1661868206851668480 +1661868206890669312 +1661868206932670208 +1661868206971671040 +1661868207013671936 +1661868207055672832 +1661868207097673728 +1661868207139674624 +1661868207187675648 +1661868207229676544 +1661868207271677440 +1661868207313678336 +1661868207355679232 +1661868207397680128 +1661868207442681088 +1661868207487682048 +1661868207526682880 +1661868207568683776 +1661868207613684736 +1661868207658685696 +1661868207700686592 +1661868207742687488 +1661868207790688512 +1661868207829689344 +1661868207868690176 +1661868207913691136 +1661868207955692032 +1661868207997692928 +1661868208039693824 +1661868208084694784 +1661868208132695808 +1661868208177696768 +1661868208216697600 +1661868208255698432 +1661868208297699328 +1661868208339700224 +1661868208375700992 +1661868208417701888 +1661868208459702784 +1661868208501703680 +1661868208549704704 +1661868208591705600 +1661868208630706432 +1661868208672707328 +1661868208714708224 +1661868208756709120 +1661868208795709952 +1661868208831710720 +1661868208876711680 +1661868208918712576 +1661868208960713472 +1661868209002714368 +1661868209047715328 +1661868209089716224 +1661868209131717120 +1661868209173718016 +1661868209218718976 +1661868209260719872 +1661868209299720704 +1661868209341721600 +1661868209386722560 +1661868209434723584 +1661868209476724480 +1661868209518725376 +1661868209563726336 +1661868209608727296 +1661868209647728128 +1661868209686728960 +1661868209731729920 +1661868209773730816 +1661868209809731584 +1661868209851732480 +1661868209899733504 +1661868209941734400 +1661868209980735232 +1661868210022736128 +1661868210067737088 +1661868210109737984 +1661868210148738816 +1661868210187739648 +1661868210226740480 +1661868210268741376 +1661868210310742272 +1661868210349743104 +1661868210391744000 +1661868210430744832 +1661868210472745728 +1661868210514746624 +1661868210556747520 +1661868210601748480 +1661868210640749312 +1661868210682750208 +1661868210724751104 +1661868210766752000 +1661868210811752960 +1661868210856753920 +1661868210898754816 +1661868210937755648 +1661868210979756544 +1661868211021757440 +1661868211063758336 +1661868211102759168 +1661868211150760192 +1661868211195761152 +1661868211237762048 +1661868211273762816 +1661868211315763712 +1661868211357764608 +1661868211396765440 +1661868211441766400 +1661868211480767232 +1661868211522768128 +1661868211567769088 +1661868211606769920 +1661868211648770816 +1661868211687771648 +1661868211729772544 +1661868211771773440 +1661868211813774336 +1661868211861775360 +1661868211906776320 +1661868211948777216 +1661868211993778176 +1661868212041779200 +1661868212083780096 +1661868212131781120 +1661868212173782016 +1661868212215782912 +1661868212257783808 +1661868212302784768 +1661868212347785728 +1661868212386786560 +1661868212431787520 +1661868212473788416 +1661868212515789312 +1661868212557790208 +1661868212599791104 +1661868212641792000 +1661868212683792896 +1661868212725793792 +1661868212767794688 +1661868212809795584 +1661868212851796480 +1661868212893797376 +1661868212935798272 +1661868212971799040 +1661868213016800000 +1661868213055800832 +1661868213094801664 +1661868213139802624 +1661868213178803456 +1661868213220804352 +1661868213259805184 +1661868213307806208 +1661868213343806976 +1661868213391808000 +1661868213430808832 +1661868213475809792 +1661868213523810816 +1661868213568811776 +1661868213610812672 +1661868213649813504 +1661868213691814400 +1661868213733815296 +1661868213772816128 +1661868213814817024 +1661868213850817792 +1661868213892818688 +1661868213937819648 +1661868213979820544 +1661868214015821312 +1661868214060822272 +1661868214099823104 +1661868214141824000 +1661868214180824832 +1661868214222825728 +1661868214264826624 +1661868214306827520 +1661868214351828480 +1661868214393829376 +1661868214432830208 +1661868214471831040 +1661868214513831936 +1661868214555832832 +1661868214594833664 +1661868214636834560 +1661868214678835456 +1661868214720836352 +1661868214762837248 +1661868214807838208 +1661868214849839104 +1661868214885839872 +1661868214927840768 +1661868214972841728 +1661868215014842624 +1661868215059843584 +1661868215101844480 +1661868215140845312 +1661868215188846336 +1661868215230847232 +1661868215278848256 +1661868215320849152 +1661868215362850048 +1661868215401850880 +1661868215443851776 +1661868215488852736 +1661868215530853632 +1661868215569854464 +1661868215611855360 +1661868215650856192 +1661868215692857088 +1661868215734857984 +1661868215776858880 +1661868215815859712 +1661868215860860672 +1661868215902861568 +1661868215944862464 +1661868215986863360 +1661868216034864384 +1661868216076865280 +1661868216121866240 +1661868216163867136 +1661868216202867968 +1661868216250868992 +1661868216295869952 +1661868216337870848 +1661868216385871872 +1661868216427872768 +1661868216475873792 +1661868216520874752 +1661868216562875648 +1661868216607876608 +1661868216649877504 +1661868216700878592 +1661868216742879488 +1661868216784880384 +1661868216823881216 +1661868216865882112 +1661868216913883136 +1661868216952883968 +1661868216991884800 +1661868217033885696 +1661868217075886592 +1661868217117887488 +1661868217162888448 +1661868217198889216 +1661868217240890112 +1661868217282891008 +1661868217321891840 +1661868217363892736 +1661868217405893632 +1661868217447894528 +1661868217489895424 +1661868217534896384 +1661868217576897280 +1661868217618898176 +1661868217666899200 +1661868217711900160 +1661868217753901056 +1661868217795901952 +1661868217837902848 +1661868217879903744 +1661868217921904640 +1661868217963905536 +1661868218005906432 +1661868218047907328 +1661868218092908288 +1661868218134909184 +1661868218182910208 +1661868218224911104 +1661868218266912000 +1661868218305912832 +1661868218350913792 +1661868218392914688 +1661868218437915648 +1661868218479916544 +1661868218521917440 +1661868218563918336 +1661868218605919232 +1661868218644920064 +1661868218686920960 +1661868218728921856 +1661868218770922752 +1661868218815923712 +1661868218857924608 +1661868218896925440 +1661868218944926464 +1661868218986927360 +1661868219028928256 +1661868219073929216 +1661868219115930112 +1661868219154930944 +1661868219202931968 +1661868219247932928 +1661868219295933952 +1661868219343934976 +1661868219385935872 +1661868219430936832 +1661868219469937664 +1661868219511938560 +1661868219553939456 +1661868219595940352 +1661868219637941248 +1661868219676942080 +1661868219715942912 +1661868219757943808 +1661868219796944640 +1661868219841945600 +1661868219883946496 +1661868219925947392 +1661868219967948288 +1661868220006949120 +1661868220045949952 +1661868220087950848 +1661868220129951744 +1661868220174952704 +1661868220213953536 +1661868220252954368 +1661868220291955200 +1661868220333956096 +1661868220375956992 +1661868220420957952 +1661868220462958848 +1661868220504959744 +1661868220549960704 +1661868220594961664 +1661868220636962560 +1661868220678963456 +1661868220717964288 +1661868220762965248 +1661868220804966144 +1661868220855967232 +1661868220897968128 +1661868220942969088 +1661868220984969984 +1661868221026970880 +1661868221068971776 +1661868221107972608 +1661868221146973440 +1661868221185974272 +1661868221224975104 +1661868221269976064 +1661868221311976960 +1661868221350977792 +1661868221395978752 +1661868221440979712 +1661868221479980544 +1661868221518981376 +1661868221560982272 +1661868221602983168 +1661868221647984128 +1661868221686984960 +1661868221731985920 +1661868221779986944 +1661868221821987840 +1661868221866988800 +1661868221908989696 +1661868221947990528 +1661868221995991552 +1661868222034992384 +1661868222076993280 +1661868222121994240 +1661868222166995200 +1661868222211996160 +1661868222253997056 +1661868222292997888 +1661868222331998720 +1661868222373999616 +1661868222416000512 +1661868222458001408 +1661868222500002304 +1661868222548003328 +1661868222584004096 +1661868222626004992 +1661868222671005952 +1661868222713006848 +1661868222764007936 +1661868222806008832 +1661868222848009728 +1661868222890010624 +1661868222932011520 +1661868222974012416 +1661868223022013440 +1661868223070014464 +1661868223109015296 +1661868223151016192 +1661868223190017024 +1661868223241018112 +1661868223283019008 +1661868223328019968 +1661868223367020800 +1661868223409021696 +1661868223457022720 +1661868223499023616 +1661868223541024512 +1661868223583025408 +1661868223625026304 +1661868223670027264 +1661868223709028096 +1661868223751028992 +1661868223793029888 +1661868223841030912 +1661868223883031808 +1661868223925032704 +1661868223967033600 +1661868224006034432 +1661868224045035264 +1661868224087036160 +1661868224129037056 +1661868224168037888 +1661868224207038720 +1661868224261039872 +1661868224300040704 +1661868224342041600 +1661868224384042496 +1661868224432043520 +1661868224474044416 +1661868224519045376 +1661868224561046272 +1661868224603047168 +1661868224645048064 +1661868224687048960 +1661868224732049920 +1661868224774050816 +1661868224816051712 +1661868224855052544 +1661868224897053440 +1661868224939054336 +1661868224981055232 +1661868225023056128 +1661868225074057216 +1661868225116058112 +1661868225161059072 +1661868225203059968 +1661868225248060928 +1661868225290061824 +1661868225338062848 +1661868225380063744 +1661868225422064640 +1661868225467065600 +1661868225509066496 +1661868225545067264 +1661868225590068224 +1661868225638069248 +1661868225686070272 +1661868225728071168 +1661868225770072064 +1661868225818073088 +1661868225860073984 +1661868225902074880 +1661868225944075776 +1661868225992076800 +1661868226034077696 +1661868226076078592 +1661868226118079488 +1661868226160080384 +1661868226199081216 +1661868226241082112 +1661868226289083136 +1661868226334084096 +1661868226376084992 +1661868226418085888 +1661868226454086656 +1661868226496087552 +1661868226535088384 +1661868226586089472 +1661868226628090368 +1661868226670091264 +1661868226709092096 +1661868226751092992 +1661868226799094016 +1661868226838094848 +1661868226883095808 +1661868226925096704 +1661868226967097600 +1661868227012098560 +1661868227054099456 +1661868227093100288 +1661868227141101312 +1661868227186102272 +1661868227225103104 +1661868227270104064 +1661868227312104960 +1661868227354105856 +1661868227396106752 +1661868227441107712 +1661868227483108608 +1661868227525109504 +1661868227567110400 +1661868227609111296 +1661868227651112192 +1661868227690113024 +1661868227732113920 +1661868227774114816 +1661868227819115776 +1661868227867116800 +1661868227912117760 +1661868227954118656 +1661868227996119552 +1661868228038120448 +1661868228086121472 +1661868228134122496 +1661868228179123456 +1661868228221124352 +1661868228263125248 +1661868228305126144 +1661868228353127168 +1661868228395128064 +1661868228434128896 +1661868228479129856 +1661868228524130816 +1661868228569131776 +1661868228611132672 +1661868228656133632 +1661868228698134528 +1661868228737135360 +1661868228776136192 +1661868228824137216 +1661868228866138112 +1661868228908139008 +1661868228950139904 +1661868228992140800 +1661868229031141632 +1661868229073142528 +1661868229124143616 +1661868229166144512 +1661868229208145408 +1661868229253146368 +1661868229295147264 +1661868229337148160 +1661868229379149056 +1661868229421149952 +1661868229463150848 +1661868229508151808 +1661868229547152640 +1661868229592153600 +1661868229634154496 +1661868229673155328 +1661868229715156224 +1661868229757157120 +1661868229796157952 +1661868229838158848 +1661868229880159744 +1661868229931160832 +1661868229973161728 +1661868230015162624 +1661868230057163520 +1661868230099164416 +1661868230141165312 +1661868230186166272 +1661868230228167168 +1661868230270168064 +1661868230309168896 +1661868230354169856 +1661868230396170752 +1661868230435171584 +1661868230480172544 +1661868230525173504 +1661868230561174272 +1661868230603175168 +1661868230642176000 +1661868230684176896 +1661868230723177728 +1661868230765178624 +1661868230807179520 +1661868230849180416 +1661868230891181312 +1661868230936182272 +1661868230978183168 +1661868231020184064 +1661868231059184896 +1661868231104185856 +1661868231146186752 +1661868231191187712 +1661868231233188608 +1661868231275189504 +1661868231317190400 +1661868231356191232 +1661868231401192192 +1661868231443193088 +1661868231482193920 +1661868231524194816 +1661868231569195776 +1661868231611196672 +1661868231653197568 +1661868231692198400 +1661868231731199232 +1661868231770200064 +1661868231812200960 +1661868231857201920 +1661868231902202880 +1661868231944203776 +1661868231986204672 +1661868232031205632 +1661868232070206464 +1661868232112207360 +1661868232157208320 +1661868232199209216 +1661868232241210112 +1661868232283211008 +1661868232328211968 +1661868232370212864 +1661868232412213760 +1661868232454214656 +1661868232496215552 +1661868232532216320 +1661868232574217216 +1661868232616218112 +1661868232652218880 +1661868232691219712 +1661868232733220608 +1661868232775221504 +1661868232817222400 +1661868232859223296 +1661868232901224192 +1661868232946225152 +1661868232991226112 +1661868233030226944 +1661868233075227904 +1661868233117228800 +1661868233159229696 +1661868233204230656 +1661868233240231424 +1661868233282232320 +1661868233324233216 +1661868233363234048 +1661868233405234944 +1661868233441235712 +1661868233483236608 +1661868233528237568 +1661868233576238592 +1661868233624239616 +1661868233669240576 +1661868233711241472 +1661868233756242432 +1661868233798243328 +1661868233840244224 +1661868233882245120 +1661868233924246016 +1661868233963246848 +1661868234005247744 +1661868234053248768 +1661868234095249664 +1661868234134250496 +1661868234179251456 +1661868234221252352 +1661868234263253248 +1661868234305254144 +1661868234347255040 +1661868234389255936 +1661868234431256832 +1661868234473257728 +1661868234518258688 +1661868234560259584 +1661868234602260480 +1661868234644261376 +1661868234686262272 +1661868234728263168 +1661868234770264064 +1661868234812264960 +1661868234848265728 +1661868234890266624 +1661868234929267456 +1661868234974268416 +1661868235013269248 +1661868235055270144 +1661868235103271168 +1661868235148272128 +1661868235187272960 +1661868235232273920 +1661868235274274816 +1661868235319275776 +1661868235361276672 +1661868235403277568 +1661868235448278528 +1661868235499279616 +1661868235544280576 +1661868235589281536 +1661868235631282432 +1661868235670283264 +1661868235715284224 +1661868235760285184 +1661868235802286080 +1661868235850287104 +1661868235892288000 +1661868235937288960 +1661868235979289856 +1661868236021290752 +1661868236069291776 +1661868236111292672 +1661868236153293568 +1661868236195294464 +1661868236240295424 +1661868236282296320 +1661868236333297408 +1661868236375298304 +1661868236417299200 +1661868236462300160 +1661868236507301120 +1661868236543301888 +1661868236585302784 +1661868236627303680 +1661868236666304512 +1661868236708305408 +1661868236756306432 +1661868236795307264 +1661868236834308096 +1661868236870308864 +1661868236915309824 +1661868236957310720 +1661868237005311744 +1661868237047312640 +1661868237089313536 +1661868237134314496 +1661868237176315392 +1661868237218316288 +1661868237263317248 +1661868237302318080 +1661868237344318976 +1661868237383319808 +1661868237425320704 +1661868237467321600 +1661868237506322432 +1661868237557323520 +1661868237599324416 +1661868237641325312 +1661868237683326208 +1661868237725327104 +1661868237770328064 +1661868237809328896 +1661868237851329792 +1661868237899330816 +1661868237941331712 +1661868237989332736 +1661868238028333568 +1661868238073334528 +1661868238118335488 +1661868238160336384 +1661868238202337280 +1661868238241338112 +1661868238292339200 +1661868238337340160 +1661868238379341056 +1661868238421341952 +1661868238463342848 +1661868238505343744 +1661868238547344640 +1661868238583345408 +1661868238628346368 +1661868238667347200 +1661868238709348096 +1661868238757349120 +1661868238799350016 +1661868238844350976 +1661868238889351936 +1661868238928352768 +1661868238967353600 +1661868239003354368 +1661868239045355264 +1661868239090356224 +1661868239138357248 +1661868239183358208 +1661868239234359296 +1661868239279360256 +1661868239321361152 +1661868239369362176 +1661868239411363072 +1661868239456364032 +1661868239504365056 +1661868239546365952 +1661868239591366912 +1661868239633367808 +1661868239678368768 +1661868239717369600 +1661868239759370496 +1661868239810371584 +1661868239852372480 +1661868239894373376 +1661868239936374272 +1661868239975375104 +1661868240023376128 +1661868240065377024 +1661868240107377920 +1661868240149378816 +1661868240191379712 +1661868240236380672 +1661868240281381632 +1661868240320382464 +1661868240359383296 +1661868240398384128 +1661868240437384960 +1661868240479385856 +1661868240521386752 +1661868240560387584 +1661868240599388416 +1661868240641389312 +1661868240683390208 +1661868240728391168 +1661868240770392064 +1661868240815393024 +1661868240857393920 +1661868240902394880 +1661868240947395840 +1661868240986396672 +1661868241028397568 +1661868241070398464 +1661868241121399552 +1661868241166400512 +1661868241208401408 +1661868241247402240 +1661868241289403136 +1661868241331404032 +1661868241373404928 +1661868241418405888 +1661868241460406784 +1661868241505407744 +1661868241544408576 +1661868241583409408 +1661868241625410304 +1661868241667411200 +1661868241709412096 +1661868241754413056 +1661868241796413952 +1661868241838414848 +1661868241880415744 +1661868241925416704 +1661868241979417856 +1661868242021418752 +1661868242060419584 +1661868242099420416 +1661868242141421312 +1661868242183422208 +1661868242225423104 +1661868242267424000 +1661868242312424960 +1661868242354425856 +1661868242390426624 +1661868242432427520 +1661868242471428352 +1661868242507429120 +1661868242549430016 +1661868242591430912 +1661868242633431808 +1661868242675432704 +1661868242717433600 +1661868242759434496 +1661868242801435392 +1661868242843436288 +1661868242885437184 +1661868242927438080 +1661868242969438976 +1661868243011439872 +1661868243053440768 +1661868243095441664 +1661868243140442624 +1661868243182443520 +1661868243221444352 +1661868243272445440 +1661868243317446400 +1661868243359447296 +1661868243401448192 +1661868243440449024 +1661868243488450048 +1661868243533451008 +1661868243575451904 +1661868243617452800 +1661868243656453632 +1661868243698454528 +1661868243740455424 +1661868243782456320 +1661868243824457216 +1661868243866458112 +1661868243914459136 +1661868243956460032 +1661868243998460928 +1661868244043461888 +1661868244085462784 +1661868244127463680 +1661868244172464640 +1661868244220465664 +1661868244265466624 +1661868244304467456 +1661868244349468416 +1661868244394469376 +1661868244439470336 +1661868244481471232 +1661868244520472064 +1661868244559472896 +1661868244601473792 +1661868244649474816 +1661868244691475712 +1661868244736476672 +1661868244778477568 +1661868244823478528 +1661868244865479424 +1661868244913480448 +1661868244961481472 +1661868245012482560 +1661868245054483456 +1661868245096484352 +1661868245138485248 +1661868245180486144 +1661868245222487040 +1661868245267488000 +1661868245309488896 +1661868245351489792 +1661868245396490752 +1661868245438491648 +1661868245483492608 +1661868245525493504 +1661868245570494464 +1661868245615495424 +1661868245657496320 +1661868245702497280 +1661868245741498112 +1661868245783499008 +1661868245822499840 +1661868245867500800 +1661868245909501696 +1661868245951502592 +1661868245993503488 +1661868246038504448 +1661868246080505344 +1661868246125506304 +1661868246182507520 +1661868246224508416 +1661868246263509248 +1661868246302510080 +1661868246344510976 +1661868246389511936 +1661868246434512896 +1661868246476513792 +1661868246521514752 +1661868246563515648 +1661868246602516480 +1661868246638517248 +1661868246686518272 +1661868246725519104 +1661868246767520000 +1661868246809520896 +1661868246851521792 +1661868246893522688 +1661868246944523776 +1661868246986524672 +1661868247028525568 +1661868247076526592 +1661868247118527488 +1661868247151528192 +1661868247190529024 +1661868247238530048 +1661868247280530944 +1661868247325531904 +1661868247370532864 +1661868247415533824 +1661868247457534720 +1661868247499535616 +1661868247541536512 +1661868247580537344 +1661868247622538240 +1661868247664539136 +1661868247709540096 +1661868247751540992 +1661868247790541824 +1661868247832542720 +1661868247874543616 +1661868247925544704 +1661868247967545600 +1661868248015546624 +1661868248057547520 +1661868248099548416 +1661868248141549312 +1661868248183550208 +1661868248222551040 +1661868248264551936 +1661868248312552960 +1661868248354553856 +1661868248399554816 +1661868248444555776 +1661868248486556672 +1661868248528557568 +1661868248567558400 +1661868248606559232 +1661868248645560064 +1661868248693561088 +1661868248735561984 +1661868248777562880 +1661868248819563776 +1661868248861564672 +1661868248906565632 +1661868248945566464 +1661868248987567360 +1661868249029568256 +1661868249077569280 +1661868249119570176 +1661868249164571136 +1661868249206572032 +1661868249248572928 +1661868249299574016 +1661868249341574912 +1661868249386575872 +1661868249425576704 +1661868249470577664 +1661868249509578496 +1661868249554579456 +1661868249599580416 +1661868249641581312 +1661868249686582272 +1661868249728583168 +1661868249767584000 +1661868249806584832 +1661868249851585792 +1661868249896586752 +1661868249932587520 +1661868249974588416 +1661868250016589312 +1661868250055590144 +1661868250097591040 +1661868250139591936 +1661868250181592832 +1661868250223593728 +1661868250265594624 +1661868250304595456 +1661868250343596288 +1661868250385597184 +1661868250430598144 +1661868250472599040 +1661868250523600128 +1661868250574601216 +1661868250619602176 +1661868250658603008 +1661868250703603968 +1661868250754605056 +1661868250796605952 +1661868250838606848 +1661868250880607744 +1661868250922608640 +1661868250964609536 +1661868251006610432 +1661868251048611328 +1661868251090612224 +1661868251129613056 +1661868251177614080 +1661868251219614976 +1661868251261615872 +1661868251303616768 +1661868251342617600 +1661868251384618496 +1661868251426619392 +1661868251471620352 +1661868251513621248 +1661868251555622144 +1661868251597623040 +1661868251642624000 +1661868251693625088 +1661868251732625920 +1661868251771626752 +1661868251810627584 +1661868251855628544 +1661868251897629440 +1661868251939630336 +1661868251984631296 +1661868252035632384 +1661868252074633216 +1661868252122634240 +1661868252164635136 +1661868252206636032 +1661868252245636864 +1661868252287637760 +1661868252338638848 +1661868252380639744 +1661868252422640640 +1661868252464641536 +1661868252506642432 +1661868252545643264 +1661868252590644224 +1661868252632645120 +1661868252677646080 +1661868252722647040 +1661868252764647936 +1661868252806648832 +1661868252842649600 +1661868252884650496 +1661868252938651648 +1661868252980652544 +1661868253022653440 +1661868253064654336 +1661868253100655104 +1661868253145656064 +1661868253184656896 +1661868253226657792 +1661868253268658688 +1661868253307659520 +1661868253349660416 +1661868253391661312 +1661868253433662208 +1661868253478663168 +1661868253520664064 +1661868253562664960 +1661868253610665984 +1661868253652666880 +1661868253694667776 +1661868253736668672 +1661868253778669568 +1661868253817670400 +1661868253859671296 +1661868253901672192 +1661868253943673088 +1661868253985673984 +1661868254027674880 +1661868254069675776 +1661868254111676672 +1661868254153677568 +1661868254195678464 +1661868254234679296 +1661868254279680256 +1661868254318681088 +1661868254360681984 +1661868254402682880 +1661868254444683776 +1661868254489684736 +1661868254534685696 +1661868254582686720 +1661868254624687616 +1661868254666688512 +1661868254708689408 +1661868254750690304 +1661868254798691328 +1661868254843692288 +1661868254885693184 +1661868254924694016 +1661868254969694976 +1661868255011695872 +1661868255053696768 +1661868255095697664 +1661868255137698560 +1661868255179699456 +1661868255224700416 +1661868255266701312 +1661868255317702400 +1661868255359703296 +1661868255398704128 +1661868255437704960 +1661868255479705856 +1661868255518706688 +1661868255557707520 +1661868255599708416 +1661868255641709312 +1661868255680710144 +1661868255722711040 +1661868255761711872 +1661868255803712768 +1661868255845713664 +1661868255887714560 +1661868255932715520 +1661868255977716480 +1661868256019717376 +1661868256061718272 +1661868256103719168 +1661868256145720064 +1661868256196721152 +1661868256238722048 +1661868256280722944 +1661868256319723776 +1661868256361724672 +1661868256403725568 +1661868256442726400 +1661868256490727424 +1661868256529728256 +1661868256568729088 +1661868256607729920 +1661868256649730816 +1661868256691731712 +1661868256727732480 +1661868256766733312 +1661868256808734208 +1661868256847735040 +1661868256892736000 +1661868256934736896 +1661868256979737856 +1661868257021738752 +1661868257063739648 +1661868257105740544 +1661868257150741504 +1661868257192742400 +1661868257234743296 +1661868257276744192 +1661868257318745088 +1661868257360745984 +1661868257408747008 +1661868257450747904 +1661868257492748800 +1661868257534749696 +1661868257582750720 +1661868257621751552 +1661868257663752448 +1661868257702753280 +1661868257741754112 +1661868257783755008 +1661868257828755968 +1661868257873756928 +1661868257915757824 +1661868257960758784 +1661868257999759616 +1661868258044760576 +1661868258092761600 +1661868258134762496 +1661868258170763264 +1661868258209764096 +1661868258251764992 +1661868258293765888 +1661868258332766720 +1661868258374767616 +1661868258416768512 +1661868258458769408 +1661868258503770368 +1661868258545771264 +1661868258587772160 +1661868258629773056 +1661868258674774016 +1661868258713774848 +1661868258749775616 +1661868258788776448 +1661868258830777344 +1661868258872778240 +1661868258914779136 +1661868258950779904 +1661868258992780800 +1661868259034781696 +1661868259073782528 +1661868259118783488 +1661868259160784384 +1661868259202785280 +1661868259244786176 +1661868259286787072 +1661868259328787968 +1661868259373788928 +1661868259415789824 +1661868259460790784 +1661868259502791680 +1661868259544792576 +1661868259592793600 +1661868259631794432 +1661868259673795328 +1661868259715796224 +1661868259757797120 +1661868259799798016 +1661868259838798848 +1661868259883799808 +1661868259928800768 +1661868259973801728 +1661868260015802624 +1661868260054803456 +1661868260096804352 +1661868260138805248 +1661868260180806144 +1661868260219806976 +1661868260261807872 +1661868260303808768 +1661868260348809728 +1661868260390810624 +1661868260432811520 +1661868260477812480 +1661868260519813376 +1661868260564814336 +1661868260606815232 +1661868260648816128 +1661868260690817024 +1661868260732817920 +1661868260774818816 +1661868260816819712 +1661868260861820672 +1661868260903821568 +1661868260939822336 +1661868260981823232 +1661868261020824064 +1661868261059824896 +1661868261104825856 +1661868261149826816 +1661868261188827648 +1661868261224828416 +1661868261272829440 +1661868261314830336 +1661868261359831296 +1661868261398832128 +1661868261443833088 +1661868261488834048 +1661868261530834944 +1661868261572835840 +1661868261620836864 +1661868261662837760 +1661868261707838720 +1661868261752839680 +1661868261791840512 +1661868261833841408 +1661868261875842304 +1661868261923843328 +1661868261965844224 +1661868262010845184 +1661868262052846080 +1661868262100847104 +1661868262139847936 +1661868262178848768 +1661868262217849600 +1661868262259850496 +1661868262301851392 +1661868262343852288 +1661868262388853248 +1661868262430854144 +1661868262472855040 +1661868262511855872 +1661868262559856896 +1661868262601857792 +1661868262646858752 +1661868262691859712 +1661868262733860608 +1661868262775861504 +1661868262820862464 +1661868262868863488 +1661868262907864320 +1661868262949865216 +1661868262991866112 +1661868263033867008 +1661868263075867904 +1661868263117868800 +1661868263159869696 +1661868263198870528 +1661868263240871424 +1661868263279872256 +1661868263321873152 +1661868263363874048 +1661868263408875008 +1661868263444875776 +1661868263486876672 +1661868263528877568 +1661868263567878400 +1661868263609879296 +1661868263651880192 +1661868263696881152 +1661868263738882048 +1661868263780882944 +1661868263822883840 +1661868263867884800 +1661868263906885632 +1661868263954886656 +1661868263996887552 +1661868264035888384 +1661868264074889216 +1661868264119890176 +1661868264161891072 +1661868264203891968 +1661868264242892800 +1661868264287893760 +1661868264329894656 +1661868264371895552 +1661868264413896448 +1661868264461897472 +1661868264500898304 +1661868264539899136 +1661868264584900096 +1661868264626900992 +1661868264665901824 +1661868264707902720 +1661868264752903680 +1661868264800904704 +1661868264851905792 +1661868264893906688 +1661868264935907584 +1661868264977908480 +1661868265016909312 +1661868265058910208 +1661868265100911104 +1661868265142912000 +1661868265187912960 +1661868265229913856 +1661868265274914816 +1661868265322915840 +1661868265361916672 +1661868265403917568 +1661868265445918464 +1661868265484919296 +1661868265526920192 +1661868265565921024 +1661868265619922176 +1661868265664923136 +1661868265706924032 +1661868265748924928 +1661868265790925824 +1661868265829926656 +1661868265874927616 +1661868265916928512 +1661868265955929344 +1661868265997930240 +1661868266036931072 +1661868266081932032 +1661868266123932928 +1661868266162933760 +1661868266204934656 +1661868266246935552 +1661868266288936448 +1661868266330937344 +1661868266369938176 +1661868266408939008 +1661868266450939904 +1661868266492940800 +1661868266540941824 +1661868266588942848 +1661868266633943808 +1661868266675944704 +1661868266729945856 +1661868266768946688 +1661868266813947648 +1661868266852948480 +1661868266894949376 +1661868266939950336 +1661868266978951168 +1661868267020952064 +1661868267065953024 +1661868267110953984 +1661868267149954816 +1661868267194955776 +1661868267236956672 +1661868267278957568 +1661868267317958400 +1661868267359959296 +1661868267398960128 +1661868267440961024 +1661868267485961984 +1661868267527962880 +1661868267569963776 +1661868267611964672 +1661868267650965504 +1661868267686966272 +1661868267728967168 +1661868267770968064 +1661868267818969088 +1661868267860969984 +1661868267902970880 +1661868267950971904 +1661868268001972992 +1661868268043973888 +1661868268091974912 +1661868268133975808 +1661868268175976704 +1661868268217977600 +1661868268259978496 +1661868268301979392 +1661868268340980224 +1661868268382981120 +1661868268427982080 +1661868268472983040 +1661868268511983872 +1661868268553984768 +1661868268598985728 +1661868268640986624 +1661868268685987584 +1661868268727988480 +1661868268766989312 +1661868268811990272 +1661868268853991168 +1661868268892992000 +1661868268937992960 +1661868268979993856 +1661868269021994752 +1661868269063995648 +1661868269105996544 +1661868269147997440 +1661868269192998400 +1661868269234999296 +1661868269277000192 +1661868269316001024 +1661868269361001984 +1661868269400002816 +1661868269442003712 +1661868269484004608 +1661868269529005568 +1661868269568006400 +1661868269607007232 +1661868269649008128 +1661868269694009088 +1661868269736009984 +1661868269784011008 +1661868269829011968 +1661868269877012992 +1661868269919013888 +1661868269961014784 +1661868270009015808 +1661868270051016704 +1661868270096017664 +1661868270147018752 +1661868270186019584 +1661868270225020416 +1661868270264021248 +1661868270300022016 +1661868270339022848 +1661868270384023808 +1661868270423024640 +1661868270474025728 +1661868270516026624 +1661868270558027520 +1661868270600028416 +1661868270639029248 +1661868270681030144 +1661868270723031040 +1661868270762031872 +1661868270807032832 +1661868270849033728 +1661868270897034752 +1661868270939035648 +1661868270978036480 +1661868271026037504 +1661868271071038464 +1661868271113039360 +1661868271152040192 +1661868271194041088 +1661868271248042240 +1661868271290043136 +1661868271335044096 +1661868271380045056 +1661868271422045952 +1661868271467046912 +1661868271506047744 +1661868271545048576 +1661868271587049472 +1661868271629050368 +1661868271668051200 +1661868271713052160 +1661868271758053120 +1661868271803054080 +1661868271845054976 +1661868271887055872 +1661868271929056768 +1661868271971057664 +1661868272010058496 +1661868272052059392 +1661868272094060288 +1661868272136061184 +1661868272181062144 +1661868272223063040 +1661868272265063936 +1661868272307064832 +1661868272352065792 +1661868272391066624 +1661868272427067392 +1661868272469068288 +1661868272508069120 +1661868272550070016 +1661868272592070912 +1661868272631071744 +1661868272673072640 +1661868272715073536 +1661868272757074432 +1661868272796075264 +1661868272838076160 +1661868272880077056 +1661868272922077952 +1661868272964078848 +1661868273006079744 +1661868273045080576 +1661868273087081472 +1661868273129082368 +1661868273171083264 +1661868273213084160 +1661868273255085056 +1661868273297085952 +1661868273342086912 +1661868273387087872 +1661868273429088768 +1661868273471089664 +1661868273516090624 +1661868273558091520 +1661868273606092544 +1661868273651093504 +1661868273693094400 +1661868273735095296 +1661868273777096192 +1661868273822097152 +1661868273864098048 +1661868273909099008 +1661868273957100032 +1661868273999100928 +1661868274041101824 +1661868274092102912 +1661868274131103744 +1661868274173104640 +1661868274215105536 +1661868274260106496 +1661868274299107328 +1661868274341108224 +1661868274386109184 +1661868274428110080 +1661868274476111104 +1661868274521112064 +1661868274566113024 +1661868274605113856 +1661868274656114944 +1661868274701115904 +1661868274743116800 +1661868274785117696 +1661868274827118592 +1661868274869119488 +1661868274911120384 +1661868274953121280 +1661868274989122048 +1661868275031122944 +1661868275070123776 +1661868275109124608 +1661868275151125504 +1661868275193126400 +1661868275238127360 +1661868275280128256 +1661868275322129152 +1661868275364130048 +1661868275403130880 +1661868275451131904 +1661868275493132800 +1661868275538133760 +1661868275580134656 +1661868275622135552 +1661868275670136576 +1661868275706137344 +1661868275745138176 +1661868275784139008 +1661868275829139968 +1661868275874140928 +1661868275916141824 +1661868275958142720 +1661868275997143552 +1661868276039144448 +1661868276081145344 +1661868276123146240 +1661868276168147200 +1661868276210148096 +1661868276249148928 +1661868276291149824 +1661868276333150720 +1661868276378151680 +1661868276417152512 +1661868276459153408 +1661868276501154304 +1661868276546155264 +1661868276588156160 +1661868276630157056 +1661868276675158016 +1661868276717158912 +1661868276759159808 +1661868276804160768 +1661868276846161664 +1661868276885162496 +1661868276924163328 +1661868276963164160 +1661868277002164992 +1661868277044165888 +1661868277086166784 +1661868277128167680 +1661868277170168576 +1661868277215169536 +1661868277260170496 +1661868277308171520 +1661868277347172352 +1661868277389173248 +1661868277431174144 +1661868277470174976 +1661868277512175872 +1661868277554176768 +1661868277596177664 +1661868277641178624 +1661868277686179584 +1661868277728180480 +1661868277770181376 +1661868277812182272 +1661868277851183104 +1661868277893184000 +1661868277932184832 +1661868277971185664 +1661868278013186560 +1661868278055187456 +1661868278100188416 +1661868278145189376 +1661868278187190272 +1661868278229191168 +1661868278271192064 +1661868278310192896 +1661868278349193728 +1661868278391194624 +1661868278427195392 +1661868278469196288 +1661868278511197184 +1661868278550198016 +1661868278598199040 +1661868278637199872 +1661868278676200704 +1661868278721201664 +1661868278763202560 +1661868278805203456 +1661868278847204352 +1661868278886205184 +1661868278925206016 +1661868278967206912 +1661868279009207808 +1661868279048208640 +1661868279090209536 +1661868279132210432 +1661868279177211392 +1661868279216212224 +1661868279264213248 +1661868279309214208 +1661868279351215104 +1661868279393216000 +1661868279435216896 +1661868279477217792 +1661868279522218752 +1661868279570219776 +1661868279612220672 +1661868279651221504 +1661868279687222272 +1661868279732223232 +1661868279774224128 +1661868279816225024 +1661868279858225920 +1661868279900226816 +1661868279945227776 +1661868279990228736 +1661868280035229696 +1661868280077230592 +1661868280125231616 +1661868280167232512 +1661868280209233408 +1661868280251234304 +1661868280293235200 +1661868280338236160 +1661868280380237056 +1661868280422237952 +1661868280464238848 +1661868280503239680 +1661868280548240640 +1661868280590241536 +1661868280635242496 +1661868280680243456 +1661868280722244352 +1661868280764245248 +1661868280800246016 +1661868280851247104 +1661868280905248256 +1661868280956249344 +1661868280998250240 +1661868281040251136 +1661868281082252032 +1661868281124252928 +1661868281166253824 +1661868281208254720 +1661868281253255680 +1661868281292256512 +1661868281337257472 +1661868281379258368 +1661868281424259328 +1661868281466260224 +1661868281511261184 +1661868281550262016 +1661868281592262912 +1661868281631263744 +1661868281676264704 +1661868281718265600 +1661868281763266560 +1661868281808267520 +1661868281850268416 +1661868281892269312 +1661868281937270272 +1661868281985271296 +1661868282024272128 +1661868282066273024 +1661868282111273984 +1661868282159275008 +1661868282204275968 +1661868282249276928 +1661868282288277760 +1661868282330278656 +1661868282378279680 +1661868282417280512 +1661868282459281408 +1661868282513282560 +1661868282555283456 +1661868282597284352 +1661868282639285248 +1661868282681286144 +1661868282726287104 +1661868282768288000 +1661868282813288960 +1661868282852289792 +1661868282894290688 +1661868282939291648 +1661868282984292608 +1661868283023293440 +1661868283068294400 +1661868283116295424 +1661868283158296320 +1661868283203297280 +1661868283245298176 +1661868283284299008 +1661868283329299968 +1661868283371300864 +1661868283419301888 +1661868283461302784 +1661868283500303616 +1661868283548304640 +1661868283590305536 +1661868283638306560 +1661868283677307392 +1661868283725308416 +1661868283770309376 +1661868283812310272 +1661868283857311232 +1661868283899312128 +1661868283941313024 +1661868283989314048 +1661868284028314880 +1661868284067315712 +1661868284109316608 +1661868284157317632 +1661868284199318528 +1661868284247319552 +1661868284286320384 +1661868284328321280 +1661868284379322368 +1661868284421323264 +1661868284457324032 +1661868284496324864 +1661868284538325760 +1661868284580326656 +1661868284622327552 +1661868284667328512 +1661868284709329408 +1661868284763330560 +1661868284805331456 +1661868284850332416 +1661868284895333376 +1661868284937334272 +1661868284976335104 +1661868285021336064 +1661868285066337024 +1661868285105337856 +1661868285156338944 +1661868285201339904 +1661868285243340800 +1661868285294341888 +1661868285336342784 +1661868285378343680 +1661868285420344576 +1661868285459345408 +1661868285501346304 +1661868285543347200 +1661868285585348096 +1661868285624348928 +1661868285666349824 +1661868285711350784 +1661868285753351680 +1661868285795352576 +1661868285834353408 +1661868285885354496 +1661868285927355392 +1661868285969356288 +1661868286011357184 +1661868286050358016 +1661868286089358848 +1661868286131359744 +1661868286176360704 +1661868286221361664 +1661868286263362560 +1661868286314363648 +1661868286353364480 +1661868286398365440 +1661868286440366336 +1661868286482367232 +1661868286524368128 +1661868286560368896 +1661868286602369792 +1661868286644370688 +1661868286686371584 +1661868286728372480 +1661868286770373376 +1661868286821374464 +1661868286863375360 +1661868286908376320 +1661868286950377216 +1661868286992378112 +1661868287037379072 +1661868287079379968 +1661868287127380992 +1661868287169381888 +1661868287208382720 +1661868287253383680 +1661868287298384640 +1661868287340385536 +1661868287382386432 +1661868287424387328 +1661868287466388224 +1661868287508389120 +1661868287550390016 +1661868287592390912 +1661868287634391808 +1661868287676392704 +1661868287718393600 +1661868287760394496 +1661868287805395456 +1661868287847396352 +1661868287895397376 +1661868287937398272 +1661868287976399104 +1661868288015399936 +1661868288063400960 +1661868288105401856 +1661868288147402752 +1661868288189403648 +1661868288231404544 +1661868288273405440 +1661868288315406336 +1661868288354407168 +1661868288396408064 +1661868288438408960 +1661868288483409920 +1661868288525410816 +1661868288570411776 +1661868288606412544 +1661868288648413440 +1661868288690414336 +1661868288732415232 +1661868288774416128 +1661868288816417024 +1661868288858417920 +1661868288900418816 +1661868288951419904 +1661868288993420800 +1661868289041421824 +1661868289083422720 +1661868289128423680 +1661868289170424576 +1661868289212425472 +1661868289257426432 +1661868289296427264 +1661868289338428160 +1661868289380429056 +1661868289428430080 +1661868289476431104 +1661868289518432000 +1661868289560432896 +1661868289602433792 +1661868289641434624 +1661868289683435520 +1661868289725436416 +1661868289767437312 +1661868289809438208 +1661868289851439104 +1661868289890439936 +1661868289935440896 +1661868289983441920 +1661868290025442816 +1661868290067443712 +1661868290115444736 +1661868290154445568 +1661868290199446528 +1661868290244447488 +1661868290289448448 +1661868290328449280 +1661868290364450048 +1661868290412451072 +1661868290454451968 +1661868290496452864 +1661868290535453696 +1661868290580454656 +1661868290622455552 +1661868290664456448 +1661868290706457344 +1661868290754458368 +1661868290802459392 +1661868290841460224 +1661868290883461120 +1661868290925462016 +1661868290967462912 +1661868291015463936 +1661868291060464896 +1661868291102465792 +1661868291144466688 +1661868291186467584 +1661868291231468544 +1661868291270469376 +1661868291312470272 +1661868291354471168 +1661868291396472064 +1661868291438472960 +1661868291483473920 +1661868291525474816 +1661868291567475712 +1661868291609476608 +1661868291648477440 +1661868291690478336 +1661868291732479232 +1661868291771480064 +1661868291813480960 +1661868291855481856 +1661868291900482816 +1661868291942483712 +1661868291984484608 +1661868292026485504 +1661868292071486464 +1661868292113487360 +1661868292152488192 +1661868292194489088 +1661868292233489920 +1661868292281490944 +1661868292320491776 +1661868292359492608 +1661868292401493504 +1661868292443494400 +1661868292485495296 +1661868292530496256 +1661868292572497152 +1661868292614498048 +1661868292656498944 +1661868292698499840 +1661868292743500800 +1661868292785501696 +1661868292821502464 +1661868292869503488 +1661868292911504384 +1661868292959505408 +1661868293001506304 +1661868293043507200 +1661868293085508096 +1661868293130509056 +1661868293175510016 +1661868293217510912 +1661868293265511936 +1661868293313512960 +1661868293352513792 +1661868293391514624 +1661868293430515456 +1661868293472516352 +1661868293520517376 +1661868293562518272 +1661868293601519104 +1661868293643520000 +1661868293685520896 +1661868293730521856 +1661868293772522752 +1661868293811523584 +1661868293853524480 +1661868293898525440 +1661868293940526336 +1661868293985527296 +1661868294027528192 +1661868294069529088 +1661868294111529984 +1661868294162531072 +1661868294204531968 +1661868294246532864 +1661868294285533696 +1661868294324534528 +1661868294366535424 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track1.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track1.txt new file mode 100644 index 0000000000..f8502440d4 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track1.txt @@ -0,0 +1,2030 @@ +1662015311059723520 +1662015311101724416 +1662015311146725376 +1662015311203726592 +1662015311248727552 +1662015311293728512 +1662015311335729408 +1662015311377730304 +1662015311422731264 +1662015311464732160 +1662015311506733056 +1662015311548733952 +1662015311590734848 +1662015311635735808 +1662015311677736704 +1662015311719737600 +1662015311761738496 +1662015311809739520 +1662015311857740544 +1662015311902741504 +1662015311944742400 +1662015311986743296 +1662015312031744256 +1662015312076745216 +1662015312130746368 +1662015312169747200 +1662015312208748032 +1662015312253748992 +1662015312295749888 +1662015312340750848 +1662015312379751680 +1662015312424752640 +1662015312463753472 +1662015312508754432 +1662015312550755328 +1662015312592756224 +1662015312631757056 +1662015312679758080 +1662015312724759040 +1662015312766759936 +1662015312811760896 +1662015312856761856 +1662015312901762816 +1662015312943763712 +1662015312985764608 +1662015313027765504 +1662015313075766528 +1662015313117767424 +1662015313159768320 +1662015313201769216 +1662015313240770048 +1662015313282770944 +1662015313327771904 +1662015313369772800 +1662015313411773696 +1662015313456774656 +1662015313498775552 +1662015313540776448 +1662015313591777536 +1662015313630778368 +1662015313672779264 +1662015313717780224 +1662015313756781056 +1662015313801782016 +1662015313843782912 +1662015313885783808 +1662015313927784704 +1662015313972785664 +1662015314014786560 +1662015314056787456 +1662015314101788416 +1662015314143789312 +1662015314185790208 +1662015314227791104 +1662015314272792064 +1662015314317793024 +1662015314362793984 +1662015314413795072 +1662015314455795968 +1662015314497796864 +1662015314539797760 +1662015314581798656 +1662015314626799616 +1662015314668800512 +1662015314716801536 +1662015314761802496 +1662015314803803392 +1662015314848804352 +1662015314896805376 +1662015314938806272 +1662015314980807168 +1662015315028808192 +1662015315073809152 +1662015315115810048 +1662015315154810880 +1662015315199811840 +1662015315238812672 +1662015315280813568 +1662015315328814592 +1662015315379815680 +1662015315427816704 +1662015315475817728 +1662015315532818944 +1662015315577819904 +1662015315619820800 +1662015315670821888 +1662015315721822976 +1662015315766823936 +1662015315814824960 +1662015315859825920 +1662015315904826880 +1662015315949827840 +1662015315991828736 +1662015316033829632 +1662015316078830592 +1662015316126831616 +1662015316174832640 +1662015316219833600 +1662015316270834688 +1662015316315835648 +1662015316366836736 +1662015316414837760 +1662015316462838784 +1662015316507839744 +1662015316552840704 +1662015316597841664 +1662015316648842752 +1662015316690843648 +1662015316729844480 +1662015316774845440 +1662015316822846464 +1662015316867847424 +1662015316909848320 +1662015316951849216 +1662015316993850112 +1662015317038851072 +1662015317083852032 +1662015317128852992 +1662015317170853888 +1662015317218854912 +1662015317260855808 +1662015317302856704 +1662015317344857600 +1662015317389858560 +1662015317434859520 +1662015317473860352 +1662015317515861248 +1662015317560862208 +1662015317605863168 +1662015317647864064 +1662015317692865024 +1662015317740866048 +1662015317782866944 +1662015317830867968 +1662015317872868864 +1662015317914869760 +1662015317962870784 +1662015318010871808 +1662015318058872832 +1662015318109873920 +1662015318148874752 +1662015318193875712 +1662015318235876608 +1662015318280877568 +1662015318325878528 +1662015318367879424 +1662015318412880384 +1662015318454881280 +1662015318499882240 +1662015318547883264 +1662015318589884160 +1662015318631885056 +1662015318682886144 +1662015318727887104 +1662015318769888000 +1662015318814888960 +1662015318859889920 +1662015318907890944 +1662015318952891904 +1662015318994892800 +1662015319036893696 +1662015319078894592 +1662015319120895488 +1662015319162896384 +1662015319207897344 +1662015319249898240 +1662015319291899136 +1662015319339900160 +1662015319387901184 +1662015319432902144 +1662015319474903040 +1662015319516903936 +1662015319561904896 +1662015319609905920 +1662015319654906880 +1662015319699907840 +1662015319741908736 +1662015319792909824 +1662015319840910848 +1662015319891911936 +1662015319939912960 +1662015319981913856 +1662015320023914752 +1662015320077915904 +1662015320125916928 +1662015320167917824 +1662015320209918720 +1662015320251919616 +1662015320296920576 +1662015320338921472 +1662015320389922560 +1662015320437923584 +1662015320485924608 +1662015320530925568 +1662015320575926528 +1662015320617927424 +1662015320659928320 +1662015320704929280 +1662015320746930176 +1662015320791931136 +1662015320839932160 +1662015320881933056 +1662015320926934016 +1662015320968934912 +1662015321010935808 +1662015321058936832 +1662015321103937792 +1662015321145938688 +1662015321193939712 +1662015321241940736 +1662015321283941632 +1662015321328942592 +1662015321373943552 +1662015321415944448 +1662015321454945280 +1662015321499946240 +1662015321541947136 +1662015321592948224 +1662015321637949184 +1662015321685950208 +1662015321727951104 +1662015321775952128 +1662015321817953024 +1662015321859953920 +1662015321901954816 +1662015321943955712 +1662015321985956608 +1662015322033957632 +1662015322084958720 +1662015322126959616 +1662015322171960576 +1662015322222961664 +1662015322267962624 +1662015322309963520 +1662015322351964416 +1662015322396965376 +1662015322438966272 +1662015322483967232 +1662015322528968192 +1662015322567969024 +1662015322609969920 +1662015322651970816 +1662015322699971840 +1662015322741972736 +1662015322786973696 +1662015322828974592 +1662015322876975616 +1662015322918976512 +1662015322966977536 +1662015323008978432 +1662015323059979520 +1662015323101980416 +1662015323143981312 +1662015323188982272 +1662015323230983168 +1662015323272984064 +1662015323314984960 +1662015323359985920 +1662015323404986880 +1662015323455987968 +1662015323494988800 +1662015323542989824 +1662015323584990720 +1662015323629991680 +1662015323671992576 +1662015323713993472 +1662015323755994368 +1662015323803995392 +1662015323848996352 +1662015323896997376 +1662015323938998272 +1662015323980999168 +1662015324026000128 +1662015324071001088 +1662015324113001984 +1662015324164003072 +1662015324206003968 +1662015324251004928 +1662015324293005824 +1662015324338006784 +1662015324386007808 +1662015324431008768 +1662015324473009664 +1662015324515010560 +1662015324560011520 +1662015324605012480 +1662015324653013504 +1662015324695014400 +1662015324740015360 +1662015324785016320 +1662015324827017216 +1662015324875018240 +1662015324917019136 +1662015324965020160 +1662015325013021184 +1662015325055022080 +1662015325100023040 +1662015325145024000 +1662015325190024960 +1662015325232025856 +1662015325274026752 +1662015325322027776 +1662015325367028736 +1662015325412029696 +1662015325457030656 +1662015325505031680 +1662015325547032576 +1662015325592033536 +1662015325634034432 +1662015325676035328 +1662015325718036224 +1662015325760037120 +1662015325805038080 +1662015325847038976 +1662015325889039872 +1662015325934040832 +1662015325985041920 +1662015326036043008 +1662015326084044032 +1662015326126044928 +1662015326177046016 +1662015326225047040 +1662015326276048128 +1662015326321049088 +1662015326363049984 +1662015326408050944 +1662015326453051904 +1662015326495052800 +1662015326537053696 +1662015326582054656 +1662015326627055616 +1662015326681056768 +1662015326723057664 +1662015326771058688 +1662015326813059584 +1662015326855060480 +1662015326897061376 +1662015326942062336 +1662015326987063296 +1662015327029064192 +1662015327074065152 +1662015327116066048 +1662015327161067008 +1662015327203067904 +1662015327245068800 +1662015327290069760 +1662015327335070720 +1662015327380071680 +1662015327419072512 +1662015327464073472 +1662015327509074432 +1662015327554075392 +1662015327596076288 +1662015327644077312 +1662015327686078208 +1662015327731079168 +1662015327776080128 +1662015327818081024 +1662015327863081984 +1662015327905082880 +1662015327950083840 +1662015327992084736 +1662015328034085632 +1662015328076086528 +1662015328118087424 +1662015328163088384 +1662015328205089280 +1662015328247090176 +1662015328292091136 +1662015328334092032 +1662015328376092928 +1662015328418093824 +1662015328457094656 +1662015328499095552 +1662015328544096512 +1662015328589097472 +1662015328634098432 +1662015328682099456 +1662015328724100352 +1662015328775101440 +1662015328820102400 +1662015328868103424 +1662015328907104256 +1662015328955105280 +1662015329012106496 +1662015329066107648 +1662015329108108544 +1662015329153109504 +1662015329198110464 +1662015329243111424 +1662015329288112384 +1662015329336113408 +1662015329378114304 +1662015329423115264 +1662015329468116224 +1662015329513117184 +1662015329555118080 +1662015329597118976 +1662015329639119872 +1662015329681120768 +1662015329726121728 +1662015329771122688 +1662015329816123648 +1662015329861124608 +1662015329906125568 +1662015329948126464 +1662015329996127488 +1662015330044128512 +1662015330086129408 +1662015330134130432 +1662015330185131520 +1662015330227132416 +1662015330272133376 +1662015330320134400 +1662015330368135424 +1662015330413136384 +1662015330458137344 +1662015330506138368 +1662015330548139264 +1662015330596140288 +1662015330638141184 +1662015330683142144 +1662015330725143040 +1662015330770144000 +1662015330815144960 +1662015330857145856 +1662015330914147072 +1662015330959148032 +1662015331010149120 +1662015331049149952 +1662015331094150912 +1662015331136151808 +1662015331178152704 +1662015331223153664 +1662015331265154560 +1662015331310155520 +1662015331355156480 +1662015331397157376 +1662015331442158336 +1662015331487159296 +1662015331529160192 +1662015331571161088 +1662015331619162112 +1662015331667163136 +1662015331709164032 +1662015331751164928 +1662015331796165888 +1662015331847166976 +1662015331895168000 +1662015331940168960 +1662015331994170112 +1662015332039171072 +1662015332081171968 +1662015332123172864 +1662015332165173760 +1662015332213174784 +1662015332255175680 +1662015332300176640 +1662015332342177536 +1662015332384178432 +1662015332432179456 +1662015332477180416 +1662015332525181440 +1662015332567182336 +1662015332609183232 +1662015332654184192 +1662015332699185152 +1662015332747186176 +1662015332792187136 +1662015332837188096 +1662015332885189120 +1662015332930190080 +1662015332972190976 +1662015333017191936 +1662015333065192960 +1662015333107193856 +1662015333149194752 +1662015333191195648 +1662015333242196736 +1662015333293197824 +1662015333335198720 +1662015333380199680 +1662015333422200576 +1662015333470201600 +1662015333515202560 +1662015333557203456 +1662015333602204416 +1662015333647205376 +1662015333689206272 +1662015333734207232 +1662015333776208128 +1662015333821209088 +1662015333863209984 +1662015333905210880 +1662015333947211776 +1662015333992212736 +1662015334037213696 +1662015334082214656 +1662015334124215552 +1662015334169216512 +1662015334214217472 +1662015334259218432 +1662015334301219328 +1662015334343220224 +1662015334385221120 +1662015334427222016 +1662015334472222976 +1662015334520224000 +1662015334559224832 +1662015334604225792 +1662015334649226752 +1662015334694227712 +1662015334739228672 +1662015334781229568 +1662015334826230528 +1662015334874231552 +1662015334925232640 +1662015334967233536 +1662015335018234624 +1662015335063235584 +1662015335111236608 +1662015335153237504 +1662015335195238400 +1662015335240239360 +1662015335285240320 +1662015335330241280 +1662015335369242112 +1662015335423243264 +1662015335465244160 +1662015335507245056 +1662015335552246016 +1662015335597246976 +1662015335639247872 +1662015335690248960 +1662015335735249920 +1662015335774250752 +1662015335822251776 +1662015335864252672 +1662015335909253632 +1662015335957254656 +1662015336005255680 +1662015336047256576 +1662015336101257728 +1662015336149258752 +1662015336191259648 +1662015336233260544 +1662015336275261440 +1662015336317262336 +1662015336365263360 +1662015336407264256 +1662015336449265152 +1662015336497266176 +1662015336536267008 +1662015336581267968 +1662015336626268928 +1662015336671269888 +1662015336716270848 +1662015336767271936 +1662015336812272896 +1662015336857273856 +1662015336902274816 +1662015336950275840 +1662015336992276736 +1662015337034277632 +1662015337076278528 +1662015337118279424 +1662015337163280384 +1662015337208281344 +1662015337250282240 +1662015337295283200 +1662015337343284224 +1662015337385285120 +1662015337427286016 +1662015337469286912 +1662015337517287936 +1662015337568289024 +1662015337610289920 +1662015337652290816 +1662015337694291712 +1662015337733292544 +1662015337778293504 +1662015337826294528 +1662015337871295488 +1662015337913296384 +1662015337958297344 +1662015338000298240 +1662015338042299136 +1662015338087300096 +1662015338135301120 +1662015338177302016 +1662015338219302912 +1662015338258303744 +1662015338300304640 +1662015338345305600 +1662015338396306688 +1662015338438307584 +1662015338474308352 +1662015338519309312 +1662015338561310208 +1662015338606311168 +1662015338645312000 +1662015338687312896 +1662015338732313856 +1662015338774314752 +1662015338816315648 +1662015338858316544 +1662015338900317440 +1662015338942318336 +1662015338984319232 +1662015339026320128 +1662015339068321024 +1662015339113321984 +1662015339161323008 +1662015339206323968 +1662015339248324864 +1662015339296325888 +1662015339338326784 +1662015339380327680 +1662015339422328576 +1662015339467329536 +1662015339509330432 +1662015339551331328 +1662015339596332288 +1662015339641333248 +1662015339686334208 +1662015339728335104 +1662015339770336000 +1662015339809336832 +1662015339857337856 +1662015339902338816 +1662015339944339712 +1662015339986340608 +1662015340028341504 +1662015340079342592 +1662015340121343488 +1662015340163344384 +1662015340205345280 +1662015340259346432 +1662015340301347328 +1662015340346348288 +1662015340388349184 +1662015340433350144 +1662015340475351040 +1662015340520352000 +1662015340565352960 +1662015340613353984 +1662015340655354880 +1662015340697355776 +1662015340745356800 +1662015340793357824 +1662015340835358720 +1662015340874359552 +1662015340919360512 +1662015340964361472 +1662015341006362368 +1662015341051363328 +1662015341093364224 +1662015341141365248 +1662015341183366144 +1662015341225367040 +1662015341270368000 +1662015341312368896 +1662015341354369792 +1662015341399370752 +1662015341438371584 +1662015341480372480 +1662015341525373440 +1662015341570374400 +1662015341615375360 +1662015341663376384 +1662015341705377280 +1662015341750378240 +1662015341798379264 +1662015341840380160 +1662015341882381056 +1662015341930382080 +1662015341969382912 +1662015342011383808 +1662015342053384704 +1662015342095385600 +1662015342140386560 +1662015342185387520 +1662015342230388480 +1662015342278389504 +1662015342326390528 +1662015342371391488 +1662015342416392448 +1662015342458393344 +1662015342500394240 +1662015342539395072 +1662015342581395968 +1662015342632397056 +1662015342674397952 +1662015342716398848 +1662015342764399872 +1662015342803400704 +1662015342845401600 +1662015342884402432 +1662015342926403328 +1662015342968404224 +1662015343013405184 +1662015343055406080 +1662015343097406976 +1662015343148408064 +1662015343193409024 +1662015343238409984 +1662015343286411008 +1662015343331411968 +1662015343373412864 +1662015343418413824 +1662015343466414848 +1662015343511415808 +1662015343553416704 +1662015343595417600 +1662015343637418496 +1662015343685419520 +1662015343727420416 +1662015343772421376 +1662015343823422464 +1662015343865423360 +1662015343907424256 +1662015343952425216 +1662015343997426176 +1662015344039427072 +1662015344084428032 +1662015344129428992 +1662015344177430016 +1662015344219430912 +1662015344264431872 +1662015344315432960 +1662015344357433856 +1662015344405434880 +1662015344447435776 +1662015344495436800 +1662015344537437696 +1662015344585438720 +1662015344627439616 +1662015344672440576 +1662015344717441536 +1662015344759442432 +1662015344810443520 +1662015344855444480 +1662015344894445312 +1662015344939446272 +1662015344987447296 +1662015345029448192 +1662015345074449152 +1662015345119450112 +1662015345161451008 +1662015345206451968 +1662015345248452864 +1662015345296453888 +1662015345338454784 +1662015345380455680 +1662015345428456704 +1662015345476457728 +1662015345521458688 +1662015345560459520 +1662015345608460544 +1662015345656461568 +1662015345695462400 +1662015345737463296 +1662015345779464192 +1662015345824465152 +1662015345866466048 +1662015345914467072 +1662015345956467968 +1662015346001468928 +1662015346052470016 +1662015346094470912 +1662015346136471808 +1662015346184472832 +1662015346229473792 +1662015346277474816 +1662015346322475776 +1662015346364476672 +1662015346406477568 +1662015346448478464 +1662015346490479360 +1662015346535480320 +1662015346577481216 +1662015346622482176 +1662015346661483008 +1662015346706483968 +1662015346748484864 +1662015346790485760 +1662015346835486720 +1662015346883487744 +1662015346922488576 +1662015346964489472 +1662015347009490432 +1662015347051491328 +1662015347093492224 +1662015347138493184 +1662015347180494080 +1662015347222494976 +1662015347270496000 +1662015347315496960 +1662015347354497792 +1662015347396498688 +1662015347438499584 +1662015347483500544 +1662015347525501440 +1662015347567502336 +1662015347609503232 +1662015347663504384 +1662015347705505280 +1662015347750506240 +1662015347798507264 +1662015347840508160 +1662015347885509120 +1662015347933510144 +1662015347975511040 +1662015348017511936 +1662015348062512896 +1662015348107513856 +1662015348155514880 +1662015348197515776 +1662015348239516672 +1662015348284517632 +1662015348332518656 +1662015348377519616 +1662015348419520512 +1662015348464521472 +1662015348509522432 +1662015348557523456 +1662015348602524416 +1662015348644525312 +1662015348683526144 +1662015348725527040 +1662015348770528000 +1662015348812528896 +1662015348854529792 +1662015348899530752 +1662015348944531712 +1662015348992532736 +1662015349034533632 +1662015349076534528 +1662015349121535488 +1662015349163536384 +1662015349205537280 +1662015349247538176 +1662015349292539136 +1662015349343540224 +1662015349391541248 +1662015349433542144 +1662015349475543040 +1662015349517543936 +1662015349562544896 +1662015349604545792 +1662015349649546752 +1662015349694547712 +1662015349739548672 +1662015349781549568 +1662015349826550528 +1662015349865551360 +1662015349907552256 +1662015349949553152 +1662015349994554112 +1662015350045555200 +1662015350090556160 +1662015350135557120 +1662015350177558016 +1662015350219558912 +1662015350255559680 +1662015350297560576 +1662015350339561472 +1662015350387562496 +1662015350438563584 +1662015350480564480 +1662015350522565376 +1662015350564566272 +1662015350606567168 +1662015350651568128 +1662015350693569024 +1662015350738569984 +1662015350786571008 +1662015350831571968 +1662015350873572864 +1662015350918573824 +1662015350963574784 +1662015351005575680 +1662015351050576640 +1662015351095577600 +1662015351140578560 +1662015351182579456 +1662015351224580352 +1662015351269581312 +1662015351314582272 +1662015351359583232 +1662015351398584064 +1662015351443585024 +1662015351488585984 +1662015351530586880 +1662015351575587840 +1662015351626588928 +1662015351668589824 +1662015351716590848 +1662015351767591936 +1662015351809592832 +1662015351857593856 +1662015351905594880 +1662015351950595840 +1662015351992596736 +1662015352037597696 +1662015352082598656 +1662015352127599616 +1662015352166600448 +1662015352214601472 +1662015352256602368 +1662015352298603264 +1662015352340604160 +1662015352373604864 +1662015352412605696 +1662015352454606592 +1662015352499607552 +1662015352544608512 +1662015352592609536 +1662015352637610496 +1662015352679611392 +1662015352724612352 +1662015352769613312 +1662015352814614272 +1662015352859615232 +1662015352901616128 +1662015352949617152 +1662015352994618112 +1662015353036619008 +1662015353081619968 +1662015353126620928 +1662015353174621952 +1662015353219622912 +1662015353264623872 +1662015353309624832 +1662015353351625728 +1662015353396626688 +1662015353438627584 +1662015353483628544 +1662015353525629440 +1662015353564630272 +1662015353606631168 +1662015353648632064 +1662015353690632960 +1662015353738633984 +1662015353780634880 +1662015353822635776 +1662015353861636608 +1662015353909637632 +1662015353954638592 +1662015353993639424 +1662015354035640320 +1662015354083641344 +1662015354122642176 +1662015354164643072 +1662015354209644032 +1662015354251644928 +1662015354299645952 +1662015354341646848 +1662015354380647680 +1662015354425648640 +1662015354470649600 +1662015354512650496 +1662015354554651392 +1662015354599652352 +1662015354647653376 +1662015354689654272 +1662015354731655168 +1662015354779656192 +1662015354824657152 +1662015354863657984 +1662015354911659008 +1662015354953659904 +1662015354992660736 +1662015355037661696 +1662015355085662720 +1662015355130663680 +1662015355172664576 +1662015355217665536 +1662015355259666432 +1662015355301667328 +1662015355343668224 +1662015355388669184 +1662015355433670144 +1662015355475671040 +1662015355520672000 +1662015355565672960 +1662015355604673792 +1662015355649674752 +1662015355691675648 +1662015355739676672 +1662015355781677568 +1662015355823678464 +1662015355865679360 +1662015355907680256 +1662015355949681152 +1662015355997682176 +1662015356042683136 +1662015356087684096 +1662015356129684992 +1662015356174685952 +1662015356216686848 +1662015356261687808 +1662015356303688704 +1662015356351689728 +1662015356399690752 +1662015356441691648 +1662015356480692480 +1662015356522693376 +1662015356564694272 +1662015356612695296 +1662015356654696192 +1662015356699697152 +1662015356741698048 +1662015356783698944 +1662015356828699904 +1662015356864700672 +1662015356906701568 +1662015356951702528 +1662015356993703424 +1662015357035704320 +1662015357083705344 +1662015357128706304 +1662015357170707200 +1662015357212708096 +1662015357254708992 +1662015357293709824 +1662015357338710784 +1662015357383711744 +1662015357428712704 +1662015357482713856 +1662015357524714752 +1662015357566715648 +1662015357611716608 +1662015357659717632 +1662015357704718592 +1662015357746719488 +1662015357794720512 +1662015357836721408 +1662015357884722432 +1662015357929723392 +1662015357971724288 +1662015358013725184 +1662015358058726144 +1662015358103727104 +1662015358145728000 +1662015358187728896 +1662015358241730048 +1662015358280730880 +1662015358325731840 +1662015358367732736 +1662015358409733632 +1662015358451734528 +1662015358493735424 +1662015358544736512 +1662015358586737408 +1662015358631738368 +1662015358676739328 +1662015358718740224 +1662015358763741184 +1662015358811742208 +1662015358853743104 +1662015358895744000 +1662015358943745024 +1662015358988745984 +1662015359036747008 +1662015359078747904 +1662015359123748864 +1662015359165749760 +1662015359207750656 +1662015359246751488 +1662015359294752512 +1662015359336753408 +1662015359381754368 +1662015359423755264 +1662015359462756096 +1662015359504756992 +1662015359546757888 +1662015359588758784 +1662015359630759680 +1662015359675760640 +1662015359714761472 +1662015359756762368 +1662015359798763264 +1662015359843764224 +1662015359888765184 +1662015359927766016 +1662015359969766912 +1662015360011767808 +1662015360053768704 +1662015360098769664 +1662015360143770624 +1662015360185771520 +1662015360230772480 +1662015360275773440 +1662015360320774400 +1662015360371775488 +1662015360413776384 +1662015360452777216 +1662015360503778304 +1662015360542779136 +1662015360590780160 +1662015360635781120 +1662015360680782080 +1662015360722782976 +1662015360767783936 +1662015360812784896 +1662015360863785984 +1662015360905786880 +1662015360947787776 +1662015360989788672 +1662015361037789696 +1662015361079790592 +1662015361121791488 +1662015361169792512 +1662015361214793472 +1662015361259794432 +1662015361301795328 +1662015361346796288 +1662015361394797312 +1662015361436798208 +1662015361478799104 +1662015361520800000 +1662015361571801088 +1662015361613801984 +1662015361658802944 +1662015361700803840 +1662015361751804928 +1662015361793805824 +1662015361838806784 +1662015361880807680 +1662015361922808576 +1662015361967809536 +1662015362012810496 +1662015362054811392 +1662015362099812352 +1662015362144813312 +1662015362189814272 +1662015362234815232 +1662015362279816192 +1662015362321817088 +1662015362363817984 +1662015362408818944 +1662015362444819712 +1662015362480820480 +1662015362522821376 +1662015362567822336 +1662015362612823296 +1662015362654824192 +1662015362702825216 +1662015362744826112 +1662015362792827136 +1662015362840828160 +1662015362885829120 +1662015362927830016 +1662015362969830912 +1662015363014831872 +1662015363056832768 +1662015363098833664 +1662015363140834560 +1662015363185835520 +1662015363230836480 +1662015363269837312 +1662015363311838208 +1662015363353839104 +1662015363401840128 +1662015363446841088 +1662015363494842112 +1662015363536843008 +1662015363581843968 +1662015363623844864 +1662015363665845760 +1662015363716846848 +1662015363758847744 +1662015363800848640 +1662015363842849536 +1662015363884850432 +1662015363926851328 +1662015363971852288 +1662015364016853248 +1662015364061854208 +1662015364106855168 +1662015364151856128 +1662015364196857088 +1662015364241858048 +1662015364283858944 +1662015364325859840 +1662015364370860800 +1662015364421861888 +1662015364469862912 +1662015364508863744 +1662015364556864768 +1662015364601865728 +1662015364643866624 +1662015364685867520 +1662015364730868480 +1662015364778869504 +1662015364823870464 +1662015364865871360 +1662015364904872192 +1662015364946873088 +1662015364991874048 +1662015365042875136 +1662015365087876096 +1662015365129876992 +1662015365177878016 +1662015365225879040 +1662015365267879936 +1662015365315880960 +1662015365357881856 +1662015365399882752 +1662015365441883648 +1662015365483884544 +1662015365525885440 +1662015365570886400 +1662015365612887296 +1662015365657888256 +1662015365696889088 +1662015365741890048 +1662015365783890944 +1662015365828891904 +1662015365870892800 +1662015365915893760 +1662015365960894720 +1662015366002895616 +1662015366050896640 +1662015366092897536 +1662015366137898496 +1662015366179899392 +1662015366224900352 +1662015366266901248 +1662015366314902272 +1662015366359903232 +1662015366407904256 +1662015366449905152 +1662015366503906304 +1662015366545907200 +1662015366590908160 +1662015366635909120 +1662015366680910080 +1662015366722910976 +1662015366773912064 +1662015366818913024 +1662015366863913984 +1662015366914915072 +1662015366959916032 +1662015367004916992 +1662015367046917888 +1662015367091918848 +1662015367145920000 +1662015367190920960 +1662015367232921856 +1662015367274922752 +1662015367319923712 +1662015367364924672 +1662015367409925632 +1662015367451926528 +1662015367496927488 +1662015367538928384 +1662015367583929344 +1662015367628930304 +1662015367667931136 +1662015367712932096 +1662015367757933056 +1662015367799933952 +1662015367841934848 +1662015367880935680 +1662015367922936576 +1662015367970937600 +1662015368012938496 +1662015368054939392 +1662015368099940352 +1662015368144941312 +1662015368183942144 +1662015368228943104 +1662015368273944064 +1662015368315944960 +1662015368360945920 +1662015368402946816 +1662015368453947904 +1662015368495948800 +1662015368537949696 +1662015368579950592 +1662015368627951616 +1662015368672952576 +1662015368723953664 +1662015368768954624 +1662015368816955648 +1662015368861956608 +1662015368900957440 +1662015368948958464 +1662015368990959360 +1662015369035960320 +1662015369077961216 +1662015369119962112 +1662015369158962944 +1662015369200963840 +1662015369242964736 +1662015369284965632 +1662015369329966592 +1662015369377967616 +1662015369419968512 +1662015369461969408 +1662015369509970432 +1662015369560971520 +1662015369602972416 +1662015369641973248 +1662015369686974208 +1662015369725975040 +1662015369770976000 +1662015369809976832 +1662015369854977792 +1662015369896978688 +1662015369935979520 +1662015369977980416 +1662015370022981376 +1662015370064982272 +1662015370103983104 +1662015370151984128 +1662015370196985088 +1662015370238985984 +1662015370280986880 +1662015370322987776 +1662015370373988864 +1662015370415989760 +1662015370457990656 +1662015370502991616 +1662015370547992576 +1662015370592993536 +1662015370640994560 +1662015370682995456 +1662015370724996352 +1662015370775997440 +1662015370820998400 +1662015370862999296 +1662015370908000256 +1662015370950001152 +1662015370995002112 +1662015371040003072 +1662015371085004032 +1662015371133005056 +1662015371172005888 +1662015371214006784 +1662015371256007680 +1662015371298008576 +1662015371340009472 +1662015371385010432 +1662015371430011392 +1662015371478012416 +1662015371526013440 +1662015371571014400 +1662015371616015360 +1662015371661016320 +1662015371703017216 +1662015371742018048 +1662015371781018880 +1662015371826019840 +1662015371865020672 +1662015371913021696 +1662015371958022656 +1662015372003023616 +1662015372045024512 +1662015372087025408 +1662015372129026304 +1662015372177027328 +1662015372216028160 +1662015372258029056 +1662015372303030016 +1662015372345030912 +1662015372384031744 +1662015372438032896 +1662015372483033856 +1662015372525034752 +1662015372570035712 +1662015372615036672 +1662015372660037632 +1662015372702038528 +1662015372747039488 +1662015372792040448 +1662015372834041344 +1662015372876042240 +1662015372915043072 +1662015372960044032 +1662015373005044992 +1662015373047045888 +1662015373089046784 +1662015373134047744 +1662015373179048704 +1662015373227049728 +1662015373278050816 +1662015373323051776 +1662015373368052736 +1662015373416053760 +1662015373464054784 +1662015373512055808 +1662015373557056768 +1662015373590057472 +1662015373635058432 +1662015373677059328 +1662015373722060288 +1662015373770061312 +1662015373812062208 +1662015373854063104 +1662015373896064000 +1662015373941064960 +1662015373986065920 +1662015374028066816 +1662015374070067712 +1662015374112068608 +1662015374157069568 +1662015374199070464 +1662015374244071424 +1662015374292072448 +1662015374334073344 +1662015374373074176 +1662015374415075072 +1662015374460076032 +1662015374511077120 +1662015374553078016 +1662015374595078912 +1662015374643079936 +1662015374697081088 +1662015374742082048 +1662015374784082944 +1662015374823083776 +1662015374868084736 +1662015374913085696 +1662015374958086656 +1662015375003087616 +1662015375045088512 +1662015375087089408 +1662015375129090304 +1662015375180091392 +1662015375225092352 +1662015375276093440 +1662015375315094272 +1662015375360095232 +1662015375402096128 +1662015375453097216 +1662015375498098176 +1662015375549099264 +1662015375591100160 +1662015375636101120 +1662015375678102016 +1662015375720102912 +1662015375765103872 +1662015375813104896 +1662015375858105856 +1662015375903106816 +1662015375948107776 +1662015375996108800 +1662015376038109696 +1662015376080110592 +1662015376119111424 +1662015376167112448 +1662015376209113344 +1662015376257114368 +1662015376305115392 +1662015376347116288 +1662015376392117248 +1662015376434118144 +1662015376479119104 +1662015376524120064 +1662015376569121024 +1662015376614121984 +1662015376656122880 +1662015376707123968 +1662015376752124928 +1662015376803126016 +1662015376848126976 +1662015376893127936 +1662015376938128896 +1662015376980129792 +1662015377028130816 +1662015377073131776 +1662015377115132672 +1662015377154133504 +1662015377196134400 +1662015377238135296 +1662015377286136320 +1662015377337137408 +1662015377379138304 +1662015377424139264 +1662015377466140160 +1662015377514141184 +1662015377556142080 +1662015377604143104 +1662015377649144064 +1662015377694145024 +1662015377739145984 +1662015377781146880 +1662015377823147776 +1662015377868148736 +1662015377907149568 +1662015377949150464 +1662015377991151360 +1662015378036152320 +1662015378081153280 +1662015378120154112 +1662015378165155072 +1662015378207155968 +1662015378249156864 +1662015378285157632 +1662015378327158528 +1662015378366159360 +1662015378408160256 +1662015378456161280 +1662015378495162112 +1662015378546163200 +1662015378591164160 +1662015378636165120 +1662015378684166144 +1662015378726167040 +1662015378768167936 +1662015378813168896 +1662015378855169792 +1662015378894170624 +1662015378936171520 +1662015378978172416 +1662015379023173376 +1662015379065174272 +1662015379107175168 +1662015379149176064 +1662015379194177024 +1662015379236177920 +1662015379278178816 +1662015379323179776 +1662015379365180672 +1662015379419181824 +1662015379461182720 +1662015379500183552 +1662015379542184448 +1662015379584185344 +1662015379629186304 +1662015379680187392 +1662015379722188288 +1662015379767189248 +1662015379812190208 +1662015379854191104 +1662015379896192000 +1662015379941192960 +1662015379989193984 +1662015380037195008 +1662015380082195968 +1662015380130196992 +1662015380175197952 +1662015380220198912 +1662015380265199872 +1662015380313200896 +1662015380355201792 +1662015380397202688 +1662015380439203584 +1662015380481204480 +1662015380526205440 +1662015380568206336 +1662015380616207360 +1662015380658208256 +1662015380706209280 +1662015380760210432 +1662015380805211392 +1662015380853212416 +1662015380895213312 +1662015380937214208 +1662015380982215168 +1662015381027216128 +1662015381078217216 +1662015381120218112 +1662015381162219008 +1662015381204219904 +1662015381246220800 +1662015381288221696 +1662015381333222656 +1662015381378223616 +1662015381423224576 +1662015381468225536 +1662015381513226496 +1662015381558227456 +1662015381600228352 +1662015381639229184 +1662015381681230080 +1662015381723230976 +1662015381768231936 +1662015381816232960 +1662015381861233920 +1662015381903234816 +1662015381945235712 +1662015381990236672 +1662015382038237696 +1662015382086238720 +1662015382134239744 +1662015382182240768 +1662015382230241792 +1662015382278242816 +1662015382323243776 +1662015382365244672 +1662015382407245568 +1662015382458246656 +1662015382500247552 +1662015382545248512 +1662015382581249280 +1662015382623250176 +1662015382662251008 +1662015382713252096 +1662015382755252992 +1662015382797253888 +1662015382839254784 +1662015382878255616 +1662015382923256576 +1662015382965257472 +1662015383007258368 +1662015383052259328 +1662015383097260288 +1662015383145261312 +1662015383193262336 +1662015383238263296 +1662015383277264128 +1662015383319265024 +1662015383364265984 +1662015383409266944 +1662015383454267904 +1662015383496268800 +1662015383541269760 +1662015383583270656 +1662015383631271680 +1662015383676272640 +1662015383718273536 +1662015383763274496 +1662015383808275456 +1662015383850276352 +1662015383892277248 +1662015383934278144 +1662015383985279232 +1662015384024280064 +1662015384066280960 +1662015384108281856 +1662015384153282816 +1662015384198283776 +1662015384246284800 +1662015384288285696 +1662015384336286720 +1662015384381287680 +1662015384423288576 +1662015384465289472 +1662015384507290368 +1662015384558291456 +1662015384603292416 +1662015384642293248 +1662015384687294208 +1662015384732295168 +1662015384789296384 +1662015384831297280 +1662015384879298304 +1662015384921299200 +1662015384963300096 +1662015385005300992 +1662015385047301888 +1662015385089302784 +1662015385131303680 +1662015385176304640 +1662015385218305536 +1662015385263306496 +1662015385305307392 +1662015385347308288 +1662015385392309248 +1662015385434310144 +1662015385476311040 +1662015385518311936 +1662015385563312896 +1662015385608313856 +1662015385653314816 +1662015385710316032 +1662015385755316992 +1662015385797317888 +1662015385839318784 +1662015385884319744 +1662015385929320704 +1662015385974321664 +1662015386022322688 +1662015386061323520 +1662015386103324416 +1662015386145325312 +1662015386187326208 +1662015386229327104 +1662015386274328064 +1662015386322329088 +1662015386370330112 +1662015386412331008 +1662015386457331968 +1662015386502332928 +1662015386547333888 +1662015386595334912 +1662015386637335808 +1662015386688336896 +1662015386733337856 +1662015386778338816 +1662015386820339712 +1662015386868340736 +1662015386916341760 +1662015386961342720 +1662015387003343616 +1662015387048344576 +1662015387093345536 +1662015387141346560 +1662015387186347520 +1662015387228348416 +1662015387282349568 +1662015387330350592 +1662015387366351360 +1662015387408352256 +1662015387447353088 +1662015387489353984 +1662015387534354944 +1662015387579355904 +1662015387627356928 +1662015387669357824 +1662015387714358784 +1662015387759359744 +1662015387804360704 +1662015387858361856 +1662015387900362752 +1662015387945363712 +1662015387987364608 +1662015388029365504 +1662015388071366400 +1662015388119367424 +1662015388164368384 +1662015388209369344 +1662015388251370240 +1662015388293371136 +1662015388332371968 +1662015388374372864 +1662015388419373824 +1662015388464374784 +1662015388506375680 +1662015388548376576 +1662015388593377536 +1662015388644378624 +1662015388689379584 +1662015388731380480 +1662015388776381440 +1662015388818382336 +1662015388860383232 +1662015388905384192 +1662015388944385024 +1662015388992386048 +1662015389040387072 +1662015389082387968 +1662015389124388864 +1662015389163389696 +1662015389205390592 +1662015389247391488 +1662015389295392512 +1662015389337393408 +1662015389382394368 +1662015389424395264 +1662015389466396160 +1662015389508397056 +1662015389556398080 +1662015389598398976 +1662015389643399936 +1662015389682400768 +1662015389724401664 +1662015389766402560 +1662015389814403584 +1662015389859404544 +1662015389904405504 +1662015389940406272 +1662015389979407104 +1662015390021408000 +1662015390072409088 +1662015390120410112 +1662015390162411008 +1662015390210412032 +1662015390255412992 +1662015390300413952 +1662015390342414848 +1662015390384415744 +1662015390429416704 +1662015390468417536 +1662015390510418432 +1662015390555419392 +1662015390597420288 +1662015390639421184 +1662015390684422144 +1662015390726423040 +1662015390771424000 +1662015390813424896 +1662015390855425792 +1662015390897426688 +1662015390936427520 +1662015390978428416 +1662015391020429312 +1662015391062430208 +1662015391104431104 +1662015391152432128 +1662015391194433024 +1662015391236433920 +1662015391278434816 +1662015391326435840 +1662015391371436800 +1662015391416437760 +1662015391461438720 +1662015391503439616 +1662015391545440512 +1662015391587441408 +1662015391632442368 +1662015391677443328 +1662015391722444288 +1662015391764445184 +1662015391806446080 +1662015391848446976 +1662015391890447872 +1662015391932448768 +1662015391974449664 +1662015392019450624 +1662015392070451712 +1662015392112452608 +1662015392160453632 +1662015392202454528 +1662015392247455488 +1662015392289456384 +1662015392334457344 +1662015392379458304 +1662015392424459264 +1662015392469460224 +1662015392520461312 +1662015392562462208 +1662015392607463168 +1662015392652464128 +1662015392694465024 +1662015392739465984 +1662015392784466944 +1662015392829467904 +1662015392877468928 +1662015392916469760 +1662015392955470592 +1662015392997471488 +1662015393054472704 +1662015393102473728 +1662015393147474688 +1662015393192475648 +1662015393240476672 +1662015393282477568 +1662015393324478464 +1662015393372479488 +1662015393423480576 +1662015393468481536 +1662015393510482432 +1662015393552483328 +1662015393597484288 +1662015393642485248 +1662015393690486272 +1662015393732487168 +1662015393771488000 +1662015393819489024 +1662015393864489984 +1662015393906490880 +1662015393948491776 +1662015393993492736 +1662015394038493696 +1662015394089494784 +1662015394131495680 +1662015394173496576 +1662015394218497536 +1662015394260498432 +1662015394302499328 +1662015394347500288 +1662015394392501248 +1662015394434502144 +1662015394479503104 +1662015394521504000 +1662015394566504960 +1662015394608505856 +1662015394653506816 +1662015394698507776 +1662015394746508800 +1662015394788509696 +1662015394833510656 +1662015394878511616 +1662015394923512576 +1662015394965513472 +1662015395010514432 +1662015395061515520 +1662015395097516288 +1662015395139517184 +1662015395181518080 +1662015395223518976 +1662015395274520064 +1662015395316520960 +1662015395367522048 +1662015395409522944 +1662015395454523904 +1662015395499524864 +1662015395550525952 +1662015395589526784 +1662015395631527680 +1662015395679528704 +1662015395724529664 +1662015395766530560 +1662015395814531584 +1662015395856532480 +1662015395898533376 +1662015395943534336 +1662015395991535360 +1662015396036536320 +1662015396078537216 +1662015396126538240 +1662015396168539136 +1662015396216540160 +1662015396264541184 +1662015396309542144 +1662015396357543168 +1662015396399544064 +1662015396447545088 +1662015396492546048 +1662015396540547072 +1662015396582547968 +1662015396627548928 +1662015396675549952 +1662015396720550912 +1662015396765551872 +1662015396807552768 +1662015396852553728 +1662015396894554624 +1662015396939555584 +1662015396987556608 +1662015397020557312 +1662015397068558336 +1662015397116559360 +1662015397161560320 +1662015397203561216 +1662015397248562176 +1662015397287563008 +1662015397332563968 +1662015397377564928 +1662015397416565760 +1662015397458566656 +1662015397503567616 +1662015397545568512 +1662015397584569344 +1662015397632570368 +1662015397677571328 +1662015397722572288 +1662015397767573248 +1662015397815574272 +1662015397860575232 +1662015397905576192 +1662015397953577216 +1662015397995578112 +1662015398040579072 +1662015398085580032 +1662015398130580992 +1662015398172581888 +1662015398217582848 +1662015398259583744 +1662015398301584640 +1662015398349585664 +1662015398391586560 +1662015398436587520 +1662015398481588480 +1662015398523589376 +1662015398568590336 +1662015398613591296 +1662015398655592192 +1662015398700593152 +1662015398742594048 +1662015398793595136 +1662015398835596032 +1662015398883597056 +1662015398928598016 +1662015398967598848 +1662015399009599744 +1662015399054600704 +1662015399102601728 +1662015399150602752 +1662015399198603776 +1662015399240604672 +1662015399282605568 +1662015399330606592 +1662015399375607552 +1662015399423608576 +1662015399465609472 +1662015399507610368 +1662015399552611328 +1662015399591612160 +1662015399636613120 +1662015399678614016 +1662015399723614976 +1662015399765615872 +1662015399819617024 +1662015399867618048 +1662015399921619200 +1662015399960620032 +1662015400005620992 +1662015400050621952 +1662015400098622976 +1662015400140623872 +1662015400182624768 +1662015400227625728 +1662015400272626688 +1662015400311627520 +1662015400353628416 +1662015400404629504 +1662015400446630400 +1662015400488631296 +1662015400530632192 +1662015400575633152 +1662015400617634048 +1662015400665635072 +1662015400710636032 +1662015400752636928 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track2.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track2.txt new file mode 100644 index 0000000000..c35350d63a --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track2.txt @@ -0,0 +1,2537 @@ +1662122091767260928 +1662122091809261824 +1662122091851262720 +1662122091893263616 +1662122091935264512 +1662122091980265472 +1662122092022266368 +1662122092064267264 +1662122092106268160 +1662122092148269056 +1662122092193270016 +1662122092232270848 +1662122092280271872 +1662122092322272768 +1662122092364273664 +1662122092412274688 +1662122092454275584 +1662122092493276416 +1662122092535277312 +1662122092580278272 +1662122092625279232 +1662122092667280128 +1662122092709281024 +1662122092751281920 +1662122092796282880 +1662122092847283968 +1662122092889284864 +1662122092931285760 +1662122092970286592 +1662122093015287552 +1662122093060288512 +1662122093105289472 +1662122093153290496 +1662122093201291520 +1662122093240292352 +1662122093282293248 +1662122093324294144 +1662122093366295040 +1662122093408295936 +1662122093453296896 +1662122093501297920 +1662122093543298816 +1662122093591299840 +1662122093633300736 +1662122093675301632 +1662122093723302656 +1662122093768303616 +1662122093810304512 +1662122093855305472 +1662122093894306304 +1662122093939307264 +1662122093981308160 +1662122094023309056 +1662122094065309952 +1662122094110310912 +1662122094146311680 +1662122094191312640 +1662122094227313408 +1662122094275314432 +1662122094317315328 +1662122094359316224 +1662122094395316992 +1662122094437317888 +1662122094482318848 +1662122094524319744 +1662122094566320640 +1662122094611321600 +1662122094653322496 +1662122094695323392 +1662122094740324352 +1662122094782325248 +1662122094824326144 +1662122094872327168 +1662122094917328128 +1662122094965329152 +1662122095007330048 +1662122095052331008 +1662122095094331904 +1662122095139332864 +1662122095181333760 +1662122095220334592 +1662122095265335552 +1662122095316336640 +1662122095358337536 +1662122095406338560 +1662122095454339584 +1662122095496340480 +1662122095541341440 +1662122095586342400 +1662122095625343232 +1662122095667344128 +1662122095709345024 +1662122095751345920 +1662122095793346816 +1662122095835347712 +1662122095874348544 +1662122095916349440 +1662122095958350336 +1662122096000351232 +1662122096045352192 +1662122096084353024 +1662122096120353792 +1662122096162354688 +1662122096204355584 +1662122096243356416 +1662122096279357184 +1662122096327358208 +1662122096375359232 +1662122096417360128 +1662122096453360896 +1662122096495361792 +1662122096540362752 +1662122096585363712 +1662122096627364608 +1662122096669365504 +1662122096717366528 +1662122096759367424 +1662122096801368320 +1662122096843369216 +1662122096885370112 +1662122096924370944 +1662122096966371840 +1662122097005372672 +1662122097047373568 +1662122097089374464 +1662122097134375424 +1662122097179376384 +1662122097221377280 +1662122097263378176 +1662122097305379072 +1662122097347379968 +1662122097395380992 +1662122097437381888 +1662122097479382784 +1662122097521383680 +1662122097563384576 +1662122097605385472 +1662122097656386560 +1662122097704387584 +1662122097743388416 +1662122097785389312 +1662122097836390400 +1662122097881391360 +1662122097923392256 +1662122097968393216 +1662122098010394112 +1662122098052395008 +1662122098094395904 +1662122098136396800 +1662122098178397696 +1662122098226398720 +1662122098271399680 +1662122098316400640 +1662122098358401536 +1662122098397402368 +1662122098439403264 +1662122098481404160 +1662122098529405184 +1662122098577406208 +1662122098628407296 +1662122098670408192 +1662122098712409088 +1662122098757410048 +1662122098796410880 +1662122098841411840 +1662122098883412736 +1662122098922413568 +1662122098970414592 +1662122099012415488 +1662122099054416384 +1662122099096417280 +1662122099141418240 +1662122099183419136 +1662122099222419968 +1662122099267420928 +1662122099315421952 +1662122099360422912 +1662122099405423872 +1662122099450424832 +1662122099498425856 +1662122099537426688 +1662122099585427712 +1662122099624428544 +1662122099669429504 +1662122099711430400 +1662122099753431296 +1662122099798432256 +1662122099843433216 +1662122099888434176 +1662122099933435136 +1662122099969435904 +1662122100014436864 +1662122100056437760 +1662122100101438720 +1662122100146439680 +1662122100197440768 +1662122100236441600 +1662122100281442560 +1662122100323443456 +1662122100365444352 +1662122100410445312 +1662122100449446144 +1662122100494447104 +1662122100536448000 +1662122100578448896 +1662122100617449728 +1662122100659450624 +1662122100701451520 +1662122100743452416 +1662122100785453312 +1662122100824454144 +1662122100866455040 +1662122100908455936 +1662122100950456832 +1662122100992457728 +1662122101037458688 +1662122101079459584 +1662122101124460544 +1662122101160461312 +1662122101205462272 +1662122101244463104 +1662122101298464256 +1662122101340465152 +1662122101379465984 +1662122101421466880 +1662122101466467840 +1662122101514468864 +1662122101556469760 +1662122101601470720 +1662122101649471744 +1662122101694472704 +1662122101733473536 +1662122101784474624 +1662122101826475520 +1662122101865476352 +1662122101904477184 +1662122101949478144 +1662122101997479168 +1662122102042480128 +1662122102090481152 +1662122102129481984 +1662122102171482880 +1662122102213483776 +1662122102255484672 +1662122102297485568 +1662122102342486528 +1662122102384487424 +1662122102423488256 +1662122102465489152 +1662122102507490048 +1662122102546490880 +1662122102588491776 +1662122102627492608 +1662122102663493376 +1662122102705494272 +1662122102747495168 +1662122102789496064 +1662122102834497024 +1662122102876497920 +1662122102918498816 +1662122102960499712 +1662122103005500672 +1662122103044501504 +1662122103089502464 +1662122103131503360 +1662122103176504320 +1662122103221505280 +1662122103263506176 +1662122103308507136 +1662122103350508032 +1662122103392508928 +1662122103437509888 +1662122103479510784 +1662122103515511552 +1662122103557512448 +1662122103593513216 +1662122103635514112 +1662122103680515072 +1662122103725516032 +1662122103767516928 +1662122103809517824 +1662122103845518592 +1662122103887519488 +1662122103932520448 +1662122103974521344 +1662122104019522304 +1662122104061523200 +1662122104106524160 +1662122104148525056 +1662122104184525824 +1662122104223526656 +1662122104268527616 +1662122104310528512 +1662122104355529472 +1662122104397530368 +1662122104439531264 +1662122104478532096 +1662122104520532992 +1662122104562533888 +1662122104604534784 +1662122104646535680 +1662122104688536576 +1662122104730537472 +1662122104772538368 +1662122104814539264 +1662122104859540224 +1662122104904541184 +1662122104949542144 +1662122104988542976 +1662122105027543808 +1662122105072544768 +1662122105114545664 +1662122105159546624 +1662122105201547520 +1662122105243548416 +1662122105285549312 +1662122105327550208 +1662122105366551040 +1662122105408551936 +1662122105450552832 +1662122105489553664 +1662122105531554560 +1662122105573555456 +1662122105615556352 +1662122105657557248 +1662122105699558144 +1662122105747559168 +1662122105789560064 +1662122105834561024 +1662122105882562048 +1662122105924562944 +1662122105969563904 +1662122106008564736 +1662122106053565696 +1662122106092566528 +1662122106134567424 +1662122106173568256 +1662122106215569152 +1662122106251569920 +1662122106290570752 +1662122106326571520 +1662122106374572544 +1662122106416573440 +1662122106461574400 +1662122106506575360 +1662122106548576256 +1662122106584577024 +1662122106626577920 +1662122106665578752 +1662122106707579648 +1662122106752580608 +1662122106794581504 +1662122106836582400 +1662122106881583360 +1662122106923584256 +1662122106965585152 +1662122107007586048 +1662122107055587072 +1662122107097587968 +1662122107136588800 +1662122107172589568 +1662122107214590464 +1662122107259591424 +1662122107307592448 +1662122107349593344 +1662122107394594304 +1662122107433595136 +1662122107472595968 +1662122107517596928 +1662122107556597760 +1662122107598598656 +1662122107643599616 +1662122107682600448 +1662122107724601344 +1662122107769602304 +1662122107814603264 +1662122107862604288 +1662122107904605184 +1662122107949606144 +1662122107991607040 +1662122108030607872 +1662122108075608832 +1662122108117609728 +1662122108159610624 +1662122108207611648 +1662122108249612544 +1662122108291613440 +1662122108339614464 +1662122108387615488 +1662122108429616384 +1662122108471617280 +1662122108516618240 +1662122108558619136 +1662122108600620032 +1662122108642620928 +1662122108687621888 +1662122108729622784 +1662122108774623744 +1662122108816624640 +1662122108861625600 +1662122108909626624 +1662122108951627520 +1662122108990628352 +1662122109035629312 +1662122109083630336 +1662122109125631232 +1662122109164632064 +1662122109206632960 +1662122109245633792 +1662122109287634688 +1662122109332635648 +1662122109368636416 +1662122109410637312 +1662122109452638208 +1662122109491639040 +1662122109539640064 +1662122109587641088 +1662122109635642112 +1662122109674642944 +1662122109716643840 +1662122109761644800 +1662122109803645696 +1662122109845646592 +1662122109887647488 +1662122109929648384 +1662122109968649216 +1662122110010650112 +1662122110055651072 +1662122110097651968 +1662122110136652800 +1662122110178653696 +1662122110220654592 +1662122110265655552 +1662122110307656448 +1662122110352657408 +1662122110394658304 +1662122110436659200 +1662122110481660160 +1662122110526661120 +1662122110571662080 +1662122110613662976 +1662122110661664000 +1662122110703664896 +1662122110748665856 +1662122110793666816 +1662122110835667712 +1662122110880668672 +1662122110919669504 +1662122110970670592 +1662122111012671488 +1662122111054672384 +1662122111093673216 +1662122111138674176 +1662122111186675200 +1662122111225676032 +1662122111267676928 +1662122111309677824 +1662122111351678720 +1662122111393679616 +1662122111435680512 +1662122111477681408 +1662122111522682368 +1662122111570683392 +1662122111615684352 +1662122111657685248 +1662122111702686208 +1662122111747687168 +1662122111789688064 +1662122111834689024 +1662122111876689920 +1662122111918690816 +1662122111963691776 +1662122112005692672 +1662122112047693568 +1662122112089694464 +1662122112134695424 +1662122112182696448 +1662122112224697344 +1662122112266698240 +1662122112308699136 +1662122112353700096 +1662122112395700992 +1662122112434701824 +1662122112476702720 +1662122112521703680 +1662122112572704768 +1662122112617705728 +1662122112656706560 +1662122112698707456 +1662122112746708480 +1662122112788709376 +1662122112833710336 +1662122112875711232 +1662122112914712064 +1662122112953712896 +1662122112998713856 +1662122113037714688 +1662122113079715584 +1662122113118716416 +1662122113154717184 +1662122113196718080 +1662122113235718912 +1662122113277719808 +1662122113319720704 +1662122113355721472 +1662122113400722432 +1662122113448723456 +1662122113487724288 +1662122113529725184 +1662122113571726080 +1662122113613726976 +1662122113655727872 +1662122113700728832 +1662122113742729728 +1662122113784730624 +1662122113826731520 +1662122113871732480 +1662122113913733376 +1662122113958734336 +1662122114006735360 +1662122114048736256 +1662122114090737152 +1662122114132738048 +1662122114177739008 +1662122114222739968 +1662122114264740864 +1662122114309741824 +1662122114354742784 +1662122114396743680 +1662122114438744576 +1662122114489745664 +1662122114534746624 +1662122114579747584 +1662122114627748608 +1662122114669749504 +1662122114708750336 +1662122114750751232 +1662122114792752128 +1662122114837753088 +1662122114882754048 +1662122114921754880 +1662122114966755840 +1662122115008756736 +1662122115059757824 +1662122115110758912 +1662122115149759744 +1662122115194760704 +1662122115236761600 +1662122115278762496 +1662122115320763392 +1662122115365764352 +1662122115404765184 +1662122115446766080 +1662122115491767040 +1662122115533767936 +1662122115575768832 +1662122115620769792 +1662122115662770688 +1662122115707771648 +1662122115749772544 +1662122115788773376 +1662122115830774272 +1662122115875775232 +1662122115917776128 +1662122115959777024 +1662122115998777856 +1662122116043778816 +1662122116088779776 +1662122116136780800 +1662122116175781632 +1662122116217782528 +1662122116265783552 +1662122116307784448 +1662122116352785408 +1662122116394786304 +1662122116430787072 +1662122116475788032 +1662122116517788928 +1662122116562789888 +1662122116604790784 +1662122116643791616 +1662122116685792512 +1662122116727793408 +1662122116769794304 +1662122116811795200 +1662122116856796160 +1662122116901797120 +1662122116943798016 +1662122116985798912 +1662122117033799936 +1662122117075800832 +1662122117114801664 +1662122117153802496 +1662122117192803328 +1662122117240804352 +1662122117282805248 +1662122117324806144 +1662122117363806976 +1662122117408807936 +1662122117450808832 +1662122117495809792 +1662122117540810752 +1662122117582811648 +1662122117627812608 +1662122117669813504 +1662122117711814400 +1662122117759815424 +1662122117798816256 +1662122117846817280 +1662122117888818176 +1662122117933819136 +1662122117978820096 +1662122118023821056 +1662122118068822016 +1662122118113822976 +1662122118161824000 +1662122118206824960 +1662122118248825856 +1662122118287826688 +1662122118332827648 +1662122118374828544 +1662122118416829440 +1662122118461830400 +1662122118503831296 +1662122118548832256 +1662122118593833216 +1662122118638834176 +1662122118680835072 +1662122118722835968 +1662122118764836864 +1662122118806837760 +1662122118848838656 +1662122118890839552 +1662122118935840512 +1662122118977841408 +1662122119019842304 +1662122119061843200 +1662122119100844032 +1662122119145844992 +1662122119187845888 +1662122119226846720 +1662122119271847680 +1662122119319848704 +1662122119364849664 +1662122119403850496 +1662122119442851328 +1662122119484852224 +1662122119526853120 +1662122119571854080 +1662122119613854976 +1662122119652855808 +1662122119697856768 +1662122119739857664 +1662122119778858496 +1662122119823859456 +1662122119874860544 +1662122119922861568 +1662122119964862464 +1662122120009863424 +1662122120054864384 +1662122120096865280 +1662122120138866176 +1662122120180867072 +1662122120222867968 +1662122120270868992 +1662122120315869952 +1662122120360870912 +1662122120405871872 +1662122120450872832 +1662122120486873600 +1662122120525874432 +1662122120567875328 +1662122120609876224 +1662122120648877056 +1662122120690877952 +1662122120732878848 +1662122120777879808 +1662122120819880704 +1662122120858881536 +1662122120903882496 +1662122120948883456 +1662122120987884288 +1662122121023885056 +1662122121068886016 +1662122121110886912 +1662122121152887808 +1662122121194888704 +1662122121239889664 +1662122121281890560 +1662122121320891392 +1662122121365892352 +1662122121407893248 +1662122121449894144 +1662122121491895040 +1662122121536896000 +1662122121581896960 +1662122121626897920 +1662122121668898816 +1662122121710899712 +1662122121752900608 +1662122121797901568 +1662122121836902400 +1662122121878903296 +1662122121923904256 +1662122121968905216 +1662122122007906048 +1662122122049906944 +1662122122091907840 +1662122122136908800 +1662122122178909696 +1662122122223910656 +1662122122265911552 +1662122122307912448 +1662122122349913344 +1662122122394914304 +1662122122436915200 +1662122122481916160 +1662122122520916992 +1662122122568918016 +1662122122616919040 +1662122122661920000 +1662122122703920896 +1662122122745921792 +1662122122790922752 +1662122122832923648 +1662122122874924544 +1662122122913925376 +1662122122955926272 +1662122123000927232 +1662122123042928128 +1662122123087929088 +1662122123132930048 +1662122123171930880 +1662122123210931712 +1662122123249932544 +1662122123288933376 +1662122123330934272 +1662122123372935168 +1662122123414936064 +1662122123456936960 +1662122123498937856 +1662122123540938752 +1662122123579939584 +1662122123621940480 +1662122123663941376 +1662122123708942336 +1662122123753943296 +1662122123795944192 +1662122123837945088 +1662122123879945984 +1662122123918946816 +1662122123960947712 +1662122124005948672 +1662122124047949568 +1662122124092950528 +1662122124134951424 +1662122124179952384 +1662122124224953344 +1662122124266954240 +1662122124311955200 +1662122124359956224 +1662122124398957056 +1662122124440957952 +1662122124482958848 +1662122124530959872 +1662122124572960768 +1662122124617961728 +1662122124659962624 +1662122124701963520 +1662122124743964416 +1662122124788965376 +1662122124833966336 +1662122124878967296 +1662122124923968256 +1662122124968969216 +1662122125013970176 +1662122125058971136 +1662122125097971968 +1662122125139972864 +1662122125181973760 +1662122125226974720 +1662122125271975680 +1662122125310976512 +1662122125361977600 +1662122125400978432 +1662122125445979392 +1662122125493980416 +1662122125535981312 +1662122125583982336 +1662122125625983232 +1662122125670984192 +1662122125709985024 +1662122125751985920 +1662122125793986816 +1662122125835987712 +1662122125874988544 +1662122125916989440 +1662122125961990400 +1662122126003991296 +1662122126045992192 +1662122126087993088 +1662122126129993984 +1662122126171994880 +1662122126219995904 +1662122126264996864 +1662122126303997696 +1662122126351998720 +1662122126393999616 +1662122126436000512 +1662122126478001408 +1662122126523002368 +1662122126565003264 +1662122126601004032 +1662122126640004864 +1662122126685005824 +1662122126727006720 +1662122126769007616 +1662122126808008448 +1662122126850009344 +1662122126895010304 +1662122126940011264 +1662122126985012224 +1662122127021012992 +1662122127063013888 +1662122127105014784 +1662122127144015616 +1662122127189016576 +1662122127231017472 +1662122127273018368 +1662122127315019264 +1662122127363020288 +1662122127408021248 +1662122127462022400 +1662122127507023360 +1662122127549024256 +1662122127594025216 +1662122127639026176 +1662122127681027072 +1662122127729028096 +1662122127783029248 +1662122127828030208 +1662122127867031040 +1662122127909031936 +1662122127954032896 +1662122127999033856 +1662122128044034816 +1662122128086035712 +1662122128125036544 +1662122128170037504 +1662122128212038400 +1662122128257039360 +1662122128302040320 +1662122128347041280 +1662122128389042176 +1662122128440043264 +1662122128479044096 +1662122128518044928 +1662122128557045760 +1662122128599046656 +1662122128644047616 +1662122128689048576 +1662122128737049600 +1662122128776050432 +1662122128824051456 +1662122128866052352 +1662122128908053248 +1662122128950054144 +1662122128992055040 +1662122129034055936 +1662122129073056768 +1662122129115057664 +1662122129160058624 +1662122129208059648 +1662122129247060480 +1662122129295061504 +1662122129340062464 +1662122129382063360 +1662122129427064320 +1662122129472065280 +1662122129517066240 +1662122129559067136 +1662122129601068032 +1662122129640068864 +1662122129679069696 +1662122129727070720 +1662122129766071552 +1662122129808072448 +1662122129844073216 +1662122129889074176 +1662122129934075136 +1662122129976076032 +1662122130021076992 +1662122130066077952 +1662122130114078976 +1662122130159079936 +1662122130198080768 +1662122130240081664 +1662122130282082560 +1662122130330083584 +1662122130369084416 +1662122130414085376 +1662122130456086272 +1662122130498087168 +1662122130540088064 +1662122130582088960 +1662122130624089856 +1662122130669090816 +1662122130711091712 +1662122130753092608 +1662122130798093568 +1662122130840094464 +1662122130885095424 +1662122130927096320 +1662122130969097216 +1662122131011098112 +1662122131056099072 +1662122131095099904 +1662122131137100800 +1662122131182101760 +1662122131227102720 +1662122131263103488 +1662122131305104384 +1662122131350105344 +1662122131395106304 +1662122131437107200 +1662122131482108160 +1662122131527109120 +1662122131566109952 +1662122131605110784 +1662122131647111680 +1662122131689112576 +1662122131737113600 +1662122131776114432 +1662122131821115392 +1662122131863116288 +1662122131905117184 +1662122131947118080 +1662122131989118976 +1662122132028119808 +1662122132073120768 +1662122132115121664 +1662122132154122496 +1662122132205123584 +1662122132247124480 +1662122132286125312 +1662122132325126144 +1662122132370127104 +1662122132409127936 +1662122132454128896 +1662122132502129920 +1662122132541130752 +1662122132583131648 +1662122132628132608 +1662122132670133504 +1662122132712134400 +1662122132754135296 +1662122132799136256 +1662122132838137088 +1662122132877137920 +1662122132919138816 +1662122132964139776 +1662122133006140672 +1662122133051141632 +1662122133093142528 +1662122133135143424 +1662122133180144384 +1662122133225145344 +1662122133267146240 +1662122133309147136 +1662122133351148032 +1662122133393148928 +1662122133438149888 +1662122133480150784 +1662122133525151744 +1662122133567152640 +1662122133609153536 +1662122133654154496 +1662122133696155392 +1662122133744156416 +1662122133786157312 +1662122133831158272 +1662122133876159232 +1662122133921160192 +1662122133966161152 +1662122134011162112 +1662122134059163136 +1662122134101164032 +1662122134143164928 +1662122134188165888 +1662122134233166848 +1662122134281167872 +1662122134326168832 +1662122134368169728 +1662122134410170624 +1662122134452171520 +1662122134500172544 +1662122134539173376 +1662122134584174336 +1662122134626175232 +1662122134668176128 +1662122134710177024 +1662122134755177984 +1662122134797178880 +1662122134839179776 +1662122134887180800 +1662122134932181760 +1662122134971182592 +1662122135013183488 +1662122135052184320 +1662122135094185216 +1662122135133186048 +1662122135175186944 +1662122135217187840 +1662122135262188800 +1662122135310189824 +1662122135355190784 +1662122135400191744 +1662122135442192640 +1662122135487193600 +1662122135526194432 +1662122135571195392 +1662122135613196288 +1662122135652197120 +1662122135697198080 +1662122135736198912 +1662122135781199872 +1662122135823200768 +1662122135868201728 +1662122135907202560 +1662122135952203520 +1662122135994204416 +1662122136039205376 +1662122136081206272 +1662122136123207168 +1662122136168208128 +1662122136207208960 +1662122136252209920 +1662122136297210880 +1662122136342211840 +1662122136381212672 +1662122136426213632 +1662122136471214592 +1662122136516215552 +1662122136561216512 +1662122136600217344 +1662122136642218240 +1662122136684219136 +1662122136726220032 +1662122136771220992 +1662122136813221888 +1662122136861222912 +1662122136903223808 +1662122136951224832 +1662122136993225728 +1662122137035226624 +1662122137083227648 +1662122137125228544 +1662122137167229440 +1662122137209230336 +1662122137254231296 +1662122137290232064 +1662122137335233024 +1662122137371233792 +1662122137416234752 +1662122137461235712 +1662122137503236608 +1662122137551237632 +1662122137596238592 +1662122137641239552 +1662122137683240448 +1662122137728241408 +1662122137770242304 +1662122137815243264 +1662122137857244160 +1662122137902245120 +1662122137950246144 +1662122137998247168 +1662122138037248000 +1662122138082248960 +1662122138127249920 +1662122138169250816 +1662122138214251776 +1662122138265252864 +1662122138307253760 +1662122138349254656 +1662122138391255552 +1662122138433256448 +1662122138478257408 +1662122138520258304 +1662122138565259264 +1662122138610260224 +1662122138652261120 +1662122138688261888 +1662122138730262784 +1662122138772263680 +1662122138817264640 +1662122138862265600 +1662122138901266432 +1662122138940267264 +1662122138991268352 +1662122139030269184 +1662122139072270080 +1662122139117271040 +1662122139159271936 +1662122139201272832 +1662122139240273664 +1662122139282274560 +1662122139327275520 +1662122139369276416 +1662122139411277312 +1662122139450278144 +1662122139492279040 +1662122139534279936 +1662122139579280896 +1662122139621281792 +1662122139660282624 +1662122139702283520 +1662122139747284480 +1662122139792285440 +1662122139837286400 +1662122139879287296 +1662122139921288192 +1662122139963289088 +1662122140002289920 +1662122140044290816 +1662122140089291776 +1662122140128292608 +1662122140170293504 +1662122140209294336 +1662122140251295232 +1662122140296296192 +1662122140338297088 +1662122140383298048 +1662122140428299008 +1662122140470299904 +1662122140512300800 +1662122140560301824 +1662122140611302912 +1662122140659303936 +1662122140704304896 +1662122140746305792 +1662122140791306752 +1662122140833307648 +1662122140872308480 +1662122140914309376 +1662122140959310336 +1662122141004311296 +1662122141049312256 +1662122141094313216 +1662122141136314112 +1662122141178315008 +1662122141223315968 +1662122141268316928 +1662122141313317888 +1662122141352318720 +1662122141394319616 +1662122141436320512 +1662122141478321408 +1662122141523322368 +1662122141565323264 +1662122141610324224 +1662122141658325248 +1662122141706326272 +1662122141742327040 +1662122141790328064 +1662122141832328960 +1662122141871329792 +1662122141916330752 +1662122141961331712 +1662122142006332672 +1662122142045333504 +1662122142087334400 +1662122142129335296 +1662122142174336256 +1662122142216337152 +1662122142261338112 +1662122142303339008 +1662122142351340032 +1662122142393340928 +1662122142435341824 +1662122142480342784 +1662122142522343680 +1662122142561344512 +1662122142603345408 +1662122142648346368 +1662122142693347328 +1662122142735348224 +1662122142783349248 +1662122142825350144 +1662122142867351040 +1662122142915352064 +1662122142960353024 +1662122143002353920 +1662122143041354752 +1662122143086355712 +1662122143131356672 +1662122143173357568 +1662122143215358464 +1662122143260359424 +1662122143299360256 +1662122143341361152 +1662122143383362048 +1662122143425362944 +1662122143467363840 +1662122143512364800 +1662122143563365888 +1662122143605366784 +1662122143644367616 +1662122143683368448 +1662122143725369344 +1662122143767370240 +1662122143812371200 +1662122143854372096 +1662122143893372928 +1662122143935373824 +1662122143980374784 +1662122144022375680 +1662122144064376576 +1662122144112377600 +1662122144154378496 +1662122144199379456 +1662122144247380480 +1662122144289381376 +1662122144331382272 +1662122144373383168 +1662122144418384128 +1662122144454384896 +1662122144499385856 +1662122144541386752 +1662122144583387648 +1662122144628388608 +1662122144664389376 +1662122144709390336 +1662122144754391296 +1662122144793392128 +1662122144838393088 +1662122144883394048 +1662122144925394944 +1662122144973395968 +1662122145021396992 +1662122145063397888 +1662122145105398784 +1662122145144399616 +1662122145189400576 +1662122145231401472 +1662122145270402304 +1662122145315403264 +1662122145360404224 +1662122145408405248 +1662122145459406336 +1662122145504407296 +1662122145546408192 +1662122145588409088 +1662122145633410048 +1662122145678411008 +1662122145720411904 +1662122145765412864 +1662122145813413888 +1662122145855414784 +1662122145903415808 +1662122145948416768 +1662122145987417600 +1662122146032418560 +1662122146074419456 +1662122146122420480 +1662122146167421440 +1662122146212422400 +1662122146257423360 +1662122146302424320 +1662122146344425216 +1662122146389426176 +1662122146434427136 +1662122146476428032 +1662122146521428992 +1662122146563429888 +1662122146605430784 +1662122146647431680 +1662122146689432576 +1662122146734433536 +1662122146779434496 +1662122146821435392 +1662122146863436288 +1662122146908437248 +1662122146950438144 +1662122146992439040 +1662122147034439936 +1662122147070440704 +1662122147112441600 +1662122147163442688 +1662122147205443584 +1662122147244444416 +1662122147289445376 +1662122147331446272 +1662122147373447168 +1662122147415448064 +1662122147454448896 +1662122147496449792 +1662122147541450752 +1662122147583451648 +1662122147625452544 +1662122147670453504 +1662122147712454400 +1662122147754455296 +1662122147796456192 +1662122147838457088 +1662122147886458112 +1662122147931459072 +1662122147973459968 +1662122148018460928 +1662122148063461888 +1662122148105462784 +1662122148150463744 +1662122148192464640 +1662122148240465664 +1662122148279466496 +1662122148321467392 +1662122148366468352 +1662122148408469248 +1662122148447470080 +1662122148492471040 +1662122148534471936 +1662122148576472832 +1662122148621473792 +1662122148663474688 +1662122148705475584 +1662122148747476480 +1662122148792477440 +1662122148837478400 +1662122148882479360 +1662122148930480384 +1662122148972481280 +1662122149014482176 +1662122149059483136 +1662122149104484096 +1662122149146484992 +1662122149191485952 +1662122149233486848 +1662122149281487872 +1662122149323488768 +1662122149365489664 +1662122149407490560 +1662122149449491456 +1662122149491492352 +1662122149536493312 +1662122149575494144 +1662122149617495040 +1662122149659495936 +1662122149704496896 +1662122149746497792 +1662122149788498688 +1662122149830499584 +1662122149872500480 +1662122149914501376 +1662122149956502272 +1662122150001503232 +1662122150043504128 +1662122150088505088 +1662122150127505920 +1662122150169506816 +1662122150208507648 +1662122150250508544 +1662122150292509440 +1662122150334510336 +1662122150379511296 +1662122150421512192 +1662122150463513088 +1662122150511514112 +1662122150553515008 +1662122150592515840 +1662122150634516736 +1662122150679517696 +1662122150721518592 +1662122150763519488 +1662122150805520384 +1662122150847521280 +1662122150895522304 +1662122150940523264 +1662122150988524288 +1662122151033525248 +1662122151078526208 +1662122151123527168 +1662122151165528064 +1662122151210529024 +1662122151252529920 +1662122151297530880 +1662122151342531840 +1662122151384532736 +1662122151423533568 +1662122151465534464 +1662122151513535488 +1662122151561536512 +1662122151603537408 +1662122151648538368 +1662122151690539264 +1662122151735540224 +1662122151777541120 +1662122151819542016 +1662122151858542848 +1662122151903543808 +1662122151942544640 +1662122151987545600 +1662122152035546624 +1662122152077547520 +1662122152119548416 +1662122152164549376 +1662122152209550336 +1662122152254551296 +1662122152293552128 +1662122152335553024 +1662122152374553856 +1662122152416554752 +1662122152455555584 +1662122152497556480 +1662122152548557568 +1662122152587558400 +1662122152632559360 +1662122152674560256 +1662122152725561344 +1662122152770562304 +1662122152815563264 +1662122152857564160 +1662122152902565120 +1662122152941565952 +1662122152986566912 +1662122153028567808 +1662122153073568768 +1662122153115569664 +1662122153157570560 +1662122153199571456 +1662122153244572416 +1662122153286573312 +1662122153331574272 +1662122153376575232 +1662122153418576128 +1662122153463577088 +1662122153505577984 +1662122153550578944 +1662122153586579712 +1662122153637580800 +1662122153679581696 +1662122153721582592 +1662122153760583424 +1662122153805584384 +1662122153853585408 +1662122153901586432 +1662122153943587328 +1662122153982588160 +1662122154021588992 +1662122154063589888 +1662122154111590912 +1662122154153591808 +1662122154198592768 +1662122154243593728 +1662122154285594624 +1662122154324595456 +1662122154369596416 +1662122154411597312 +1662122154447598080 +1662122154489598976 +1662122154534599936 +1662122154579600896 +1662122154624601856 +1662122154666602752 +1662122154708603648 +1662122154750604544 +1662122154795605504 +1662122154837606400 +1662122154879607296 +1662122154924608256 +1662122154972609280 +1662122155014610176 +1662122155056611072 +1662122155095611904 +1662122155137612800 +1662122155179613696 +1662122155221614592 +1662122155260615424 +1662122155305616384 +1662122155347617280 +1662122155389618176 +1662122155434619136 +1662122155479620096 +1662122155524621056 +1662122155569622016 +1662122155611622912 +1662122155650623744 +1662122155695624704 +1662122155737625600 +1662122155779626496 +1662122155824627456 +1662122155866628352 +1662122155914629376 +1662122155953630208 +1662122155995631104 +1662122156043632128 +1662122156088633088 +1662122156130633984 +1662122156172634880 +1662122156214635776 +1662122156259636736 +1662122156307637760 +1662122156349638656 +1662122156397639680 +1662122156436640512 +1662122156481641472 +1662122156535642624 +1662122156574643456 +1662122156619644416 +1662122156667645440 +1662122156709646336 +1662122156751647232 +1662122156799648256 +1662122156841649152 +1662122156883650048 +1662122156928651008 +1662122156973651968 +1662122157015652864 +1662122157057653760 +1662122157102654720 +1662122157144655616 +1662122157183656448 +1662122157231657472 +1662122157273658368 +1662122157315659264 +1662122157363660288 +1662122157408661248 +1662122157450662144 +1662122157498663168 +1662122157537664000 +1662122157576664832 +1662122157618665728 +1662122157663666688 +1662122157705667584 +1662122157747668480 +1662122157789669376 +1662122157837670400 +1662122157882671360 +1662122157924672256 +1662122157966673152 +1662122158014674176 +1662122158062675200 +1662122158101676032 +1662122158149677056 +1662122158191677952 +1662122158236678912 +1662122158275679744 +1662122158317680640 +1662122158353681408 +1662122158395682304 +1662122158440683264 +1662122158482684160 +1662122158524685056 +1662122158572686080 +1662122158617687040 +1662122158662688000 +1662122158704688896 +1662122158746689792 +1662122158791690752 +1662122158830691584 +1662122158872692480 +1662122158911693312 +1662122158953694208 +1662122158998695168 +1662122159043696128 +1662122159085697024 +1662122159127697920 +1662122159163698688 +1662122159205699584 +1662122159247700480 +1662122159292701440 +1662122159337702400 +1662122159382703360 +1662122159421704192 +1662122159463705088 +1662122159502705920 +1662122159550706944 +1662122159589707776 +1662122159634708736 +1662122159673709568 +1662122159727710720 +1662122159766711552 +1662122159808712448 +1662122159850713344 +1662122159895714304 +1662122159940715264 +1662122159982716160 +1662122160021716992 +1662122160063717888 +1662122160108718848 +1662122160153719808 +1662122160201720832 +1662122160240721664 +1662122160282722560 +1662122160324723456 +1662122160366724352 +1662122160408725248 +1662122160456726272 +1662122160501727232 +1662122160546728192 +1662122160588729088 +1662122160636730112 +1662122160684731136 +1662122160732732160 +1662122160774733056 +1662122160816733952 +1662122160861734912 +1662122160903735808 +1662122160942736640 +1662122160984737536 +1662122161026738432 +1662122161068739328 +1662122161113740288 +1662122161158741248 +1662122161203742208 +1662122161245743104 +1662122161287744000 +1662122161332744960 +1662122161377745920 +1662122161419746816 +1662122161461747712 +1662122161503748608 +1662122161545749504 +1662122161593750528 +1662122161635751424 +1662122161680752384 +1662122161722753280 +1662122161764754176 +1662122161806755072 +1662122161845755904 +1662122161884756736 +1662122161926757632 +1662122161974758656 +1662122162016759552 +1662122162052760320 +1662122162091761152 +1662122162133762048 +1662122162178763008 +1662122162223763968 +1662122162265764864 +1662122162313765888 +1662122162355766784 +1662122162397767680 +1662122162439768576 +1662122162484769536 +1662122162523770368 +1662122162565771264 +1662122162607772160 +1662122162652773120 +1662122162694774016 +1662122162733774848 +1662122162778775808 +1662122162823776768 +1662122162868777728 +1662122162910778624 +1662122162949779456 +1662122162991780352 +1662122163039781376 +1662122163084782336 +1662122163126783232 +1662122163168784128 +1662122163213785088 +1662122163258786048 +1662122163297786880 +1662122163339787776 +1662122163378788608 +1662122163420789504 +1662122163456790272 +1662122163504791296 +1662122163549792256 +1662122163591793152 +1662122163633794048 +1662122163675794944 +1662122163717795840 +1662122163762796800 +1662122163804797696 +1662122163849798656 +1662122163888799488 +1662122163930800384 +1662122163972801280 +1662122164011802112 +1662122164050802944 +1662122164092803840 +1662122164134804736 +1662122164176805632 +1662122164221806592 +1662122164263807488 +1662122164305808384 +1662122164347809280 +1662122164392810240 +1662122164431811072 +1662122164470811904 +1662122164512812800 +1662122164548813568 +1662122164593814528 +1662122164635815424 +1662122164677816320 +1662122164719817216 +1662122164764818176 +1662122164812819200 +1662122164857820160 +1662122164893820928 +1662122164938821888 +1662122164980822784 +1662122165025823744 +1662122165070824704 +1662122165112825600 +1662122165157826560 +1662122165202827520 +1662122165244828416 +1662122165283829248 +1662122165325830144 +1662122165367831040 +1662122165412832000 +1662122165454832896 +1662122165499833856 +1662122165544834816 +1662122165586835712 +1662122165628836608 +1662122165670837504 +1662122165715838464 +1662122165760839424 +1662122165805840384 +1662122165853841408 +1662122165895842304 +1662122165934843136 +1662122165979844096 +1662122166021844992 +1662122166063845888 +1662122166105846784 +1662122166147847680 +1662122166189848576 +1662122166231849472 +1662122166276850432 +1662122166321851392 +1662122166360852224 +1662122166405853184 +1662122166450854144 +1662122166492855040 +1662122166531855872 +1662122166570856704 +1662122166615857664 +1662122166657858560 +1662122166702859520 +1662122166744860416 +1662122166786861312 +1662122166831862272 +1662122166876863232 +1662122166912864000 +1662122166951864832 +1662122166993865728 +1662122167035866624 +1662122167077867520 +1662122167116868352 +1662122167161869312 +1662122167206870272 +1662122167248871168 +1662122167296872192 +1662122167344873216 +1662122167386874112 +1662122167428875008 +1662122167470875904 +1662122167515876864 +1662122167560877824 +1662122167599878656 +1662122167638879488 +1662122167680880384 +1662122167722881280 +1662122167767882240 +1662122167815883264 +1662122167857884160 +1662122167899885056 +1662122167944886016 +1662122167989886976 +1662122168034887936 +1662122168079888896 +1662122168121889792 +1662122168163890688 +1662122168211891712 +1662122168253892608 +1662122168298893568 +1662122168331894272 +1662122168373895168 +1662122168415896064 +1662122168460897024 +1662122168502897920 +1662122168544898816 +1662122168586899712 +1662122168631900672 +1662122168670901504 +1662122168721902592 +1662122168763903488 +1662122168808904448 +1662122168850905344 +1662122168892906240 +1662122168931907072 +1662122168970907904 +1662122169012908800 +1662122169057909760 +1662122169096910592 +1662122169138911488 +1662122169180912384 +1662122169219913216 +1662122169264914176 +1662122169306915072 +1662122169354916096 +1662122169393916928 +1662122169438917888 +1662122169483918848 +1662122169522919680 +1662122169567920640 +1662122169609921536 +1662122169657922560 +1662122169702923520 +1662122169744924416 +1662122169786925312 +1662122169828926208 +1662122169870927104 +1662122169912928000 +1662122169957928960 +1662122169999929856 +1662122170041930752 +1662122170089931776 +1662122170128932608 +1662122170170933504 +1662122170209934336 +1662122170254935296 +1662122170296936192 +1662122170341937152 +1662122170389938176 +1662122170434939136 +1662122170476940032 +1662122170521940992 +1662122170563941888 +1662122170611942912 +1662122170659943936 +1662122170707944960 +1662122170749945856 +1662122170794946816 +1662122170839947776 +1662122170881948672 +1662122170920949504 +1662122170965950464 +1662122171016951552 +1662122171061952512 +1662122171106953472 +1662122171148954368 +1662122171193955328 +1662122171235956224 +1662122171280957184 +1662122171322958080 +1662122171364958976 +1662122171406959872 +1662122171451960832 +1662122171493961728 +1662122171541962752 +1662122171583963648 +1662122171625964544 +1662122171667965440 +1662122171715966464 +1662122171763967488 +1662122171805968384 +1662122171847969280 +1662122171892970240 +1662122171940971264 +1662122171982972160 +1662122172024973056 +1662122172066973952 +1662122172111974912 +1662122172153975808 +1662122172195976704 +1662122172237977600 +1662122172279978496 +1662122172318979328 +1662122172357980160 +1662122172402981120 +1662122172444982016 +1662122172489982976 +1662122172531983872 +1662122172576984832 +1662122172618985728 +1662122172663986688 +1662122172705987584 +1662122172750988544 +1662122172795989504 +1662122172837990400 +1662122172882991360 +1662122172924992256 +1662122172966993152 +1662122173011994112 +1662122173053995008 +1662122173095995904 +1662122173134996736 +1662122173185997824 +1662122173227998720 +1662122173275999744 +1662122173318000640 +1662122173363001600 +1662122173405002496 +1662122173447003392 +1662122173492004352 +1662122173537005312 +1662122173582006272 +1662122173627007232 +1662122173672008192 +1662122173717009152 +1662122173759010048 +1662122173804011008 +1662122173849011968 +1662122173894012928 +1662122173939013888 +1662122173981014784 +1662122174023015680 +1662122174065016576 +1662122174107017472 +1662122174149018368 +1662122174194019328 +1662122174236020224 +1662122174284021248 +1662122174329022208 +1662122174371023104 +1662122174416024064 +1662122174461025024 +1662122174503025920 +1662122174545026816 +1662122174593027840 +1662122174638028800 +1662122174680029696 +1662122174722030592 +1662122174764031488 +1662122174800032256 +1662122174845033216 +1662122174887034112 +1662122174926034944 +1662122174968035840 +1662122175007036672 +1662122175049037568 +1662122175091038464 +1662122175136039424 +1662122175175040256 +1662122175220041216 +1662122175262042112 +1662122175307043072 +1662122175352044032 +1662122175394044928 +1662122175442045952 +1662122175484046848 +1662122175535047936 +1662122175577048832 +1662122175625049856 +1662122175667050752 +1662122175712051712 +1662122175754052608 +1662122175799053568 +1662122175841054464 +1662122175883055360 +1662122175925056256 +1662122175973057280 +1662122176015058176 +1662122176057059072 +1662122176102060032 +1662122176144060928 +1662122176189061888 +1662122176231062784 +1662122176273063680 +1662122176312064512 +1662122176354065408 +1662122176396066304 +1662122176432067072 +1662122176474067968 +1662122176516068864 +1662122176558069760 +1662122176600070656 +1662122176636071424 +1662122176681072384 +1662122176726073344 +1662122176768074240 +1662122176816075264 +1662122176858076160 +1662122176900077056 +1662122176948078080 +1662122176990078976 +1662122177032079872 +1662122177077080832 +1662122177119081728 +1662122177161082624 +1662122177203083520 +1662122177245084416 +1662122177287085312 +1662122177332086272 +1662122177374087168 +1662122177416088064 +1662122177461089024 +1662122177506089984 +1662122177554091008 +1662122177596091904 +1662122177635092736 +1662122177680093696 +1662122177725094656 +1662122177770095616 +1662122177815096576 +1662122177860097536 +1662122177905098496 +1662122177947099392 +1662122177986100224 +1662122178028101120 +1662122178070102016 +1662122178112102912 +1662122178154103808 +1662122178202104832 +1662122178241105664 +1662122178280106496 +1662122178325107456 +1662122178370108416 +1662122178415109376 +1662122178454110208 +1662122178502111232 +1662122178547112192 +1662122178589113088 +1662122178634114048 +1662122178679115008 +1662122178724115968 +1662122178766116864 +1662122178814117888 +1662122178859118848 +1662122178910119936 +1662122178955120896 +1662122179003121920 +1662122179051122944 +1662122179096123904 +1662122179138124800 +1662122179180125696 +1662122179228126720 +1662122179267127552 +1662122179312128512 +1662122179363129600 +1662122179405130496 +1662122179450131456 +1662122179498132480 +1662122179540133376 +1662122179579134208 +1662122179624135168 +1662122179666136064 +1662122179711137024 +1662122179753137920 +1662122179798138880 +1662122179840139776 +1662122179885140736 +1662122179930141696 +1662122179972142592 +1662122180014143488 +1662122180056144384 +1662122180098145280 +1662122180137146112 +1662122180176146944 +1662122180227148032 +1662122180269148928 +1662122180314149888 +1662122180356150784 +1662122180395151616 +1662122180437152512 +1662122180479153408 +1662122180521154304 +1662122180566155264 +1662122180608156160 +1662122180653157120 +1662122180695158016 +1662122180734158848 +1662122180776159744 +1662122180821160704 +1662122180863161600 +1662122180908162560 +1662122180956163584 +1662122181001164544 +1662122181049165568 +1662122181091166464 +1662122181133167360 +1662122181172168192 +1662122181217169152 +1662122181262170112 +1662122181310171136 +1662122181355172096 +1662122181400173056 +1662122181442173952 +1662122181484174848 +1662122181526175744 +1662122181571176704 +1662122181613177600 +1662122181652178432 +1662122181694179328 +1662122181736180224 +1662122181772180992 +1662122181817181952 +1662122181862182912 +1662122181907183872 +1662122181949184768 +1662122181994185728 +1662122182042186752 +1662122182081187584 +1662122182117188352 +1662122182159189248 +1662122182198190080 +1662122182243191040 +1662122182285191936 +1662122182327192832 +1662122182369193728 +1662122182411194624 +1662122182456195584 +1662122182498196480 +1662122182540197376 +1662122182582198272 +1662122182624199168 +1662122182666200064 +1662122182708200960 +1662122182750201856 +1662122182795202816 +1662122182837203712 +1662122182882204672 +1662122182927205632 +1662122182969206528 +1662122183011207424 +1662122183059208448 +1662122183098209280 +1662122183137210112 +1662122183182211072 +1662122183224211968 +1662122183269212928 +1662122183308213760 +1662122183353214720 +1662122183395215616 +1662122183437216512 +1662122183476217344 +1662122183515218176 +1662122183557219072 +1662122183599219968 +1662122183641220864 +1662122183689221888 +1662122183731222784 +1662122183776223744 +1662122183821224704 +1662122183863225600 +1662122183908226560 +1662122183947227392 +1662122183989228288 +1662122184034229248 +1662122184076230144 +1662122184121231104 +1662122184163232000 +1662122184202232832 +1662122184247233792 +1662122184292234752 +1662122184334235648 +1662122184376236544 +1662122184421237504 +1662122184463238400 +1662122184508239360 +1662122184553240320 +1662122184595241216 +1662122184637242112 +1662122184679243008 +1662122184721243904 +1662122184763244800 +1662122184808245760 +1662122184850246656 +1662122184892247552 +1662122184934248448 +1662122184976249344 +1662122185015250176 +1662122185057251072 +1662122185099251968 +1662122185144252928 +1662122185192253952 +1662122185234254848 +1662122185276255744 +1662122185321256704 +1662122185366257664 +1662122185411258624 +1662122185450259456 +1662122185492260352 +1662122185531261184 +1662122185579262208 +1662122185627263232 +1662122185672264192 +1662122185717265152 +1662122185759266048 +1662122185807267072 +1662122185849267968 +1662122185888268800 +1662122185930269696 +1662122185966270464 +1662122186011271424 +1662122186053272320 +1662122186095273216 +1662122186137274112 +1662122186173274880 +1662122186218275840 +1662122186260276736 +1662122186299277568 +1662122186341278464 +1662122186383279360 +1662122186428280320 +1662122186473281280 +1662122186515282176 +1662122186563283200 +1662122186614284288 +1662122186656285184 +1662122186701286144 +1662122186746287104 +1662122186788288000 +1662122186833288960 +1662122186878289920 +1662122186917290752 +1662122186962291712 +1662122187004292608 +1662122187049293568 +1662122187088294400 +1662122187130295296 +1662122187175296256 +1662122187220297216 +1662122187262298112 +1662122187301298944 +1662122187343299840 +1662122187382300672 +1662122187424301568 +1662122187463302400 +1662122187505303296 +1662122187544304128 +1662122187586305024 +1662122187631305984 +1662122187673306880 +1662122187715307776 +1662122187757308672 +1662122187802309632 +1662122187844310528 +1662122187889311488 +1662122187934312448 +1662122187979313408 +1662122188024314368 +1662122188063315200 +1662122188111316224 +1662122188153317120 +1662122188201318144 +1662122188243319040 +1662122188294320128 +1662122188336321024 +1662122188378321920 +1662122188423322880 +1662122188465323776 +1662122188504324608 +1662122188549325568 +1662122188591326464 +1662122188636327424 +1662122188681328384 +1662122188723329280 +1662122188768330240 +1662122188813331200 +1662122188858332160 +1662122188906333184 +1662122188951334144 +1662122188996335104 +1662122189041336064 +1662122189086337024 +1662122189128337920 +1662122189173338880 +1662122189221339904 +1662122189263340800 +1662122189305341696 +1662122189350342656 +1662122189395343616 +1662122189431344384 +1662122189476345344 +1662122189518346240 +1662122189560347136 +1662122189605348096 +1662122189647348992 +1662122189692349952 +1662122189737350912 +1662122189782351872 +1662122189827352832 +1662122189872353792 +1662122189917354752 +1662122189962355712 +1662122190007356672 +1662122190052357632 +1662122190097358592 +1662122190139359488 +1662122190181360384 +1662122190220361216 +1662122190265362176 +1662122190307363072 +1662122190352364032 +1662122190397364992 +1662122190436365824 +1662122190475366656 +1662122190520367616 +1662122190565368576 +1662122190613369600 +1662122190661370624 +1662122190700371456 +1662122190742372352 +1662122190787373312 +1662122190829374208 +1662122190874375168 +1662122190916376064 +1662122190964377088 +1662122191006377984 +1662122191048378880 +1662122191099379968 +1662122191141380864 +1662122191186381824 +1662122191228382720 +1662122191276383744 +1662122191318384640 +1662122191360385536 +1662122191405386496 +1662122191444387328 +1662122191489388288 +1662122191531389184 +1662122191570390016 +1662122191609390848 +1662122191651391744 +1662122191690392576 +1662122191732393472 +1662122191774394368 +1662122191813395200 +1662122191855396096 +1662122191897396992 +1662122191936397824 +1662122191978398720 +1662122192020399616 +1662122192062400512 +1662122192101401344 +1662122192143402240 +1662122192185403136 +1662122192227404032 +1662122192269404928 +1662122192311405824 +1662122192350406656 +1662122192395407616 +1662122192437408512 +1662122192476409344 +1662122192518410240 +1662122192563411200 +1662122192608412160 +1662122192650413056 +1662122192695414016 +1662122192740414976 +1662122192782415872 +1662122192824416768 +1662122192869417728 +1662122192914418688 +1662122192956419584 +1662122193001420544 +1662122193040421376 +1662122193082422272 +1662122193127423232 +1662122193166424064 +1662122193208424960 +1662122193247425792 +1662122193289426688 +1662122193331427584 +1662122193370428416 +1662122193415429376 +1662122193454430208 +1662122193499431168 +1662122193541432064 +1662122193589433088 +1662122193631433984 +1662122193676434944 +1662122193721435904 +1662122193763436800 +1662122193808437760 +1662122193850438656 +1662122193889439488 +1662122193934440448 +1662122193976441344 +1662122194018442240 +1662122194057443072 +1662122194093443840 +1662122194135444736 +1662122194186445824 +1662122194231446784 +1662122194270447616 +1662122194309448448 +1662122194348449280 +1662122194390450176 +1662122194432451072 +1662122194471451904 +1662122194513452800 +1662122194558453760 +1662122194603454720 +1662122194645455616 +1662122194690456576 +1662122194729457408 +1662122194777458432 +1662122194819459328 +1662122194864460288 +1662122194906461184 +1662122194954462208 +1662122194999463168 +1662122195044464128 +1662122195089465088 +1662122195131465984 +1662122195179467008 +1662122195224467968 +1662122195266468864 +1662122195308469760 +1662122195353470720 +1662122195395471616 +1662122195443472640 +1662122195488473600 +1662122195533474560 +1662122195572475392 +1662122195614476288 +1662122195656477184 +1662122195698478080 +1662122195740478976 +1662122195782479872 +1662122195821480704 +1662122195866481664 +1662122195908482560 +1662122195953483520 +1662122195992484352 +1662122196037485312 +1662122196082486272 +1662122196127487232 +1662122196169488128 +1662122196211489024 +1662122196253489920 +1662122196292490752 +1662122196334491648 +1662122196373492480 +1662122196415493376 +1662122196454494208 +1662122196496495104 +1662122196538496000 +1662122196580496896 +1662122196622497792 +1662122196667498752 +1662122196709499648 +1662122196748500480 +1662122196793501440 +1662122196838502400 +1662122196880503296 +1662122196922504192 +1662122196967505152 +1662122197015506176 +1662122197057507072 +1662122197099507968 +1662122197138508800 +1662122197180509696 +1662122197222510592 +1662122197264511488 +1662122197309512448 +1662122197351513344 +1662122197393514240 +1662122197441515264 +1662122197483516160 +1662122197528517120 +1662122197570518016 +1662122197621519104 +1662122197663520000 +1662122197705520896 +1662122197747521792 +1662122197789522688 +1662122197834523648 +1662122197879524608 +1662122197921525504 +1662122197963526400 +1662122198005527296 +1662122198044528128 +1662122198086529024 +1662122198131529984 +1662122198176530944 +1662122198218531840 +1662122198263532800 +1662122198302533632 +1662122198347534592 +1662122198395535616 +1662122198434536448 +1662122198482537472 +1662122198521538304 +1662122198563539200 +1662122198605540096 +1662122198644540928 +1662122198680541696 +1662122198722542592 +1662122198767543552 +1662122198806544384 +1662122198851545344 +1662122198890546176 +1662122198938547200 +1662122198986548224 +1662122199025549056 +1662122199064549888 +1662122199103550720 +1662122199145551616 +1662122199193552640 +1662122199241553664 +1662122199283554560 +1662122199331555584 +1662122199376556544 +1662122199415557376 +1662122199463558400 +1662122199508559360 +1662122199553560320 +1662122199601561344 +1662122199640562176 +1662122199682563072 +1662122199727564032 +1662122199769564928 +1662122199814565888 +1662122199862566912 +1662122199904567808 +1662122199943568640 +1662122199994569728 +1662122200033570560 +1662122200078571520 +1662122200120572416 +1662122200159573248 +1662122200204574208 +1662122200240574976 +1662122200285575936 +1662122200330576896 +1662122200369577728 +1662122200420578816 +1662122200459579648 +1662122200498580480 +1662122200540581376 +1662122200582582272 +1662122200621583104 +1662122200666584064 +1662122200708584960 +1662122200753585920 +1662122200795586816 +1662122200834587648 +1662122200876588544 +1662122200918589440 diff --git a/Examples/Monocular/mono_mimir.cc b/Examples/Monocular/mono_mimir.cc index 1bb32ead61..9d690a9d4d 100644 --- a/Examples/Monocular/mono_mimir.cc +++ b/Examples/Monocular/mono_mimir.cc @@ -35,7 +35,7 @@ int main(int argc, char **argv) if(argc < 5) { cerr << endl << "Usage: ./mono_Mimir path_to_vocabulary path_to_settings path_to_sequence_folder_1 path_to_times_file_1 (path_to_image_folder_2 path_to_times_file_2 ... path_to_image_folder_N path_to_times_file_N) (trajectory_file_name)" << endl; - cerr << endl << "Example: ./Examples/Monocular/mono_mimir /home/olaya/dev/ORB_SLAM3/Vocabulary/ORBvoc.txt /home/olaya/dev/ORB_SLAM3/Examples/Monocular/MIMIR.yaml /home/olaya/Datasets/MIMIR/SeaFloor/track0/auv0/rgb/cam0/data /home/olaya/Datasets/MIMIR/SeaFloor/track0/auv0/ORB_timestamps.txt seafloor_track1.txt" << endl; + cerr << endl << "Example: ./Examples/Monocular/mono_mimir /home/olaya/dev/ORB_SLAM3/Vocabulary/ORBvoc.txt /home/olaya/dev/ORB_SLAM3/Examples/Monocular/MIMIR.yaml /home/olaya/Datasets/MIMIR/SeaFloor/track0/auv0/rgb/cam2/data /home/olaya/Datasets/MIMIR/SeaFloor/track0/auv0/ORB_timestamps.txt seafloor_cam2_track0.txt" << endl; return 1; } @@ -63,7 +63,7 @@ int main(int argc, char **argv) for (seq = 0; seq Date: Fri, 23 Sep 2022 16:14:32 +0200 Subject: [PATCH 07/17] bash files for easy running of algorithms --- run_mono.sh | 2 +- run_stereo.sh | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/run_mono.sh b/run_mono.sh index cf26fcf93a..103395b6e4 100755 --- a/run_mono.sh +++ b/run_mono.sh @@ -3,6 +3,6 @@ echo "Environment: $1"; echo "Track: $2"; echo "camera: $3"; -./Examples/Monocular/mono_mimir Vocabulary/ORBvoc.txt Examples/Monocular/MIMIR.yaml $HOME/Datasets/MIMIR/$1/$2/auv0/rgb/$3/data $HOME/Datasets/MIMIR/$1/$2/auv0/ORB_timestamps.txt $1_$2_$3.txt +./Examples/Monocular/mono_mimir Vocabulary/ORBvoc.txt Examples/Monocular/MIMIR.yaml $HOME/Datasets/MIMIR/$1/$2/auv0/rgb/$3/data Examples/Monocular/MIMIR_TimeStamps/$1_$2.txt $1_$2_$3.txt diff --git a/run_stereo.sh b/run_stereo.sh index 028ecca652..f9657b7afd 100755 --- a/run_stereo.sh +++ b/run_stereo.sh @@ -2,4 +2,4 @@ echo "Environment: $1"; echo "Track: $2"; -./Examples/Stereo/stereo_mimir /home/olaya/dev/ORB_SLAM3/Vocabulary/ORBvoc.txt Examples/Stereo/MIMIR.yaml $HOME/Datasets/MIMIR/$1/$2 $HOME/Datasets/MIMIR/$1/$2/auv0/ORB_timestamps.txt /home/olaya/Datasets/MIMIR/$1/$2 /home/olaya/Datasets/MIMIR/$1/$2/auv0/ORB_timestamps.txt $1_$2_cam2.txt \ No newline at end of file +./Examples/Stereo/stereo_mimir /home/olaya/dev/ORB_SLAM3/Vocabulary/ORBvoc.txt Examples/Stereo/MIMIR.yaml $HOME/Datasets/MIMIR/$1/$2 Examples/Monocular/MIMIR_TimeStamps/$1_$2.txt /home/olaya/Datasets/MIMIR/$1/$2 Examples/Monocular/MIMIR_TimeStamps/$1_$2.txt $1_$2_cam2.txt \ No newline at end of file From bd34d378fab97754db5ee88e90f8ad7be5607600 Mon Sep 17 00:00:00 2001 From: olayasturias Date: Fri, 23 Sep 2022 16:29:37 +0200 Subject: [PATCH 08/17] readme MIMIR instructions --- README.md | 31 +++++++++++++++++++++++++++---- 1 file changed, 27 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 0ca3a9f2d3..9242f408c4 100644 --- a/README.md +++ b/README.md @@ -7,7 +7,13 @@ The [Changelog](https://github.com/UZ-SLAMLab/ORB_SLAM3/blob/master/Changelog.md ORB-SLAM3 is the first real-time SLAM library able to perform **Visual, Visual-Inertial and Multi-Map SLAM** with **monocular, stereo and RGB-D** cameras, using **pin-hole and fisheye** lens models. In all sensor configurations, ORB-SLAM3 is as robust as the best systems available in the literature, and significantly more accurate. -We provide examples to run ORB-SLAM3 in the [EuRoC dataset](http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets) using stereo or monocular, with or without IMU, and in the [TUM-VI dataset](https://vision.in.tum.de/data/datasets/visual-inertial-dataset) using fisheye stereo or monocular, with or without IMU. Videos of some example executions can be found at [ORB-SLAM3 channel](https://www.youtube.com/channel/UCXVt-kXG6T95Z4tVaYlU80Q). +We provide examples to run ORB-SLAM3 in the datasets: + - [EuRoC](http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets) using stereo or monocular, with or without IMU. + - [TUM-VI](https://vision.in.tum.de/data/datasets/visual-inertial-dataset) using fisheye stereo or monocular, with or without IMU. + - [MIMIR-UW](https://github.com/remaro-network/MIMIR-UW) using stereo or monocular, without IMU. + +Videos of some example executions can be found at [ORB-SLAM3 channel](https://www.youtube.com/channel/UCXVt-kXG6T95Z4tVaYlU80Q). + This software is based on [ORB-SLAM2](https://github.com/raulmur/ORB_SLAM2) developed by [Raul Mur-Artal](http://webdiis.unizar.es/~raulmur/), [Juan D. Tardos](http://webdiis.unizar.es/~jdtardos/), [J. M. M. Montiel](http://webdiis.unizar.es/~josemari/) and [Dorian Galvez-Lopez](http://doriangalvez.com/) ([DBoW2](https://github.com/dorian3d/DBoW2)). @@ -143,6 +149,23 @@ Execute the following script to process sequences and compute the RMS ATE: ./tum_vi_examples ``` +# 7. MIMIR-UW Examples +[MIMIR-UW](https://github.com/remaro-network/MIMIR-UW) was recorded with three cameras comprising an stereo set and a downward-looking camera, and an inertial sensor. + +1. Download the sequences following the structure detailed in the dataset's readme. + +2. For easy execution of MIMIR-UW, we provide two executable files for mono (`run_mono.sh`) and stereo (`run_stereo.sh`). Open the scripts and change the directories to the dataset to the directory in which you have downloading and uncompressed them. + +3. Execute the scripts as: +``` +./run_mono +``` +For example: +``` +./run_mono SeaFloor track0 cam0 +``` + + ## Evaluation In TUM-VI ground truth is only available in the room where all sequences start and end. As a result the error measures the drift at the end of the sequence. @@ -151,7 +174,7 @@ Execute the following script to process sequences and compute the RMS ATE: ./tum_vi_eval_examples ``` -# 7. ROS Examples +# 8. ROS Examples ### Building the nodes for mono, mono-inertial, stereo, stereo-inertial and RGB-D Tested with ROS Melodic and ubuntu 18.04. @@ -228,8 +251,8 @@ Once ORB-SLAM3 has loaded the vocabulary, press space in the rosbag tab. rosrun rosbag fastrebag.py dataset-room1_512_16.bag dataset-room1_512_16_small_chunks.bag ``` -# 8. Running time analysis +# 9. Running time analysis A flag in `include\Config.h` activates time measurements. It is necessary to uncomment the line `#define REGISTER_TIMES` to obtain the time stats of one execution which is shown at the terminal and stored in a text file(`ExecTimeMean.txt`). -# 9. Calibration +# 10. Calibration You can find a tutorial for visual-inertial calibration and a detailed description of the contents of valid configuration files at `Calibration_Tutorial.pdf` From c43b1ffcee4d532454a9feae4812061ec4b04918 Mon Sep 17 00:00:00 2001 From: olayasturias Date: Tue, 22 Nov 2022 16:36:12 +0100 Subject: [PATCH 09/17] running on Aqualoc --- CMakeLists.txt | 4 + Examples/Monocular/Aqualoc.yaml | 65 ++++++++++++ Examples/Monocular/mono_aqualoc.cc | 157 +++++++++++++++++++++++++++++ Examples/aqualoc_mono.sh | 12 +++ 4 files changed, 238 insertions(+) create mode 100755 Examples/Monocular/Aqualoc.yaml create mode 100644 Examples/Monocular/mono_aqualoc.cc create mode 100755 Examples/aqualoc_mono.sh diff --git a/CMakeLists.txt b/CMakeLists.txt index 5a87d4e2f7..1b85de7d19 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -209,6 +209,10 @@ add_executable(mono_mimir Examples/Monocular/mono_mimir.cc) target_link_libraries(mono_mimir ${PROJECT_NAME}) +add_executable(mono_aqualoc + Examples/Monocular/mono_aqualoc.cc) +target_link_libraries(mono_aqualoc ${PROJECT_NAME}) + add_executable(mono_tum_vi Examples/Monocular/mono_tum_vi.cc) target_link_libraries(mono_tum_vi ${PROJECT_NAME}) diff --git a/Examples/Monocular/Aqualoc.yaml b/Examples/Monocular/Aqualoc.yaml new file mode 100755 index 0000000000..66799ff3ee --- /dev/null +++ b/Examples/Monocular/Aqualoc.yaml @@ -0,0 +1,65 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- +File.version: "1.0" + +Camera.type: "PinHole" + +# Camera calibration and distortion parameters (OpenCV) +Camera1.fx: 543.3327734182214 +Camera1.fy: 542.398772982566 +Camera1.cx: 489.02536042247897 +Camera1.cy: 305.38727712002805 + +Camera1.k1: -0.1255945656257394 +Camera1.k2: 0.053221287232781606 +Camera1.p1: 9.94070021080493e-05 +Camera1.p2: 9.550660927242349e-05 +Camera1.k3: 0. +Camera.width: 968 +Camera.height: 608 + +Camera.newWidth: 640 +Camera.newHeight: 480 + +# Camera frames per second +Camera.fps: 20 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#--------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1.0 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize: 2.0 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3.0 +Viewer.ViewpointX: 0.0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500.0 \ No newline at end of file diff --git a/Examples/Monocular/mono_aqualoc.cc b/Examples/Monocular/mono_aqualoc.cc new file mode 100644 index 0000000000..65100e40e3 --- /dev/null +++ b/Examples/Monocular/mono_aqualoc.cc @@ -0,0 +1,157 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + + +#include +#include +#include +#include + +#include + +#include + +using namespace std; + +void LoadImages(const string &strFile, vector &vstrImageFilenames, + vector &vTimestamps); + +int main(int argc, char **argv) +{ + if(argc != 5) + { + cerr << endl << "Usage: ./mono_tum path_to_vocabulary path_to_settings path_to_sequence number_of_seq" << endl; + return 1; + } + + // Retrieve paths to images + vector vstrImageFilenames; + vector vTimestamps; + string strFile = string(argv[3])+"/raw_data/img_sequence_"+string(argv[4])+".csv"; + LoadImages(strFile, vstrImageFilenames, vTimestamps); + + + int nImages = vstrImageFilenames.size(); + cout << nImages << endl; + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR,true); + + // Vector for tracking time statistics + vector vTimesTrack; + vTimesTrack.resize(nImages); + + // Main loop + cv::Mat im; + for(int ni=0; ni >(t2 - t1).count(); + + vTimesTrack[ni]=ttrack; + + // Wait to load the next frame + double T=0; + if(ni0) + T = tframe-vTimestamps[ni-1]; + + if(ttrack &vstrImageFilenames, vector &vTimestamps) +{ + ifstream f; + f.open(strFile.c_str()); + + // skip first line + string s0; + getline(f,s0,','); + getline(f,s0,','); + + while(!f.eof()) + { + string s; + getline(f,s,','); + if(!s.empty()) + { + stringstream ss; + ss << s; + + double t; + string sRGB; + + ss >> sRGB; + ss >> t; + + vTimestamps.push_back(t/1e9d); + vstrImageFilenames.push_back(sRGB); + + + } + } +} diff --git a/Examples/aqualoc_mono.sh b/Examples/aqualoc_mono.sh new file mode 100755 index 0000000000..8aefb8ebc1 --- /dev/null +++ b/Examples/aqualoc_mono.sh @@ -0,0 +1,12 @@ +#!/bin/bash +pathDatasetaqualoc='/home/olaya/Datasets/Aqualoc/Archaeological_site_sequences' #Example, it is necesary to change it by the dataset path + +tracks='1 2 3 4 5 6' +for track in $tracks +do +echo "Launching $track with Monocular sensor" +./Monocular/mono_aqualoc ../Vocabulary/ORBvoc.txt Monocular/Aqualoc.yaml "$pathDatasetaqualoc"/archaeo_sequence_$track\_raw_data $track +mv KeyFrameTrajectory.txt kf_archaeo_sequence_$track\_raw_data.txt +done + +# ./Monocular/mono_aqualoc ../Vocabulary/ORBvoc.txt Monocular/Aqualoc.yaml /home/olaya/Datasets/Aqualoc/Archaeological_site_sequences/archaeo_sequence_1_raw_data 1 \ No newline at end of file From 3c89149ae448368c309f955a81f35db111a01666 Mon Sep 17 00:00:00 2001 From: olayasturias Date: Tue, 22 Nov 2022 17:31:49 +0100 Subject: [PATCH 10/17] aqualoc loader and example --- CMakeLists.txt | 4 + Examples/Monocular/Aqualoc.yaml | 65 ++++++++++++ Examples/Monocular/mono_aqualoc.cc | 157 +++++++++++++++++++++++++++++ 3 files changed, 226 insertions(+) create mode 100755 Examples/Monocular/Aqualoc.yaml create mode 100644 Examples/Monocular/mono_aqualoc.cc diff --git a/CMakeLists.txt b/CMakeLists.txt index 016e74354d..fd6f1fcb65 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -205,6 +205,10 @@ add_executable(mono_tum_vi Examples/Monocular/mono_tum_vi.cc) target_link_libraries(mono_tum_vi ${PROJECT_NAME}) +add_executable(mono_aqualoc + Examples/Monocular/mono_aqualoc.cc) +target_link_libraries(mono_aqualoc ${PROJECT_NAME}) + if(realsense2_FOUND) add_executable(mono_realsense_t265 Examples/Monocular/mono_realsense_t265.cc) diff --git a/Examples/Monocular/Aqualoc.yaml b/Examples/Monocular/Aqualoc.yaml new file mode 100755 index 0000000000..66799ff3ee --- /dev/null +++ b/Examples/Monocular/Aqualoc.yaml @@ -0,0 +1,65 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- +File.version: "1.0" + +Camera.type: "PinHole" + +# Camera calibration and distortion parameters (OpenCV) +Camera1.fx: 543.3327734182214 +Camera1.fy: 542.398772982566 +Camera1.cx: 489.02536042247897 +Camera1.cy: 305.38727712002805 + +Camera1.k1: -0.1255945656257394 +Camera1.k2: 0.053221287232781606 +Camera1.p1: 9.94070021080493e-05 +Camera1.p2: 9.550660927242349e-05 +Camera1.k3: 0. +Camera.width: 968 +Camera.height: 608 + +Camera.newWidth: 640 +Camera.newHeight: 480 + +# Camera frames per second +Camera.fps: 20 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#--------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1.0 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize: 2.0 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3.0 +Viewer.ViewpointX: 0.0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500.0 \ No newline at end of file diff --git a/Examples/Monocular/mono_aqualoc.cc b/Examples/Monocular/mono_aqualoc.cc new file mode 100644 index 0000000000..65100e40e3 --- /dev/null +++ b/Examples/Monocular/mono_aqualoc.cc @@ -0,0 +1,157 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + + +#include +#include +#include +#include + +#include + +#include + +using namespace std; + +void LoadImages(const string &strFile, vector &vstrImageFilenames, + vector &vTimestamps); + +int main(int argc, char **argv) +{ + if(argc != 5) + { + cerr << endl << "Usage: ./mono_tum path_to_vocabulary path_to_settings path_to_sequence number_of_seq" << endl; + return 1; + } + + // Retrieve paths to images + vector vstrImageFilenames; + vector vTimestamps; + string strFile = string(argv[3])+"/raw_data/img_sequence_"+string(argv[4])+".csv"; + LoadImages(strFile, vstrImageFilenames, vTimestamps); + + + int nImages = vstrImageFilenames.size(); + cout << nImages << endl; + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR,true); + + // Vector for tracking time statistics + vector vTimesTrack; + vTimesTrack.resize(nImages); + + // Main loop + cv::Mat im; + for(int ni=0; ni >(t2 - t1).count(); + + vTimesTrack[ni]=ttrack; + + // Wait to load the next frame + double T=0; + if(ni0) + T = tframe-vTimestamps[ni-1]; + + if(ttrack &vstrImageFilenames, vector &vTimestamps) +{ + ifstream f; + f.open(strFile.c_str()); + + // skip first line + string s0; + getline(f,s0,','); + getline(f,s0,','); + + while(!f.eof()) + { + string s; + getline(f,s,','); + if(!s.empty()) + { + stringstream ss; + ss << s; + + double t; + string sRGB; + + ss >> sRGB; + ss >> t; + + vTimestamps.push_back(t/1e9d); + vstrImageFilenames.push_back(sRGB); + + + } + } +} From b24a3a2df5c0e16eefcc38e89c190f03783139a9 Mon Sep 17 00:00:00 2001 From: olayasturias Date: Tue, 22 Nov 2022 17:35:44 +0100 Subject: [PATCH 11/17] example usage for aqualoc script --- Examples/Monocular/mono_aqualoc.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Examples/Monocular/mono_aqualoc.cc b/Examples/Monocular/mono_aqualoc.cc index 65100e40e3..007ae7ac30 100644 --- a/Examples/Monocular/mono_aqualoc.cc +++ b/Examples/Monocular/mono_aqualoc.cc @@ -36,7 +36,7 @@ int main(int argc, char **argv) { if(argc != 5) { - cerr << endl << "Usage: ./mono_tum path_to_vocabulary path_to_settings path_to_sequence number_of_seq" << endl; + cerr << endl << "Usage: ./mono_aqualoc path_to_vocabulary path_to_settings path_to_sequence number_of_seq" << endl; return 1; } From 5e7879c6af2f8da7c56bda2e0e1f59499b4b804a Mon Sep 17 00:00:00 2001 From: olayasturias Date: Wed, 23 Nov 2022 15:23:21 +0100 Subject: [PATCH 12/17] add MIMIR dataset capabilities --- CMakeLists.txt | 10 +- Examples/Monocular/MIMIR.yaml | 77 + .../OceanFloor_track0_dark.txt | 2405 +++++++ .../OceanFloor_track0_light.txt | 2421 +++++++ .../OceanFloor_track1_light.txt | 6263 +++++++++++++++++ .../MIMIR_TimeStamps/SandPipe_track0_dark.txt | 2741 ++++++++ .../SandPipe_track0_light.txt | 2605 +++++++ .../SeaFloor_Algae_track0.txt | 2934 ++++++++ .../SeaFloor_Algae_track1.txt | 2076 ++++++ .../SeaFloor_Algae_track2.txt | 2489 +++++++ .../MIMIR_TimeStamps/SeaFloor_track0.txt | 2847 ++++++++ .../MIMIR_TimeStamps/SeaFloor_track1.txt | 2030 ++++++ .../MIMIR_TimeStamps/SeaFloor_track2.txt | 2537 +++++++ Examples/Monocular/mono_mimir.cc | 230 + Examples/Stereo/MIMIR.yaml | 96 + .../OceanFloor_track0_dark.txt | 2405 +++++++ .../OceanFloor_track0_light.txt | 2421 +++++++ .../OceanFloor_track1_light.txt | 6263 +++++++++++++++++ .../MIMIR_TimeStamps/SandPipe_track0_dark.txt | 2741 ++++++++ .../SandPipe_track0_light.txt | 2605 +++++++ .../SeaFloor_Algae_track0.txt | 2934 ++++++++ .../SeaFloor_Algae_track1.txt | 2076 ++++++ .../SeaFloor_Algae_track2.txt | 2489 +++++++ .../MIMIR_TimeStamps/SeaFloor_track0.txt | 2847 ++++++++ .../MIMIR_TimeStamps/SeaFloor_track1.txt | 2030 ++++++ .../MIMIR_TimeStamps/SeaFloor_track2.txt | 2537 +++++++ Examples/Stereo/stereo_mimir.cc | 212 + 27 files changed, 63320 insertions(+), 1 deletion(-) create mode 100644 Examples/Monocular/MIMIR.yaml create mode 100644 Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_dark.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_light.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track1_light.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_dark.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_light.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track0.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track1.txt create mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track2.txt create mode 100644 Examples/Monocular/mono_mimir.cc create mode 100644 Examples/Stereo/MIMIR.yaml create mode 100644 Examples/Stereo/MIMIR_TimeStamps/OceanFloor_track0_dark.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/OceanFloor_track0_light.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/OceanFloor_track1_light.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SandPipe_track0_dark.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SandPipe_track0_light.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SeaFloor_track0.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SeaFloor_track1.txt create mode 100644 Examples/Stereo/MIMIR_TimeStamps/SeaFloor_track2.txt create mode 100644 Examples/Stereo/stereo_mimir.cc diff --git a/CMakeLists.txt b/CMakeLists.txt index fd6f1fcb65..5fdb0a481a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -30,7 +30,7 @@ endif() LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules) -find_package(OpenCV 4.4) +find_package(OpenCV) if(NOT OpenCV_FOUND) message(FATAL_ERROR "OpenCV > 4.4 not found.") endif() @@ -209,6 +209,10 @@ add_executable(mono_aqualoc Examples/Monocular/mono_aqualoc.cc) target_link_libraries(mono_aqualoc ${PROJECT_NAME}) +add_executable(mono_mimir + Examples/Monocular/mono_mimir.cc) +target_link_libraries(mono_mimir ${PROJECT_NAME}) + if(realsense2_FOUND) add_executable(mono_realsense_t265 Examples/Monocular/mono_realsense_t265.cc) @@ -247,6 +251,10 @@ add_executable(stereo_inertial_euroc Examples/Stereo-Inertial/stereo_inertial_euroc.cc) target_link_libraries(stereo_inertial_euroc ${PROJECT_NAME}) +add_executable(stereo_mimir + Examples/Stereo/stereo_mimir.cc) +target_link_libraries(stereo_mimir ${PROJECT_NAME}) + add_executable(stereo_inertial_tum_vi Examples/Stereo-Inertial/stereo_inertial_tum_vi.cc) target_link_libraries(stereo_inertial_tum_vi ${PROJECT_NAME}) diff --git a/Examples/Monocular/MIMIR.yaml b/Examples/Monocular/MIMIR.yaml new file mode 100644 index 0000000000..4ee9715b10 --- /dev/null +++ b/Examples/Monocular/MIMIR.yaml @@ -0,0 +1,77 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# System config +#-------------------------------------------------------------------------------------------- + +# When the variables are commented, the system doesn't load a previous session or not store the current one + +# If the LoadFile doesn't exist, the system give a message and create a new Atlas from scratch +#System.LoadAtlasFromFile: "Session_MH01_MH02_MH03_Mono" + +# The store file is created from the current session, if a file with the same name exists it is deleted +#System.SaveAtlasToFile: "Session_MH01_MH02_MH03_Mono" + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- +File.version: "1.0" + +Camera.type: "PinHole" + +# Camera calibration and distortion parameters (OpenCV) +Camera1.fx: 252.07470703125 +Camera1.fy: 252.07470703125 +Camera1.cx: 360.0 +Camera1.cy: 270.0 + +Camera1.k1: 0.0 +Camera1.k2: 0.0 +Camera1.p1: 0.0 +Camera1.p2: 0.0 + +Camera.width: 720 +Camera.height: 540 + +Camera.newWidth: 720 +Camera.newHeight: 540 + +# Camera frames per second +Camera.fps: 30 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#--------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1.0 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize: 2.0 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3.0 +Viewer.ViewpointX: 0.0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500.0 \ No newline at end of file diff --git a/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_dark.txt b/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_dark.txt new file mode 100644 index 0000000000..e14794a331 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_dark.txt @@ -0,0 +1,2405 @@ +1662138209585822464 +1662138209624823296 +1662138209666824192 +1662138209705825024 +1662138209747825920 +1662138209789826816 +1662138209831827712 +1662138209873828608 +1662138209918829568 +1662138209972830720 +1662138210017831680 +1662138210065832704 +1662138210110833664 +1662138210155834624 +1662138210197835520 +1662138210242836480 +1662138210287837440 +1662138210329838336 +1662138210374839296 +1662138210416840192 +1662138210467841280 +1662138210515842304 +1662138210563843328 +1662138210605844224 +1662138210647845120 +1662138210698846208 +1662138210740847104 +1662138210782848000 +1662138210824848896 +1662138210869849856 +1662138210914850816 +1662138210959851776 +1662138211001852672 +1662138211046853632 +1662138211088854528 +1662138211130855424 +1662138211181856512 +1662138211223857408 +1662138211262858240 +1662138211304859136 +1662138211349860096 +1662138211391860992 +1662138211436861952 +1662138211475862784 +1662138211517863680 +1662138211562864640 +1662138211607865600 +1662138211652866560 +1662138211697867520 +1662138211745868544 +1662138211787869440 +1662138211829870336 +1662138211874871296 +1662138211925872384 +1662138211967873280 +1662138212012874240 +1662138212060875264 +1662138212102876160 +1662138212141876992 +1662138212180877824 +1662138212222878720 +1662138212270879744 +1662138212318880768 +1662138212363881728 +1662138212411882752 +1662138212465883904 +1662138212507884800 +1662138212552885760 +1662138212597886720 +1662138212639887616 +1662138212684888576 +1662138212732889600 +1662138212771890432 +1662138212813891328 +1662138212855892224 +1662138212897893120 +1662138212939894016 +1662138212981894912 +1662138213026895872 +1662138213068896768 +1662138213116897792 +1662138213161898752 +1662138213206899712 +1662138213248900608 +1662138213290901504 +1662138213332902400 +1662138213374903296 +1662138213416904192 +1662138213461905152 +1662138213509906176 +1662138213551907072 +1662138213599908096 +1662138213641908992 +1662138213695910144 +1662138213737911040 +1662138213788912128 +1662138213833913088 +1662138213881914112 +1662138213929915136 +1662138213971916032 +1662138214019917056 +1662138214061917952 +1662138214109918976 +1662138214157920000 +1662138214208921088 +1662138214250921984 +1662138214298923008 +1662138214337923840 +1662138214382924800 +1662138214430925824 +1662138214478926848 +1662138214520927744 +1662138214562928640 +1662138214604929536 +1662138214649930496 +1662138214691931392 +1662138214733932288 +1662138214775933184 +1662138214820934144 +1662138214859934976 +1662138214904935936 +1662138214955937024 +1662138214997937920 +1662138215042938880 +1662138215084939776 +1662138215132940800 +1662138215171941632 +1662138215210942464 +1662138215255943424 +1662138215300944384 +1662138215342945280 +1662138215387946240 +1662138215429947136 +1662138215468947968 +1662138215513948928 +1662138215561949952 +1662138215606950912 +1662138215648951808 +1662138215690952704 +1662138215738953728 +1662138215780954624 +1662138215828955648 +1662138215870956544 +1662138215909957376 +1662138215957958400 +1662138215999959296 +1662138216041960192 +1662138216083961088 +1662138216122961920 +1662138216164962816 +1662138216212963840 +1662138216257964800 +1662138216299965696 +1662138216341966592 +1662138216383967488 +1662138216431968512 +1662138216470969344 +1662138216512970240 +1662138216554971136 +1662138216596972032 +1662138216641972992 +1662138216689974016 +1662138216737975040 +1662138216782976000 +1662138216824976896 +1662138216866977792 +1662138216905978624 +1662138216947979520 +1662138216992980480 +1662138217034981376 +1662138217085982464 +1662138217133983488 +1662138217175984384 +1662138217214985216 +1662138217259986176 +1662138217301987072 +1662138217349988096 +1662138217391988992 +1662138217433989888 +1662138217475990784 +1662138217517991680 +1662138217559992576 +1662138217607993600 +1662138217652994560 +1662138217700995584 +1662138217742996480 +1662138217787997440 +1662138217829998336 +1662138217871999232 +1662138217914000128 +1662138217956001024 +1662138217998001920 +1662138218040002816 +1662138218085003776 +1662138218130004736 +1662138218175005696 +1662138218217006592 +1662138218256007424 +1662138218298008320 +1662138218343009280 +1662138218385010176 +1662138218427011072 +1662138218469011968 +1662138218517012992 +1662138218559013888 +1662138218601014784 +1662138218646015744 +1662138218694016768 +1662138218739017728 +1662138218781018624 +1662138218823019520 +1662138218865020416 +1662138218907021312 +1662138218949022208 +1662138218997023232 +1662138219036024064 +1662138219081025024 +1662138219123025920 +1662138219162026752 +1662138219207027712 +1662138219249028608 +1662138219294029568 +1662138219339030528 +1662138219381031424 +1662138219423032320 +1662138219474033408 +1662138219519034368 +1662138219567035392 +1662138219612036352 +1662138219660037376 +1662138219708038400 +1662138219756039424 +1662138219798040320 +1662138219846041344 +1662138219888042240 +1662138219933043200 +1662138219987044352 +1662138220035045376 +1662138220080046336 +1662138220128047360 +1662138220173048320 +1662138220218049280 +1662138220263050240 +1662138220305051136 +1662138220350052096 +1662138220395053056 +1662138220434053888 +1662138220479054848 +1662138220524055808 +1662138220569056768 +1662138220611057664 +1662138220650058496 +1662138220692059392 +1662138220734060288 +1662138220779061248 +1662138220824062208 +1662138220869063168 +1662138220917064192 +1662138220962065152 +1662138221007066112 +1662138221049067008 +1662138221091067904 +1662138221133068800 +1662138221178069760 +1662138221220070656 +1662138221265071616 +1662138221307072512 +1662138221349073408 +1662138221403074560 +1662138221445075456 +1662138221493076480 +1662138221535077376 +1662138221580078336 +1662138221628079360 +1662138221670080256 +1662138221712081152 +1662138221757082112 +1662138221799083008 +1662138221838083840 +1662138221880084736 +1662138221922085632 +1662138221961086464 +1662138222009087488 +1662138222051088384 +1662138222102089472 +1662138222150090496 +1662138222195091456 +1662138222240092416 +1662138222288093440 +1662138222336094464 +1662138222381095424 +1662138222429096448 +1662138222471097344 +1662138222513098240 +1662138222558099200 +1662138222600100096 +1662138222648101120 +1662138222687101952 +1662138222732102912 +1662138222777103872 +1662138222822104832 +1662138222870105856 +1662138222912106752 +1662138222960107776 +1662138223002108672 +1662138223044109568 +1662138223086110464 +1662138223131111424 +1662138223173112320 +1662138223221113344 +1662138223266114304 +1662138223311115264 +1662138223359116288 +1662138223401117184 +1662138223437117952 +1662138223479118848 +1662138223527119872 +1662138223569120768 +1662138223611121664 +1662138223656122624 +1662138223701123584 +1662138223749124608 +1662138223791125504 +1662138223839126528 +1662138223881127424 +1662138223926128384 +1662138223968129280 +1662138224019130368 +1662138224058131200 +1662138224112132352 +1662138224160133376 +1662138224208134400 +1662138224247135232 +1662138224289136128 +1662138224334137088 +1662138224376137984 +1662138224418138880 +1662138224463139840 +1662138224511140864 +1662138224553141760 +1662138224598142720 +1662138224643143680 +1662138224688144640 +1662138224733145600 +1662138224784146688 +1662138224826147584 +1662138224868148480 +1662138224910149376 +1662138224952150272 +1662138224994151168 +1662138225039152128 +1662138225084153088 +1662138225132154112 +1662138225174155008 +1662138225219155968 +1662138225267156992 +1662138225315158016 +1662138225360158976 +1662138225405159936 +1662138225450160896 +1662138225501161984 +1662138225546162944 +1662138225588163840 +1662138225633164800 +1662138225678165760 +1662138225723166720 +1662138225765167616 +1662138225810168576 +1662138225858169600 +1662138225900170496 +1662138225948171520 +1662138225993172480 +1662138226035173376 +1662138226077174272 +1662138226122175232 +1662138226167176192 +1662138226212177152 +1662138226254178048 +1662138226302179072 +1662138226344179968 +1662138226392180992 +1662138226431181824 +1662138226473182720 +1662138226521183744 +1662138226566184704 +1662138226608185600 +1662138226650186496 +1662138226689187328 +1662138226743188480 +1662138226794189568 +1662138226839190528 +1662138226881191424 +1662138226923192320 +1662138226971193344 +1662138227013194240 +1662138227058195200 +1662138227103196160 +1662138227148197120 +1662138227193198080 +1662138227241199104 +1662138227286200064 +1662138227337201152 +1662138227391202304 +1662138227433203200 +1662138227475204096 +1662138227517204992 +1662138227559205888 +1662138227604206848 +1662138227652207872 +1662138227694208768 +1662138227739209728 +1662138227784210688 +1662138227826211584 +1662138227868212480 +1662138227910213376 +1662138227955214336 +1662138227997215232 +1662138228039216128 +1662138228084217088 +1662138228126217984 +1662138228171218944 +1662138228225220096 +1662138228267220992 +1662138228318222080 +1662138228363223040 +1662138228405223936 +1662138228456225024 +1662138228504226048 +1662138228549227008 +1662138228594227968 +1662138228642228992 +1662138228684229888 +1662138228729230848 +1662138228783232000 +1662138228828232960 +1662138228870233856 +1662138228918234880 +1662138228966235904 +1662138229008236800 +1662138229056237824 +1662138229095238656 +1662138229143239680 +1662138229185240576 +1662138229227241472 +1662138229269242368 +1662138229317243392 +1662138229359244288 +1662138229401245184 +1662138229449246208 +1662138229503247360 +1662138229545248256 +1662138229590249216 +1662138229632250112 +1662138229674251008 +1662138229716251904 +1662138229764252928 +1662138229806253824 +1662138229851254784 +1662138229893255680 +1662138229941256704 +1662138229986257664 +1662138230028258560 +1662138230073259520 +1662138230127260672 +1662138230169261568 +1662138230217262592 +1662138230262263552 +1662138230304264448 +1662138230349265408 +1662138230394266368 +1662138230436267264 +1662138230481268224 +1662138230526269184 +1662138230574270208 +1662138230613271040 +1662138230658272000 +1662138230706273024 +1662138230748273920 +1662138230790274816 +1662138230835275776 +1662138230877276672 +1662138230919277568 +1662138230961278464 +1662138231006279424 +1662138231048280320 +1662138231099281408 +1662138231141282304 +1662138231186283264 +1662138231228284160 +1662138231279285248 +1662138231324286208 +1662138231372287232 +1662138231414288128 +1662138231468289280 +1662138231510290176 +1662138231552291072 +1662138231594291968 +1662138231633292800 +1662138231675293696 +1662138231714294528 +1662138231759295488 +1662138231810296576 +1662138231852297472 +1662138231894298368 +1662138231942299392 +1662138231984300288 +1662138232023301120 +1662138232068302080 +1662138232113303040 +1662138232155303936 +1662138232203304960 +1662138232248305920 +1662138232290306816 +1662138232338307840 +1662138232386308864 +1662138232428309760 +1662138232467310592 +1662138232515311616 +1662138232557312512 +1662138232614313728 +1662138232656314624 +1662138232695315456 +1662138232737316352 +1662138232782317312 +1662138232833318400 +1662138232875319296 +1662138232917320192 +1662138232959321088 +1662138233001321984 +1662138233046322944 +1662138233088323840 +1662138233136324864 +1662138233187325952 +1662138233232326912 +1662138233280327936 +1662138233322328832 +1662138233364329728 +1662138233409330688 +1662138233451331584 +1662138233493332480 +1662138233535333376 +1662138233580334336 +1662138233625335296 +1662138233667336192 +1662138233715337216 +1662138233757338112 +1662138233805339136 +1662138233856340224 +1662138233895341056 +1662138233940342016 +1662138233979342848 +1662138234021343744 +1662138234066344704 +1662138234108345600 +1662138234153346560 +1662138234192347392 +1662138234237348352 +1662138234282349312 +1662138234324350208 +1662138234366351104 +1662138234408352000 +1662138234453352960 +1662138234504354048 +1662138234549355008 +1662138234591355904 +1662138234645357056 +1662138234690358016 +1662138234735358976 +1662138234780359936 +1662138234828360960 +1662138234870361856 +1662138234912362752 +1662138234957363712 +1662138235002364672 +1662138235050365696 +1662138235095366656 +1662138235143367680 +1662138235194368768 +1662138235236369664 +1662138235275370496 +1662138235317371392 +1662138235359372288 +1662138235407373312 +1662138235452374272 +1662138235497375232 +1662138235545376256 +1662138235596377344 +1662138235644378368 +1662138235686379264 +1662138235728380160 +1662138235773381120 +1662138235812381952 +1662138235854382848 +1662138235905383936 +1662138235947384832 +1662138235989385728 +1662138236037386752 +1662138236079387648 +1662138236121388544 +1662138236163389440 +1662138236211390464 +1662138236256391424 +1662138236298392320 +1662138236340393216 +1662138236388394240 +1662138236430395136 +1662138236475396096 +1662138236520397056 +1662138236565398016 +1662138236607398912 +1662138236652399872 +1662138236706401024 +1662138236748401920 +1662138236796402944 +1662138236844403968 +1662138236886404864 +1662138236931405824 +1662138236976406784 +1662138237018407680 +1662138237066408704 +1662138237108409600 +1662138237150410496 +1662138237201411584 +1662138237246412544 +1662138237288413440 +1662138237336414464 +1662138237378415360 +1662138237423416320 +1662138237471417344 +1662138237513418240 +1662138237555419136 +1662138237597420032 +1662138237642420992 +1662138237687421952 +1662138237729422848 +1662138237771423744 +1662138237813424640 +1662138237852425472 +1662138237894426368 +1662138237939427328 +1662138237981428224 +1662138238023429120 +1662138238065430016 +1662138238110430976 +1662138238152431872 +1662138238197432832 +1662138238248433920 +1662138238299435008 +1662138238350436096 +1662138238392436992 +1662138238434437888 +1662138238476438784 +1662138238515439616 +1662138238563440640 +1662138238608441600 +1662138238653442560 +1662138238695443456 +1662138238737444352 +1662138238779445248 +1662138238821446144 +1662138238863447040 +1662138238905447936 +1662138238956449024 +1662138239001449984 +1662138239049451008 +1662138239091451904 +1662138239130452736 +1662138239169453568 +1662138239211454464 +1662138239259455488 +1662138239304456448 +1662138239349457408 +1662138239400458496 +1662138239451459584 +1662138239499460608 +1662138239541461504 +1662138239586462464 +1662138239640463616 +1662138239682464512 +1662138239733465600 +1662138239778466560 +1662138239823467520 +1662138239865468416 +1662138239910469376 +1662138239961470464 +1662138240006471424 +1662138240048472320 +1662138240096473344 +1662138240141474304 +1662138240183475200 +1662138240225476096 +1662138240270477056 +1662138240315478016 +1662138240357478912 +1662138240402479872 +1662138240447480832 +1662138240492481792 +1662138240534482688 +1662138240576483584 +1662138240618484480 +1662138240663485440 +1662138240717486592 +1662138240762487552 +1662138240810488576 +1662138240849489408 +1662138240897490432 +1662138240945491456 +1662138240987492352 +1662138241032493312 +1662138241077494272 +1662138241122495232 +1662138241167496192 +1662138241209497088 +1662138241257498112 +1662138241299499008 +1662138241344499968 +1662138241389500928 +1662138241434501888 +1662138241479502848 +1662138241527503872 +1662138241569504768 +1662138241608505600 +1662138241650506496 +1662138241695507456 +1662138241743508480 +1662138241785509376 +1662138241830510336 +1662138241878511360 +1662138241923512320 +1662138241974513408 +1662138242019514368 +1662138242061515264 +1662138242106516224 +1662138242151517184 +1662138242193518080 +1662138242235518976 +1662138242277519872 +1662138242319520768 +1662138242361521664 +1662138242406522624 +1662138242454523648 +1662138242499524608 +1662138242538525440 +1662138242580526336 +1662138242622527232 +1662138242667528192 +1662138242712529152 +1662138242754530048 +1662138242796530944 +1662138242844531968 +1662138242889532928 +1662138242931533824 +1662138242982534912 +1662138243030535936 +1662138243072536832 +1662138243114537728 +1662138243159538688 +1662138243204539648 +1662138243249540608 +1662138243294541568 +1662138243336542464 +1662138243381543424 +1662138243423544320 +1662138243465545216 +1662138243510546176 +1662138243552547072 +1662138243594547968 +1662138243639548928 +1662138243681549824 +1662138243723550720 +1662138243765551616 +1662138243810552576 +1662138243861553664 +1662138243900554496 +1662138243948555520 +1662138243996556544 +1662138244044557568 +1662138244086558464 +1662138244131559424 +1662138244173560320 +1662138244218561280 +1662138244260562176 +1662138244308563200 +1662138244350564096 +1662138244392564992 +1662138244431565824 +1662138244473566720 +1662138244515567616 +1662138244557568512 +1662138244599569408 +1662138244641570304 +1662138244689571328 +1662138244737572352 +1662138244782573312 +1662138244824574208 +1662138244866575104 +1662138244914576128 +1662138244965577216 +1662138245010578176 +1662138245058579200 +1662138245106580224 +1662138245151581184 +1662138245196582144 +1662138245244583168 +1662138245292584192 +1662138245337585152 +1662138245391586304 +1662138245442587392 +1662138245487588352 +1662138245535589376 +1662138245577590272 +1662138245619591168 +1662138245667592192 +1662138245706593024 +1662138245754594048 +1662138245796594944 +1662138245847596032 +1662138245895597056 +1662138245937597952 +1662138245982598912 +1662138246027599872 +1662138246078600960 +1662138246123601920 +1662138246174603008 +1662138246216603904 +1662138246258604800 +1662138246300605696 +1662138246345606656 +1662138246387607552 +1662138246435608576 +1662138246480609536 +1662138246522610432 +1662138246567611392 +1662138246609612288 +1662138246654613248 +1662138246699614208 +1662138246744615168 +1662138246786616064 +1662138246825616896 +1662138246876617984 +1662138246918618880 +1662138246960619776 +1662138247011620864 +1662138247053621760 +1662138247104622848 +1662138247149623808 +1662138247191624704 +1662138247233625600 +1662138247284626688 +1662138247329627648 +1662138247371628544 +1662138247419629568 +1662138247461630464 +1662138247509631488 +1662138247554632448 +1662138247599633408 +1662138247650634496 +1662138247692635392 +1662138247740636416 +1662138247782637312 +1662138247833638400 +1662138247875639296 +1662138247917640192 +1662138247959641088 +1662138248007642112 +1662138248049643008 +1662138248097644032 +1662138248139644928 +1662138248181645824 +1662138248229646848 +1662138248268647680 +1662138248313648640 +1662138248355649536 +1662138248400650496 +1662138248442651392 +1662138248487652352 +1662138248532653312 +1662138248571654144 +1662138248616655104 +1662138248655655936 +1662138248697656832 +1662138248739657728 +1662138248784658688 +1662138248832659712 +1662138248874660608 +1662138248919661568 +1662138248967662592 +1662138249015663616 +1662138249057664512 +1662138249105665536 +1662138249150666496 +1662138249198667520 +1662138249240668416 +1662138249282669312 +1662138249324670208 +1662138249366671104 +1662138249411672064 +1662138249456673024 +1662138249501673984 +1662138249546674944 +1662138249594675968 +1662138249636676864 +1662138249678677760 +1662138249726678784 +1662138249768679680 +1662138249810680576 +1662138249855681536 +1662138249897682432 +1662138249942683392 +1662138249990684416 +1662138250032685312 +1662138250080686336 +1662138250122687232 +1662138250170688256 +1662138250215689216 +1662138250257690112 +1662138250305691136 +1662138250347692032 +1662138250398693120 +1662138250440694016 +1662138250485694976 +1662138250527695872 +1662138250569696768 +1662138250614697728 +1662138250662698752 +1662138250707699712 +1662138250752700672 +1662138250800701696 +1662138250845702656 +1662138250887703552 +1662138250938704640 +1662138250980705536 +1662138251022706432 +1662138251067707392 +1662138251112708352 +1662138251154709248 +1662138251196710144 +1662138251238711040 +1662138251280711936 +1662138251322712832 +1662138251364713728 +1662138251409714688 +1662138251451715584 +1662138251493716480 +1662138251541717504 +1662138251583718400 +1662138251628719360 +1662138251676720384 +1662138251715721216 +1662138251757722112 +1662138251808723200 +1662138251853724160 +1662138251898725120 +1662138251937725952 +1662138251985726976 +1662138252027727872 +1662138252072728832 +1662138252114729728 +1662138252156730624 +1662138252198731520 +1662138252246732544 +1662138252285733376 +1662138252327734272 +1662138252372735232 +1662138252420736256 +1662138252459737088 +1662138252501737984 +1662138252546738944 +1662138252591739904 +1662138252633740800 +1662138252690742016 +1662138252735742976 +1662138252783744000 +1662138252831745024 +1662138252873745920 +1662138252915746816 +1662138252957747712 +1662138252996748544 +1662138253041749504 +1662138253083750400 +1662138253125751296 +1662138253167752192 +1662138253215753216 +1662138253263754240 +1662138253314755328 +1662138253353756160 +1662138253398757120 +1662138253443758080 +1662138253494759168 +1662138253536760064 +1662138253581761024 +1662138253629762048 +1662138253683763200 +1662138253725764096 +1662138253770765056 +1662138253818766080 +1662138253857766912 +1662138253899767808 +1662138253953768960 +1662138254001769984 +1662138254043770880 +1662138254088771840 +1662138254136772864 +1662138254181773824 +1662138254223774720 +1662138254265775616 +1662138254310776576 +1662138254361777664 +1662138254406778624 +1662138254451779584 +1662138254496780544 +1662138254532781312 +1662138254577782272 +1662138254622783232 +1662138254670784256 +1662138254709785088 +1662138254751785984 +1662138254799787008 +1662138254841787904 +1662138254883788800 +1662138254931789824 +1662138254979790848 +1662138255024791808 +1662138255069792768 +1662138255111793664 +1662138255153794560 +1662138255195795456 +1662138255237796352 +1662138255282797312 +1662138255333798400 +1662138255378799360 +1662138255423800320 +1662138255462801152 +1662138255507802112 +1662138255549803008 +1662138255588803840 +1662138255633804800 +1662138255675805696 +1662138255717806592 +1662138255759807488 +1662138255801808384 +1662138255846809344 +1662138255894810368 +1662138255936811264 +1662138255981812224 +1662138256023813120 +1662138256065814016 +1662138256113815040 +1662138256161816064 +1662138256206817024 +1662138256242817792 +1662138256281818624 +1662138256329819648 +1662138256371820544 +1662138256419821568 +1662138256464822528 +1662138256506823424 +1662138256554824448 +1662138256596825344 +1662138256638826240 +1662138256683827200 +1662138256725828096 +1662138256770829056 +1662138256812829952 +1662138256860830976 +1662138256911832064 +1662138256956833024 +1662138257001833984 +1662138257052835072 +1662138257094835968 +1662138257139836928 +1662138257184837888 +1662138257235838976 +1662138257277839872 +1662138257328840960 +1662138257370841856 +1662138257412842752 +1662138257454843648 +1662138257496844544 +1662138257544845568 +1662138257586846464 +1662138257628847360 +1662138257670848256 +1662138257724849408 +1662138257769850368 +1662138257811851264 +1662138257853852160 +1662138257895853056 +1662138257937853952 +1662138257979854848 +1662138258021855744 +1662138258069856768 +1662138258117857792 +1662138258156858624 +1662138258201859584 +1662138258246860544 +1662138258294861568 +1662138258342862592 +1662138258387863552 +1662138258429864448 +1662138258471865344 +1662138258516866304 +1662138258567867392 +1662138258609868288 +1662138258654869248 +1662138258696870144 +1662138258741871104 +1662138258786872064 +1662138258825872896 +1662138258867873792 +1662138258912874752 +1662138258957875712 +1662138259005876736 +1662138259047877632 +1662138259095878656 +1662138259149879808 +1662138259200880896 +1662138259242881792 +1662138259287882752 +1662138259335883776 +1662138259386884864 +1662138259428885760 +1662138259470886656 +1662138259512887552 +1662138259560888576 +1662138259602889472 +1662138259647890432 +1662138259689891328 +1662138259734892288 +1662138259776893184 +1662138259824894208 +1662138259866895104 +1662138259911896064 +1662138259956897024 +1662138259998897920 +1662138260040898816 +1662138260088899840 +1662138260133900800 +1662138260175901696 +1662138260226902784 +1662138260268903680 +1662138260316904704 +1662138260364905728 +1662138260406906624 +1662138260448907520 +1662138260490908416 +1662138260529909248 +1662138260574910208 +1662138260616911104 +1662138260667912192 +1662138260721913344 +1662138260769914368 +1662138260814915328 +1662138260856916224 +1662138260898917120 +1662138260937917952 +1662138260985918976 +1662138261036920064 +1662138261081921024 +1662138261120921856 +1662138261165922816 +1662138261207923712 +1662138261252924672 +1662138261300925696 +1662138261342926592 +1662138261384927488 +1662138261441928704 +1662138261483929600 +1662138261528930560 +1662138261573931520 +1662138261618932480 +1662138261666933504 +1662138261708934400 +1662138261753935360 +1662138261801936384 +1662138261849937408 +1662138261900938496 +1662138261945939456 +1662138261987940352 +1662138262026941184 +1662138262074942208 +1662138262116943104 +1662138262164944128 +1662138262209945088 +1662138262254946048 +1662138262296946944 +1662138262350948096 +1662138262395949056 +1662138262437949952 +1662138262482950912 +1662138262533952000 +1662138262575952896 +1662138262617953792 +1662138262668954880 +1662138262716955904 +1662138262767956992 +1662138262815958016 +1662138262857958912 +1662138262905959936 +1662138262950960896 +1662138262992961792 +1662138263043962880 +1662138263088963840 +1662138263130964736 +1662138263178965760 +1662138263220966656 +1662138263265967616 +1662138263304968448 +1662138263355969536 +1662138263400970496 +1662138263451971584 +1662138263493972480 +1662138263544973568 +1662138263592974592 +1662138263634975488 +1662138263673976320 +1662138263718977280 +1662138263763978240 +1662138263811979264 +1662138263859980288 +1662138263901981184 +1662138263949982208 +1662138263991983104 +1662138264036984064 +1662138264087985152 +1662138264129986048 +1662138264174987008 +1662138264219987968 +1662138264258988800 +1662138264303989760 +1662138264354990848 +1662138264399991808 +1662138264444992768 +1662138264483993600 +1662138264525994496 +1662138264573995520 +1662138264618996480 +1662138264660997376 +1662138264702998272 +1662138264762999552 +1662138264808000512 +1662138264850001408 +1662138264898002432 +1662138264943003392 +1662138264985004288 +1662138265030005248 +1662138265072006144 +1662138265114007040 +1662138265159008000 +1662138265207009024 +1662138265249009920 +1662138265300011008 +1662138265348012032 +1662138265390012928 +1662138265432013824 +1662138265477014784 +1662138265522015744 +1662138265564016640 +1662138265606017536 +1662138265651018496 +1662138265696019456 +1662138265744020480 +1662138265786021376 +1662138265831022336 +1662138265873023232 +1662138265918024192 +1662138265966025216 +1662138266008026112 +1662138266050027008 +1662138266095027968 +1662138266146029056 +1662138266188029952 +1662138266239031040 +1662138266284032000 +1662138266332033024 +1662138266371033856 +1662138266413034752 +1662138266455035648 +1662138266497036544 +1662138266542037504 +1662138266587038464 +1662138266629039360 +1662138266674040320 +1662138266725041408 +1662138266770042368 +1662138266821043456 +1662138266863044352 +1662138266908045312 +1662138266950046208 +1662138266992047104 +1662138267037048064 +1662138267079048960 +1662138267121049856 +1662138267166050816 +1662138267208051712 +1662138267253052672 +1662138267298053632 +1662138267343054592 +1662138267391055616 +1662138267433056512 +1662138267475057408 +1662138267520058368 +1662138267568059392 +1662138267610060288 +1662138267649061120 +1662138267694062080 +1662138267739063040 +1662138267778063872 +1662138267820064768 +1662138267862065664 +1662138267907066624 +1662138267952067584 +1662138267994068480 +1662138268039069440 +1662138268078070272 +1662138268117071104 +1662138268165072128 +1662138268210073088 +1662138268264074240 +1662138268306075136 +1662138268348076032 +1662138268387076864 +1662138268429077760 +1662138268471078656 +1662138268519079680 +1662138268564080640 +1662138268606081536 +1662138268657082624 +1662138268696083456 +1662138268744084480 +1662138268792085504 +1662138268831086336 +1662138268879087360 +1662138268924088320 +1662138268972089344 +1662138269017090304 +1662138269068091392 +1662138269107092224 +1662138269152093184 +1662138269194094080 +1662138269236094976 +1662138269290096128 +1662138269335097088 +1662138269377097984 +1662138269419098880 +1662138269464099840 +1662138269506100736 +1662138269548101632 +1662138269590102528 +1662138269632103424 +1662138269680104448 +1662138269731105536 +1662138269776106496 +1662138269818107392 +1662138269863108352 +1662138269905109248 +1662138269956110336 +1662138269998111232 +1662138270040112128 +1662138270085113088 +1662138270130114048 +1662138270172114944 +1662138270217115904 +1662138270262116864 +1662138270304117760 +1662138270352118784 +1662138270394119680 +1662138270442120704 +1662138270484121600 +1662138270529122560 +1662138270571123456 +1662138270613124352 +1662138270661125376 +1662138270703126272 +1662138270745127168 +1662138270790128128 +1662138270841129216 +1662138270886130176 +1662138270928131072 +1662138270973132032 +1662138271015132928 +1662138271063133952 +1662138271108134912 +1662138271156135936 +1662138271201136896 +1662138271243137792 +1662138271294138880 +1662138271336139776 +1662138271384140800 +1662138271426141696 +1662138271477142784 +1662138271519143680 +1662138271558144512 +1662138271600145408 +1662138271645146368 +1662138271690147328 +1662138271729148160 +1662138271777149184 +1662138271819150080 +1662138271864151040 +1662138271912152064 +1662138271954152960 +1662138271996153856 +1662138272038154752 +1662138272080155648 +1662138272125156608 +1662138272173157632 +1662138272215158528 +1662138272260159488 +1662138272305160448 +1662138272347161344 +1662138272389162240 +1662138272434163200 +1662138272485164288 +1662138272530165248 +1662138272572166144 +1662138272614167040 +1662138272659168000 +1662138272716169216 +1662138272758170112 +1662138272803171072 +1662138272848172032 +1662138272893172992 +1662138272935173888 +1662138272983174912 +1662138273028175872 +1662138273070176768 +1662138273118177792 +1662138273172178944 +1662138273217179904 +1662138273265180928 +1662138273313181952 +1662138273358182912 +1662138273406183936 +1662138273448184832 +1662138273490185728 +1662138273538186752 +1662138273583187712 +1662138273634188800 +1662138273676189696 +1662138273721190656 +1662138273766191616 +1662138273808192512 +1662138273850193408 +1662138273892194304 +1662138273931195136 +1662138273970195968 +1662138274012196864 +1662138274057197824 +1662138274099198720 +1662138274141199616 +1662138274183200512 +1662138274231201536 +1662138274279202560 +1662138274324203520 +1662138274372204544 +1662138274414205440 +1662138274459206400 +1662138274501207296 +1662138274549208320 +1662138274591209216 +1662138274633210112 +1662138274681211136 +1662138274729212160 +1662138274771213056 +1662138274813213952 +1662138274855214848 +1662138274897215744 +1662138274939216640 +1662138274981217536 +1662138275026218496 +1662138275071219456 +1662138275113220352 +1662138275155221248 +1662138275197222144 +1662138275242223104 +1662138275287224064 +1662138275332225024 +1662138275380226048 +1662138275425227008 +1662138275473228032 +1662138275518228992 +1662138275563229952 +1662138275602230784 +1662138275647231744 +1662138275689232640 +1662138275734233600 +1662138275776234496 +1662138275821235456 +1662138275863236352 +1662138275905237248 +1662138275953238272 +1662138275998239232 +1662138276040240128 +1662138276085241088 +1662138276133242112 +1662138276178243072 +1662138276220243968 +1662138276265244928 +1662138276307245824 +1662138276355246848 +1662138276394247680 +1662138276445248768 +1662138276487249664 +1662138276529250560 +1662138276577251584 +1662138276622252544 +1662138276673253632 +1662138276718254592 +1662138276760255488 +1662138276802256384 +1662138276850257408 +1662138276892258304 +1662138276940259328 +1662138276982260224 +1662138277030261248 +1662138277072262144 +1662138277120263168 +1662138277165264128 +1662138277210265088 +1662138277252265984 +1662138277303267072 +1662138277342267904 +1662138277384268800 +1662138277423269632 +1662138277465270528 +1662138277507271424 +1662138277555272448 +1662138277600273408 +1662138277645274368 +1662138277696275456 +1662138277741276416 +1662138277783277312 +1662138277825278208 +1662138277864279040 +1662138277906279936 +1662138277951280896 +1662138277999281920 +1662138278044282880 +1662138278086283776 +1662138278125284608 +1662138278179285760 +1662138278224286720 +1662138278266287616 +1662138278308288512 +1662138278350289408 +1662138278398290432 +1662138278443291392 +1662138278485292288 +1662138278524293120 +1662138278566294016 +1662138278608294912 +1662138278662296064 +1662138278710297088 +1662138278752297984 +1662138278800299008 +1662138278845299968 +1662138278887300864 +1662138278929301760 +1662138278971302656 +1662138279016303616 +1662138279058304512 +1662138279100305408 +1662138279151306496 +1662138279196307456 +1662138279244308480 +1662138279295309568 +1662138279343310592 +1662138279385311488 +1662138279430312448 +1662138279475313408 +1662138279526314496 +1662138279571315456 +1662138279634316800 +1662138279673317632 +1662138279721318656 +1662138279766319616 +1662138279820320768 +1662138279862321664 +1662138279907322624 +1662138279952323584 +1662138279994324480 +1662138280039325440 +1662138280081326336 +1662138280126327296 +1662138280174328320 +1662138280222329344 +1662138280264330240 +1662138280306331136 +1662138280348332032 +1662138280390332928 +1662138280438333952 +1662138280483334912 +1662138280525335808 +1662138280567336704 +1662138280615337728 +1662138280663338752 +1662138280705339648 +1662138280747340544 +1662138280792341504 +1662138280834342400 +1662138280879343360 +1662138280921344256 +1662138280966345216 +1662138281011346176 +1662138281056347136 +1662138281104348160 +1662138281152349184 +1662138281194350080 +1662138281242351104 +1662138281287352064 +1662138281338353152 +1662138281380354048 +1662138281419354880 +1662138281461355776 +1662138281503356672 +1662138281557357824 +1662138281599358720 +1662138281644359680 +1662138281689360640 +1662138281731361536 +1662138281782362624 +1662138281824363520 +1662138281878364672 +1662138281926365696 +1662138281971366656 +1662138282022367744 +1662138282064368640 +1662138282106369536 +1662138282148370432 +1662138282190371328 +1662138282232372224 +1662138282271373056 +1662138282313373952 +1662138282352374784 +1662138282397375744 +1662138282442376704 +1662138282484377600 +1662138282532378624 +1662138282574379520 +1662138282619380480 +1662138282661381376 +1662138282703382272 +1662138282745383168 +1662138282787384064 +1662138282829384960 +1662138282889386240 +1662138282934387200 +1662138282976388096 +1662138283024389120 +1662138283066390016 +1662138283108390912 +1662138283153391872 +1662138283195392768 +1662138283237393664 +1662138283279394560 +1662138283330395648 +1662138283375396608 +1662138283426397696 +1662138283477398784 +1662138283519399680 +1662138283561400576 +1662138283603401472 +1662138283645402368 +1662138283687403264 +1662138283729404160 +1662138283768404992 +1662138283810405888 +1662138283855406848 +1662138283900407808 +1662138283942408704 +1662138283987409664 +1662138284032410624 +1662138284077411584 +1662138284122412544 +1662138284167413504 +1662138284212414464 +1662138284254415360 +1662138284302416384 +1662138284350417408 +1662138284404418560 +1662138284446419456 +1662138284488420352 +1662138284536421376 +1662138284584422400 +1662138284626423296 +1662138284668424192 +1662138284728425472 +1662138284770426368 +1662138284812427264 +1662138284854428160 +1662138284896429056 +1662138284941430016 +1662138284992431104 +1662138285037432064 +1662138285082433024 +1662138285130434048 +1662138285178435072 +1662138285229436160 +1662138285271437056 +1662138285319438080 +1662138285370439168 +1662138285418440192 +1662138285460441088 +1662138285502441984 +1662138285550443008 +1662138285601444096 +1662138285655445248 +1662138285694446080 +1662138285742447104 +1662138285784448000 +1662138285826448896 +1662138285880450048 +1662138285928451072 +1662138285970451968 +1662138286012452864 +1662138286057453824 +1662138286108454912 +1662138286165456128 +1662138286207457024 +1662138286249457920 +1662138286297458944 +1662138286342459904 +1662138286390460928 +1662138286435461888 +1662138286480462848 +1662138286519463680 +1662138286564464640 +1662138286609465600 +1662138286660466688 +1662138286711467776 +1662138286756468736 +1662138286804469760 +1662138286852470784 +1662138286891471616 +1662138286933472512 +1662138286975473408 +1662138287020474368 +1662138287071475456 +1662138287113476352 +1662138287152477184 +1662138287197478144 +1662138287239479040 +1662138287281479936 +1662138287320480768 +1662138287362481664 +1662138287416482816 +1662138287458483712 +1662138287500484608 +1662138287545485568 +1662138287587486464 +1662138287629487360 +1662138287677488384 +1662138287719489280 +1662138287761490176 +1662138287806491136 +1662138287851492096 +1662138287893492992 +1662138287938493952 +1662138287983494912 +1662138288025495808 +1662138288067496704 +1662138288118497792 +1662138288157498624 +1662138288199499520 +1662138288238500352 +1662138288283501312 +1662138288325502208 +1662138288373503232 +1662138288418504192 +1662138288460505088 +1662138288502505984 +1662138288547506944 +1662138288592507904 +1662138288634508800 +1662138288676509696 +1662138288718510592 +1662138288763511552 +1662138288814512640 +1662138288856513536 +1662138288898514432 +1662138288940515328 +1662138288985516288 +1662138289027517184 +1662138289075518208 +1662138289117519104 +1662138289159520000 +1662138289201520896 +1662138289246521856 +1662138289291522816 +1662138289336523776 +1662138289384524800 +1662138289435525888 +1662138289480526848 +1662138289528527872 +1662138289576528896 +1662138289621529856 +1662138289663530752 +1662138289711531776 +1662138289759532800 +1662138289810533888 +1662138289852534784 +1662138289897535744 +1662138289942536704 +1662138289981537536 +1662138290026538496 +1662138290068539392 +1662138290122540544 +1662138290167541504 +1662138290215542528 +1662138290260543488 +1662138290302544384 +1662138290350545408 +1662138290392546304 +1662138290446547456 +1662138290494548480 +1662138290539549440 +1662138290584550400 +1662138290626551296 +1662138290674552320 +1662138290725553408 +1662138290767554304 +1662138290815555328 +1662138290857556224 +1662138290899557120 +1662138290944558080 +1662138290995559168 +1662138291037560064 +1662138291082561024 +1662138291124561920 +1662138291166562816 +1662138291208563712 +1662138291253564672 +1662138291304565760 +1662138291352566784 +1662138291394567680 +1662138291439568640 +1662138291484569600 +1662138291532570624 +1662138291574571520 +1662138291622572544 +1662138291667573504 +1662138291712574464 +1662138291760575488 +1662138291802576384 +1662138291844577280 +1662138291889578240 +1662138291931579136 +1662138291979580160 +1662138292021581056 +1662138292063581952 +1662138292105582848 +1662138292147583744 +1662138292198584832 +1662138292243585792 +1662138292288586752 +1662138292333587712 +1662138292378588672 +1662138292429589760 +1662138292471590656 +1662138292510591488 +1662138292552592384 +1662138292597593344 +1662138292645594368 +1662138292687595264 +1662138292726596096 +1662138292768596992 +1662138292813597952 +1662138292861598976 +1662138292903599872 +1662138292948600832 +1662138292990601728 +1662138293032602624 +1662138293077603584 +1662138293125604608 +1662138293170605568 +1662138293218606592 +1662138293266607616 +1662138293311608576 +1662138293359609600 +1662138293404610560 +1662138293446611456 +1662138293488612352 +1662138293533613312 +1662138293581614336 +1662138293623615232 +1662138293665616128 +1662138293710617088 +1662138293755618048 +1662138293800619008 +1662138293845619968 +1662138293887620864 +1662138293929621760 +1662138293989623040 +1662138294037624064 +1662138294085625088 +1662138294127625984 +1662138294172626944 +1662138294214627840 +1662138294265628928 +1662138294307629824 +1662138294349630720 +1662138294394631680 +1662138294436632576 +1662138294481633536 +1662138294526634496 +1662138294574635520 +1662138294619636480 +1662138294661637376 +1662138294706638336 +1662138294751639296 +1662138294796640256 +1662138294841641216 +1662138294886642176 +1662138294931643136 +1662138294973644032 +1662138295018644992 +1662138295063645952 +1662138295105646848 +1662138295153647872 +1662138295195648768 +1662138295246649856 +1662138295288650752 +1662138295339651840 +1662138295384652800 +1662138295426653696 +1662138295480654848 +1662138295531655936 +1662138295573656832 +1662138295618657792 +1662138295663658752 +1662138295708659712 +1662138295765660928 +1662138295810661888 +1662138295852662784 +1662138295897663744 +1662138295936664576 +1662138295975665408 +1662138296026666496 +1662138296068667392 +1662138296110668288 +1662138296155669248 +1662138296200670208 +1662138296242671104 +1662138296284672000 +1662138296329672960 +1662138296380674048 +1662138296419674880 +1662138296470675968 +1662138296512676864 +1662138296554677760 +1662138296602678784 +1662138296644679680 +1662138296686680576 +1662138296737681664 +1662138296779682560 +1662138296821683456 +1662138296872684544 +1662138296917685504 +1662138296959686400 +1662138297016687616 +1662138297061688576 +1662138297109689600 +1662138297154690560 +1662138297193691392 +1662138297235692288 +1662138297289693440 +1662138297337694464 +1662138297382695424 +1662138297424696320 +1662138297466697216 +1662138297508698112 +1662138297559699200 +1662138297601700096 +1662138297646701056 +1662138297697702144 +1662138297742703104 +1662138297784704000 +1662138297823704832 +1662138297862705664 +1662138297901706496 +1662138297952707584 +1662138298000708608 +1662138298045709568 +1662138298090710528 +1662138298141711616 +1662138298183712512 +1662138298225713408 +1662138298270714368 +1662138298315715328 +1662138298360716288 +1662138298405717248 +1662138298447718144 +1662138298492719104 +1662138298534720000 +1662138298576720896 +1662138298618721792 +1662138298660722688 +1662138298702723584 +1662138298744724480 +1662138298798725632 +1662138298840726528 +1662138298888727552 +1662138298936728576 +1662138298981729536 +1662138299023730432 +1662138299065731328 +1662138299107732224 +1662138299155733248 +1662138299197734144 +1662138299239735040 +1662138299287736064 +1662138299329736960 +1662138299374737920 +1662138299428739072 +1662138299479740160 +1662138299527741184 +1662138299578742272 +1662138299620743168 +1662138299662744064 +1662138299707745024 +1662138299749745920 +1662138299803747072 +1662138299848748032 +1662138299902749184 +1662138299944750080 +1662138299986750976 +1662138300028751872 +1662138300073752832 +1662138300118753792 +1662138300160754688 +1662138300199755520 +1662138300241756416 +1662138300286757376 +1662138300331758336 +1662138300373759232 +1662138300421760256 +1662138300463761152 +1662138300505762048 +1662138300559763200 +1662138300601764096 +1662138300643764992 +1662138300691766016 +1662138300730766848 +1662138300781767936 +1662138300823768832 +1662138300865769728 +1662138300904770560 +1662138300949771520 +1662138300997772544 +1662138301039773440 +1662138301087774464 +1662138301129775360 +1662138301174776320 +1662138301222777344 +1662138301264778240 +1662138301306779136 +1662138301351780096 +1662138301399781120 +1662138301441782016 +1662138301489783040 +1662138301531783936 +1662138301573784832 +1662138301621785856 +1662138301666786816 +1662138301708787712 +1662138301753788672 +1662138301795789568 +1662138301837790464 +1662138301879791360 +1662138301927792384 +1662138301978793472 +1662138302023794432 +1662138302065795328 +1662138302116796416 +1662138302167797504 +1662138302215798528 +1662138302266799616 +1662138302308800512 +1662138302356801536 +1662138302398802432 +1662138302446803456 +1662138302488804352 +1662138302533805312 +1662138302587806464 +1662138302629807360 +1662138302671808256 +1662138302713809152 +1662138302758810112 +1662138302803811072 +1662138302851812096 +1662138302896813056 +1662138302938813952 +1662138302983814912 +1662138303025815808 +1662138303073816832 +1662138303118817792 +1662138303163818752 +1662138303208819712 +1662138303256820736 +1662138303298821632 +1662138303340822528 +1662138303391823616 +1662138303439824640 +1662138303487825664 +1662138303532826624 +1662138303577827584 +1662138303625828608 +1662138303667829504 +1662138303709830400 +1662138303754831360 +1662138303799832320 +1662138303844833280 +1662138303886834176 +1662138303937835264 +1662138303982836224 +1662138304024837120 +1662138304066838016 +1662138304114839040 +1662138304171840256 +1662138304213841152 +1662138304264842240 +1662138304309843200 +1662138304357844224 +1662138304405845248 +1662138304450846208 +1662138304492847104 +1662138304540848128 +1662138304585849088 +1662138304627849984 +1662138304675851008 +1662138304720851968 +1662138304765852928 +1662138304813853952 +1662138304855854848 +1662138304903855872 +1662138304948856832 +1662138304999857920 +1662138305047858944 +1662138305089859840 +1662138305140860928 +1662138305194862080 +1662138305239863040 +1662138305278863872 +1662138305326864896 +1662138305374865920 +1662138305419866880 +1662138305461867776 +1662138305509868800 +1662138305557869824 +1662138305599870720 +1662138305647871744 +1662138305689872640 +1662138305734873600 +1662138305776874496 +1662138305830875648 +1662138305878876672 +1662138305929877760 +1662138305974878720 +1662138306019879680 +1662138306073880832 +1662138306115881728 +1662138306160882688 +1662138306202883584 +1662138306250884608 +1662138306292885504 +1662138306334886400 +1662138306376887296 +1662138306421888256 +1662138306463889152 +1662138306505890048 +1662138306565891328 +1662138306610892288 +1662138306652893184 +1662138306694894080 +1662138306742895104 +1662138306787896064 +1662138306838897152 +1662138306880898048 +1662138306925899008 +1662138306970899968 +1662138307021901056 +1662138307060901888 +1662138307105902848 +1662138307147903744 +1662138307192904704 +1662138307237905664 +1662138307288906752 +1662138307327907584 +1662138307375908608 +1662138307420909568 +1662138307468910592 +1662138307516911616 +1662138307561912576 +1662138307612913664 +1662138307654914560 +1662138307705915648 +1662138307753916672 +1662138307801917696 +1662138307852918784 +1662138307900919808 +1662138307948920832 +1662138307990921728 +1662138308032922624 +1662138308080923648 +1662138308125924608 +1662138308176925696 +1662138308221926656 +1662138308266927616 +1662138308308928512 +1662138308356929536 +1662138308401930496 +1662138308446931456 +1662138308494932480 +1662138308545933568 +1662138308584934400 +1662138308623935232 +1662138308668936192 +1662138308713937152 +1662138308758938112 +1662138308800939008 +1662138308845939968 +1662138308887940864 +1662138308929941760 +1662138308980942848 +1662138309022943744 +1662138309064944640 +1662138309109945600 +1662138309157946624 +1662138309205947648 +1662138309256948736 +1662138309301949696 +1662138309352950784 +1662138309397951744 +1662138309442952704 +1662138309493953792 +1662138309535954688 +1662138309583955712 +1662138309634956800 +1662138309676957696 +1662138309718958592 +1662138309763959552 +1662138309805960448 +1662138309859961600 +1662138309907962624 +1662138309949963520 +1662138310006964736 +1662138310048965632 +1662138310090966528 +1662138310138967552 +1662138310183968512 +1662138310225969408 +1662138310282970624 +1662138310321971456 +1662138310363972352 +1662138310411973376 +1662138310456974336 +1662138310501975296 +1662138310552976384 +1662138310594977280 +1662138310639978240 +1662138310684979200 +1662138310729980160 +1662138310771981056 +1662138310819982080 +1662138310861982976 +1662138310909984000 +1662138310960985088 +1662138311011986176 +1662138311065987328 +1662138311110988288 +1662138311152989184 +1662138311194990080 +1662138311239991040 +1662138311284992000 +1662138311332993024 +1662138311380994048 +1662138311428995072 +1662138311479996160 +1662138311530997248 +1662138311578998272 +1662138311623999232 +1662138311675000320 +1662138311717001216 +1662138311759002112 +1662138311804003072 +1662138311855004160 +1662138311906005248 +1662138311951006208 +1662138311993007104 +1662138312044008192 +1662138312089009152 +1662138312134010112 +1662138312179011072 +1662138312224012032 +1662138312266012928 +1662138312314013952 +1662138312362014976 +1662138312407015936 +1662138312449016832 +1662138312497017856 +1662138312536018688 +1662138312593019904 +1662138312638020864 +1662138312686021888 +1662138312731022848 +1662138312782023936 +1662138312830024960 +1662138312878025984 +1662138312920026880 +1662138312962027776 +1662138313010028800 +1662138313064029952 +1662138313112030976 +1662138313163032064 +1662138313208033024 +1662138313253033984 +1662138313301035008 +1662138313343035904 +1662138313388036864 +1662138313427037696 +1662138313472038656 +1662138313517039616 +1662138313565040640 +1662138313610041600 +1662138313658042624 +1662138313703043584 +1662138313748044544 +1662138313787045376 +1662138313841046528 +1662138313886047488 +1662138313931048448 +1662138313976049408 +1662138314021050368 +1662138314063051264 +1662138314111052288 +1662138314156053248 +1662138314201054208 +1662138314258055424 +1662138314303056384 +1662138314345057280 +1662138314387058176 +1662138314432059136 +1662138314474060032 +1662138314516060928 +1662138314564061952 +1662138314612062976 +1662138314657063936 +1662138314696064768 +1662138314738065664 +1662138314783066624 +1662138314783066624 +1662138314828067584 +1662138314873068544 +1662138314915069440 +1662138314957070336 +1662138314999071232 +1662138315041072128 +1662138315080072960 +1662138315128073984 +1662138315176075008 +1662138315224076032 +1662138315269076992 +1662138315317078016 +1662138315362078976 +1662138315410080000 +1662138315461081088 +1662138315509082112 +1662138315551083008 +1662138315599084032 +1662138315641084928 +1662138315683085824 +1662138315728086784 +1662138315770087680 +1662138315815088640 +1662138315854089472 +1662138315905090560 +1662138315947091456 +1662138315992092416 +1662138316037093376 +1662138316082094336 +1662138316133095424 +1662138316178096384 +1662138316223097344 +1662138316265098240 +1662138316310099200 +1662138316358100224 +1662138316397101056 +1662138316442102016 +1662138316493103104 +1662138316538104064 +1662138316583105024 +1662138316625105920 +1662138316676107008 +1662138316727108096 +1662138316772109056 +1662138316814109952 +1662138316859110912 +1662138316901111808 +1662138316946112768 +1662138316994113792 +1662138317036114688 +1662138317081115648 +1662138317123116544 +1662138317165117440 diff --git a/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_light.txt b/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_light.txt new file mode 100644 index 0000000000..cca6f70bc4 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_light.txt @@ -0,0 +1,2421 @@ +1662135911410189568 +1662135911452190464 +1662135911491191296 +1662135911539192320 +1662135911584193280 +1662135911638194432 +1662135911683195392 +1662135911731196416 +1662135911776197376 +1662135911824198400 +1662135911866199296 +1662135911908200192 +1662135911953201152 +1662135912001202176 +1662135912052203264 +1662135912094204160 +1662135912136205056 +1662135912181206016 +1662135912232207104 +1662135912280208128 +1662135912322209024 +1662135912370210048 +1662135912412210944 +1662135912454211840 +1662135912496212736 +1662135912538213632 +1662135912583214592 +1662135912625215488 +1662135912667216384 +1662135912712217344 +1662135912754218240 +1662135912796219136 +1662135912844220160 +1662135912889221120 +1662135912928221952 +1662135912970222848 +1662135913015223808 +1662135913057224704 +1662135913108225792 +1662135913159226880 +1662135913210227968 +1662135913249228800 +1662135913306230016 +1662135913351230976 +1662135913396231936 +1662135913441232896 +1662135913492233984 +1662135913540235008 +1662135913585235968 +1662135913639237120 +1662135913681238016 +1662135913729239040 +1662135913774240000 +1662135913825241088 +1662135913867241984 +1662135913909242880 +1662135913951243776 +1662135913993244672 +1662135914041245696 +1662135914086246656 +1662135914131247616 +1662135914173248512 +1662135914218249472 +1662135914260250368 +1662135914302251264 +1662135914350252288 +1662135914392253184 +1662135914437254144 +1662135914491255296 +1662135914530256128 +1662135914569256960 +1662135914611257856 +1662135914653258752 +1662135914698259712 +1662135914740260608 +1662135914782261504 +1662135914824262400 +1662135914866263296 +1662135914908264192 +1662135914953265152 +1662135914998266112 +1662135915046267136 +1662135915091268096 +1662135915136269056 +1662135915181270016 +1662135915223270912 +1662135915277272064 +1662135915325273088 +1662135915364273920 +1662135915415275008 +1662135915457275904 +1662135915499276800 +1662135915544277760 +1662135915586278656 +1662135915628279552 +1662135915676280576 +1662135915718281472 +1662135915772282624 +1662135915811283456 +1662135915853284352 +1662135915907285504 +1662135915949286400 +1662135915994287360 +1662135916039288320 +1662135916093289472 +1662135916135290368 +1662135916177291264 +1662135916222292224 +1662135916267293184 +1662135916309294080 +1662135916351294976 +1662135916393295872 +1662135916438296832 +1662135916486297856 +1662135916531298816 +1662135916573299712 +1662135916621300736 +1662135916669301760 +1662135916714302720 +1662135916759303680 +1662135916807304704 +1662135916849305600 +1662135916891306496 +1662135916933307392 +1662135916984308480 +1662135917035309568 +1662135917080310528 +1662135917125311488 +1662135917167312384 +1662135917212313344 +1662135917257314304 +1662135917311315456 +1662135917356316416 +1662135917395317248 +1662135917437318144 +1662135917482319104 +1662135917524320000 +1662135917569320960 +1662135917623322112 +1662135917668323072 +1662135917716324096 +1662135917758324992 +1662135917800325888 +1662135917839326720 +1662135917887327744 +1662135917929328640 +1662135917971329536 +1662135918013330432 +1662135918052331264 +1662135918094332160 +1662135918136333056 +1662135918178333952 +1662135918220334848 +1662135918262335744 +1662135918307336704 +1662135918361337856 +1662135918406338816 +1662135918448339712 +1662135918508340992 +1662135918550341888 +1662135918592342784 +1662135918643343872 +1662135918685344768 +1662135918733345792 +1662135918775346688 +1662135918817347584 +1662135918856348416 +1662135918898349312 +1662135918946350336 +1662135918994351360 +1662135919036352256 +1662135919078353152 +1662135919120354048 +1662135919159354880 +1662135919201355776 +1662135919246356736 +1662135919294357760 +1662135919342358784 +1662135919387359744 +1662135919429360640 +1662135919474361600 +1662135919513362432 +1662135919555363328 +1662135919597364224 +1662135919645365248 +1662135919690366208 +1662135919732367104 +1662135919774368000 +1662135919816368896 +1662135919861369856 +1662135919906370816 +1662135919951371776 +1662135920005372928 +1662135920047373824 +1662135920095374848 +1662135920140375808 +1662135920185376768 +1662135920230377728 +1662135920272378624 +1662135920314379520 +1662135920356380416 +1662135920398381312 +1662135920440382208 +1662135920488383232 +1662135920536384256 +1662135920578385152 +1662135920617385984 +1662135920659386880 +1662135920704387840 +1662135920749388800 +1662135920797389824 +1662135920851390976 +1662135920896391936 +1662135920941392896 +1662135920983393792 +1662135921025394688 +1662135921070395648 +1662135921115396608 +1662135921154397440 +1662135921196398336 +1662135921250399488 +1662135921292400384 +1662135921358401792 +1662135921406402816 +1662135921448403712 +1662135921496404736 +1662135921544405760 +1662135921595406848 +1662135921640407808 +1662135921685408768 +1662135921724409600 +1662135921775410688 +1662135921823411712 +1662135921865412608 +1662135921907413504 +1662135921952414464 +1662135921997415424 +1662135922039416320 +1662135922081417216 +1662135922123418112 +1662135922165419008 +1662135922207419904 +1662135922249420800 +1662135922300421888 +1662135922345422848 +1662135922390423808 +1662135922435424768 +1662135922480425728 +1662135922522426624 +1662135922567427584 +1662135922609428480 +1662135922654429440 +1662135922705430528 +1662135922750431488 +1662135922792432384 +1662135922840433408 +1662135922897434624 +1662135922942435584 +1662135922987436544 +1662135923029437440 +1662135923071438336 +1662135923113439232 +1662135923155440128 +1662135923203441152 +1662135923245442048 +1662135923284442880 +1662135923326443776 +1662135923365444608 +1662135923407445504 +1662135923449446400 +1662135923491447296 +1662135923533448192 +1662135923578449152 +1662135923620450048 +1662135923674451200 +1662135923716452096 +1662135923758452992 +1662135923800453888 +1662135923848454912 +1662135923890455808 +1662135923932456704 +1662135923983457792 +1662135924025458688 +1662135924079459840 +1662135924121460736 +1662135924163461632 +1662135924208462592 +1662135924268463872 +1662135924310464768 +1662135924355465728 +1662135924394466560 +1662135924436467456 +1662135924481468416 +1662135924532469504 +1662135924577470464 +1662135924616471296 +1662135924667472384 +1662135924709473280 +1662135924751474176 +1662135924793475072 +1662135924835475968 +1662135924883476992 +1662135924925477888 +1662135924973478912 +1662135925015479808 +1662135925057480704 +1662135925099481600 +1662135925147482624 +1662135925186483456 +1662135925228484352 +1662135925273485312 +1662135925315486208 +1662135925360487168 +1662135925408488192 +1662135925453489152 +1662135925495490048 +1662135925540491008 +1662135925582491904 +1662135925624492800 +1662135925663493632 +1662135925708494592 +1662135925750495488 +1662135925798496512 +1662135925846497536 +1662135925888498432 +1662135925930499328 +1662135925987500544 +1662135926035501568 +1662135926077502464 +1662135926122503424 +1662135926164504320 +1662135926209505280 +1662135926263506432 +1662135926311507456 +1662135926353508352 +1662135926401509376 +1662135926449510400 +1662135926488511232 +1662135926530512128 +1662135926578513152 +1662135926620514048 +1662135926665515008 +1662135926707515904 +1662135926749516800 +1662135926791517696 +1662135926833518592 +1662135926875519488 +1662135926914520320 +1662135926959521280 +1662135927001522176 +1662135927055523328 +1662135927097524224 +1662135927148525312 +1662135927199526400 +1662135927238527232 +1662135927280528128 +1662135927322529024 +1662135927367529984 +1662135927406530816 +1662135927445531648 +1662135927487532544 +1662135927538533632 +1662135927580534528 +1662135927622535424 +1662135927664536320 +1662135927709537280 +1662135927760538368 +1662135927802539264 +1662135927850540288 +1662135927892541184 +1662135927937542144 +1662135927988543232 +1662135928030544128 +1662135928075545088 +1662135928120546048 +1662135928162546944 +1662135928207547904 +1662135928255548928 +1662135928303549952 +1662135928345550848 +1662135928393551872 +1662135928435552768 +1662135928477553664 +1662135928519554560 +1662135928561555456 +1662135928603556352 +1662135928645557248 +1662135928687558144 +1662135928729559040 +1662135928774560000 +1662135928822561024 +1662135928864561920 +1662135928912562944 +1662135928954563840 +1662135929002564864 +1662135929041565696 +1662135929083566592 +1662135929125567488 +1662135929167568384 +1662135929212569344 +1662135929257570304 +1662135929299571200 +1662135929341572096 +1662135929386573056 +1662135929428573952 +1662135929467574784 +1662135929512575744 +1662135929566576896 +1662135929608577792 +1662135929659578880 +1662135929707579904 +1662135929749580800 +1662135929800581888 +1662135929842582784 +1662135929884583680 +1662135929926584576 +1662135929968585472 +1662135930010586368 +1662135930061587456 +1662135930103588352 +1662135930154589440 +1662135930199590400 +1662135930241591296 +1662135930283592192 +1662135930328593152 +1662135930367593984 +1662135930415595008 +1662135930460595968 +1662135930511597056 +1662135930553597952 +1662135930598598912 +1662135930640599808 +1662135930685600768 +1662135930730601728 +1662135930778602752 +1662135930820603648 +1662135930865604608 +1662135930907605504 +1662135930952606464 +1662135930997607424 +1662135931039608320 +1662135931081609216 +1662135931135610368 +1662135931180611328 +1662135931222612224 +1662135931270613248 +1662135931321614336 +1662135931372615424 +1662135931420616448 +1662135931465617408 +1662135931507618304 +1662135931549619200 +1662135931591620096 +1662135931639621120 +1662135931684622080 +1662135931726622976 +1662135931774624000 +1662135931819624960 +1662135931870626048 +1662135931912626944 +1662135931960627968 +1662135932002628864 +1662135932065630208 +1662135932107631104 +1662135932149632000 +1662135932209633280 +1662135932254634240 +1662135932299635200 +1662135932350636288 +1662135932392637184 +1662135932434638080 +1662135932482639104 +1662135932524640000 +1662135932566640896 +1662135932608641792 +1662135932650642688 +1662135932695643648 +1662135932743644672 +1662135932785645568 +1662135932830646528 +1662135932875647488 +1662135932917648384 +1662135932959649280 +1662135933004650240 +1662135933049651200 +1662135933091652096 +1662135933133652992 +1662135933178653952 +1662135933223654912 +1662135933268655872 +1662135933310656768 +1662135933358657792 +1662135933403658752 +1662135933454659840 +1662135933499660800 +1662135933541661696 +1662135933589662720 +1662135933631663616 +1662135933679664640 +1662135933718665472 +1662135933757666304 +1662135933802667264 +1662135933853668352 +1662135933898669312 +1662135933940670208 +1662135933979671040 +1662135934024672000 +1662135934066672896 +1662135934111673856 +1662135934156674816 +1662135934210675968 +1662135934255676928 +1662135934297677824 +1662135934345678848 +1662135934387679744 +1662135934429680640 +1662135934468681472 +1662135934513682432 +1662135934555683328 +1662135934600684288 +1662135934642685184 +1662135934684686080 +1662135934729687040 +1662135934771687936 +1662135934816688896 +1662135934858689792 +1662135934900690688 +1662135934942691584 +1662135934990692608 +1662135935032693504 +1662135935077694464 +1662135935119695360 +1662135935158696192 +1662135935209697280 +1662135935251698176 +1662135935293699072 +1662135935344700160 +1662135935389701120 +1662135935431702016 +1662135935482703104 +1662135935524704000 +1662135935572705024 +1662135935620706048 +1662135935668707072 +1662135935713708032 +1662135935758708992 +1662135935803709952 +1662135935845710848 +1662135935887711744 +1662135935932712704 +1662135935974713600 +1662135936019714560 +1662135936067715584 +1662135936106716416 +1662135936154717440 +1662135936196718336 +1662135936235719168 +1662135936277720064 +1662135936325721088 +1662135936367721984 +1662135936415723008 +1662135936457723904 +1662135936499724800 +1662135936544725760 +1662135936592726784 +1662135936631727616 +1662135936679728640 +1662135936727729664 +1662135936772730624 +1662135936814731520 +1662135936856732416 +1662135936907733504 +1662135936949734400 +1662135936997735424 +1662135937045736448 +1662135937093737472 +1662135937135738368 +1662135937180739328 +1662135937222740224 +1662135937267741184 +1662135937306742016 +1662135937351742976 +1662135937396743936 +1662135937435744768 +1662135937477745664 +1662135937522746624 +1662135937567747584 +1662135937609748480 +1662135937660749568 +1662135937705750528 +1662135937756751616 +1662135937804752640 +1662135937846753536 +1662135937903754752 +1662135937942755584 +1662135937984756480 +1662135938032757504 +1662135938071758336 +1662135938119759360 +1662135938161760256 +1662135938212761344 +1662135938254762240 +1662135938308763392 +1662135938350764288 +1662135938395765248 +1662135938452766464 +1662135938500767488 +1662135938539768320 +1662135938584769280 +1662135938629770240 +1662135938671771136 +1662135938716772096 +1662135938764773120 +1662135938815774208 +1662135938863775232 +1662135938905776128 +1662135938953777152 +1662135939001778176 +1662135939043779072 +1662135939094780160 +1662135939142781184 +1662135939187782144 +1662135939235783168 +1662135939274784000 +1662135939322785024 +1662135939367785984 +1662135939409786880 +1662135939460787968 +1662135939502788864 +1662135939541789696 +1662135939592790784 +1662135939637791744 +1662135939688792832 +1662135939736793856 +1662135939778794752 +1662135939820795648 +1662135939865796608 +1662135939919797760 +1662135939961798656 +1662135940006799616 +1662135940045800448 +1662135940093801472 +1662135940135802368 +1662135940180803328 +1662135940228804352 +1662135940282805504 +1662135940327806464 +1662135940372807424 +1662135940426808576 +1662135940468809472 +1662135940510810368 +1662135940552811264 +1662135940603812352 +1662135940642813184 +1662135940681814016 +1662135940723814912 +1662135940765815808 +1662135940807816704 +1662135940849817600 +1662135940888818432 +1662135940930819328 +1662135940978820352 +1662135941023821312 +1662135941065822208 +1662135941107823104 +1662135941149824000 +1662135941188824832 +1662135941233825792 +1662135941281826816 +1662135941323827712 +1662135941365828608 +1662135941413829632 +1662135941455830528 +1662135941500831488 +1662135941542832384 +1662135941581833216 +1662135941623834112 +1662135941665835008 +1662135941707835904 +1662135941746836736 +1662135941791837696 +1662135941833838592 +1662135941878839552 +1662135941929840640 +1662135941977841664 +1662135942025842688 +1662135942061843456 +1662135942103844352 +1662135942145845248 +1662135942199846400 +1662135942247847424 +1662135942292848384 +1662135942334849280 +1662135942388850432 +1662135942433851392 +1662135942478852352 +1662135942520853248 +1662135942562854144 +1662135942613855232 +1662135942658856192 +1662135942700857088 +1662135942751858176 +1662135942793859072 +1662135942835859968 +1662135942883860992 +1662135942925861888 +1662135942967862784 +1662135943006863616 +1662135943048864512 +1662135943093865472 +1662135943138866432 +1662135943186867456 +1662135943234868480 +1662135943276869376 +1662135943321870336 +1662135943369871360 +1662135943408872192 +1662135943456873216 +1662135943501874176 +1662135943543875072 +1662135943582875904 +1662135943627876864 +1662135943669877760 +1662135943720878848 +1662135943762879744 +1662135943804880640 +1662135943849881600 +1662135943894882560 +1662135943945883648 +1662135943996884736 +1662135944038885632 +1662135944083886592 +1662135944134887680 +1662135944182888704 +1662135944224889600 +1662135944275890688 +1662135944317891584 +1662135944362892544 +1662135944410893568 +1662135944452894464 +1662135944497895424 +1662135944551896576 +1662135944593897472 +1662135944635898368 +1662135944680899328 +1662135944731900416 +1662135944776901376 +1662135944824902400 +1662135944878903552 +1662135944923904512 +1662135944965905408 +1662135945010906368 +1662135945058907392 +1662135945100908288 +1662135945142909184 +1662135945190910208 +1662135945235911168 +1662135945289912320 +1662135945331913216 +1662135945376914176 +1662135945421915136 +1662135945466916096 +1662135945508916992 +1662135945550917888 +1662135945595918848 +1662135945634919680 +1662135945679920640 +1662135945727921664 +1662135945775922688 +1662135945817923584 +1662135945862924544 +1662135945904925440 +1662135945949926400 +1662135945991927296 +1662135946036928256 +1662135946081929216 +1662135946123930112 +1662135946165931008 +1662135946216932096 +1662135946261933056 +1662135946306934016 +1662135946351934976 +1662135946393935872 +1662135946438936832 +1662135946477937664 +1662135946519938560 +1662135946564939520 +1662135946609940480 +1662135946651941376 +1662135946690942208 +1662135946735943168 +1662135946783944192 +1662135946825945088 +1662135946867945984 +1662135946918947072 +1662135946963948032 +1662135947005948928 +1662135947047949824 +1662135947095950848 +1662135947134951680 +1662135947188952832 +1662135947236953856 +1662135947278954752 +1662135947320955648 +1662135947368956672 +1662135947410957568 +1662135947452958464 +1662135947494959360 +1662135947539960320 +1662135947578961152 +1662135947623962112 +1662135947665963008 +1662135947716964096 +1662135947758964992 +1662135947800965888 +1662135947842966784 +1662135947890967808 +1662135947941968896 +1662135947989969920 +1662135948031970816 +1662135948079971840 +1662135948121972736 +1662135948163973632 +1662135948211974656 +1662135948253975552 +1662135948292976384 +1662135948337977344 +1662135948382978304 +1662135948430979328 +1662135948472980224 +1662135948514981120 +1662135948553981952 +1662135948595982848 +1662135948637983744 +1662135948685984768 +1662135948730985728 +1662135948772986624 +1662135948814987520 +1662135948856988416 +1662135948895989248 +1662135948937990144 +1662135948982991104 +1662135949033992192 +1662135949078993152 +1662135949120994048 +1662135949174995200 +1662135949216996096 +1662135949261997056 +1662135949306998016 +1662135949348998912 +1662135949393999872 +1662135949439000832 +1662135949481001728 +1662135949529002752 +1662135949568003584 +1662135949616004608 +1662135949667005696 +1662135949709006592 +1662135949754007552 +1662135949796008448 +1662135949838009344 +1662135949886010368 +1662135949928011264 +1662135949970012160 +1662135950012013056 +1662135950057014016 +1662135950099014912 +1662135950144015872 +1662135950186016768 +1662135950240017920 +1662135950285018880 +1662135950327019776 +1662135950375020800 +1662135950417021696 +1662135950468022784 +1662135950510023680 +1662135950558024704 +1662135950600025600 +1662135950642026496 +1662135950690027520 +1662135950735028480 +1662135950777029376 +1662135950822030336 +1662135950870031360 +1662135950918032384 +1662135950960033280 +1662135951002034176 +1662135951047035136 +1662135951089036032 +1662135951146037248 +1662135951188038144 +1662135951230039040 +1662135951272039936 +1662135951317040896 +1662135951368041984 +1662135951413042944 +1662135951455043840 +1662135951494044672 +1662135951545045760 +1662135951587046656 +1662135951632047616 +1662135951674048512 +1662135951722049536 +1662135951770050560 +1662135951815051520 +1662135951860052480 +1662135951902053376 +1662135951944054272 +1662135951986055168 +1662135952028056064 +1662135952067056896 +1662135952112057856 +1662135952154058752 +1662135952196059648 +1662135952238060544 +1662135952280061440 +1662135952337062656 +1662135952379063552 +1662135952424064512 +1662135952466065408 +1662135952517066496 +1662135952559067392 +1662135952616068608 +1662135952661069568 +1662135952709070592 +1662135952763071744 +1662135952808072704 +1662135952850073600 +1662135952895074560 +1662135952937075456 +1662135952982076416 +1662135953033077504 +1662135953075078400 +1662135953117079296 +1662135953159080192 +1662135953201081088 +1662135953243081984 +1662135953291083008 +1662135953333083904 +1662135953384084992 +1662135953426085888 +1662135953471086848 +1662135953513087744 +1662135953555088640 +1662135953603089664 +1662135953651090688 +1662135953693091584 +1662135953741092608 +1662135953786093568 +1662135953828094464 +1662135953870095360 +1662135953912096256 +1662135953957097216 +1662135953999098112 +1662135954044099072 +1662135954092100096 +1662135954134100992 +1662135954176101888 +1662135954218102784 +1662135954260103680 +1662135954308104704 +1662135954353105664 +1662135954392106496 +1662135954431107328 +1662135954479108352 +1662135954518109184 +1662135954566110208 +1662135954611111168 +1662135954656112128 +1662135954704113152 +1662135954746114048 +1662135954791115008 +1662135954833115904 +1662135954878116864 +1662135954923117824 +1662135954965118720 +1662135955016119808 +1662135955058120704 +1662135955097121536 +1662135955136122368 +1662135955178123264 +1662135955217124096 +1662135955259124992 +1662135955304125952 +1662135955346126848 +1662135955391127808 +1662135955436128768 +1662135955487129856 +1662135955526130688 +1662135955568131584 +1662135955610132480 +1662135955655133440 +1662135955697134336 +1662135955739135232 +1662135955781136128 +1662135955826137088 +1662135955868137984 +1662135955913138944 +1662135955964140032 +1662135956009140992 +1662135956057142016 +1662135956105143040 +1662135956153144064 +1662135956195144960 +1662135956240145920 +1662135956288146944 +1662135956336147968 +1662135956381148928 +1662135956426149888 +1662135956468150784 +1662135956513151744 +1662135956555152640 +1662135956600153600 +1662135956648154624 +1662135956690155520 +1662135956732156416 +1662135956774157312 +1662135956828158464 +1662135956876159488 +1662135956921160448 +1662135956963161344 +1662135957008162304 +1662135957056163328 +1662135957104164352 +1662135957146165248 +1662135957188166144 +1662135957230167040 +1662135957266167808 +1662135957308168704 +1662135957350169600 +1662135957392170496 +1662135957437171456 +1662135957479172352 +1662135957521173248 +1662135957566174208 +1662135957608175104 +1662135957650176000 +1662135957695176960 +1662135957734177792 +1662135957785178880 +1662135957827179776 +1662135957869180672 +1662135957911181568 +1662135957956182528 +1662135958001183488 +1662135958046184448 +1662135958088185344 +1662135958130186240 +1662135958175187200 +1662135958226188288 +1662135958268189184 +1662135958310190080 +1662135958352190976 +1662135958394191872 +1662135958445192960 +1662135958487193856 +1662135958529194752 +1662135958565195520 +1662135958610196480 +1662135958652197376 +1662135958694198272 +1662135958739199232 +1662135958781200128 +1662135958826201088 +1662135958868201984 +1662135958910202880 +1662135958952203776 +1662135958994204672 +1662135959039205632 +1662135959084206592 +1662135959129207552 +1662135959174208512 +1662135959216209408 +1662135959261210368 +1662135959306211328 +1662135959351212288 +1662135959396213248 +1662135959438214144 +1662135959483215104 +1662135959531216128 +1662135959573217024 +1662135959615217920 +1662135959654218752 +1662135959696219648 +1662135959738220544 +1662135959780221440 +1662135959825222400 +1662135959870223360 +1662135959909224192 +1662135959951225088 +1662135959999226112 +1662135960041227008 +1662135960083227904 +1662135960125228800 +1662135960167229696 +1662135960218230784 +1662135960260231680 +1662135960299232512 +1662135960347233536 +1662135960392234496 +1662135960440235520 +1662135960485236480 +1662135960539237632 +1662135960584238592 +1662135960635239680 +1662135960680240640 +1662135960725241600 +1662135960776242688 +1662135960818243584 +1662135960863244544 +1662135960908245504 +1662135960950246400 +1662135961001247488 +1662135961043248384 +1662135961085249280 +1662135961127250176 +1662135961178251264 +1662135961220252160 +1662135961265253120 +1662135961307254016 +1662135961352254976 +1662135961400256000 +1662135961448257024 +1662135961490257920 +1662135961535258880 +1662135961580259840 +1662135961619260672 +1662135961658261504 +1662135961700262400 +1662135961742263296 +1662135961784264192 +1662135961826265088 +1662135961868265984 +1662135961907266816 +1662135961949267712 +1662135961991268608 +1662135962039269632 +1662135962081270528 +1662135962123271424 +1662135962165272320 +1662135962210273280 +1662135962252274176 +1662135962303275264 +1662135962345276160 +1662135962387277056 +1662135962432278016 +1662135962477278976 +1662135962528280064 +1662135962570280960 +1662135962615281920 +1662135962657282816 +1662135962699283712 +1662135962741284608 +1662135962792285696 +1662135962837286656 +1662135962882287616 +1662135962924288512 +1662135962972289536 +1662135963014290432 +1662135963065291520 +1662135963113292544 +1662135963164293632 +1662135963212294656 +1662135963254295552 +1662135963299296512 +1662135963341297408 +1662135963386298368 +1662135963425299200 +1662135963467300096 +1662135963512301056 +1662135963554301952 +1662135963596302848 +1662135963644303872 +1662135963686304768 +1662135963728305664 +1662135963773306624 +1662135963815307520 +1662135963857308416 +1662135963902309376 +1662135963947310336 +1662135963995311360 +1662135964040312320 +1662135964088313344 +1662135964139314432 +1662135964181315328 +1662135964223316224 +1662135964271317248 +1662135964313318144 +1662135964358319104 +1662135964406320128 +1662135964445320960 +1662135964487321856 +1662135964532322816 +1662135964574323712 +1662135964619324672 +1662135964667325696 +1662135964709326592 +1662135964754327552 +1662135964796328448 +1662135964835329280 +1662135964883330304 +1662135964928331264 +1662135964970332160 +1662135965012333056 +1662135965057334016 +1662135965108335104 +1662135965144335872 +1662135965186336768 +1662135965234337792 +1662135965276338688 +1662135965327339776 +1662135965369340672 +1662135965414341632 +1662135965459342592 +1662135965507343616 +1662135965549344512 +1662135965591345408 +1662135965633346304 +1662135965678347264 +1662135965720348160 +1662135965765349120 +1662135965810350080 +1662135965852350976 +1662135965894351872 +1662135965933352704 +1662135965972353536 +1662135966017354496 +1662135966065355520 +1662135966107356416 +1662135966152357376 +1662135966191358208 +1662135966239359232 +1662135966284360192 +1662135966329361152 +1662135966371362048 +1662135966419363072 +1662135966464364032 +1662135966512365056 +1662135966551365888 +1662135966596366848 +1662135966638367744 +1662135966680368640 +1662135966719369472 +1662135966761370368 +1662135966803371264 +1662135966848372224 +1662135966890373120 +1662135966932374016 +1662135966974374912 +1662135967025376000 +1662135967067376896 +1662135967115377920 +1662135967160378880 +1662135967202379776 +1662135967250380800 +1662135967295381760 +1662135967340382720 +1662135967382383616 +1662135967424384512 +1662135967466385408 +1662135967505386240 +1662135967550387200 +1662135967592388096 +1662135967646389248 +1662135967685390080 +1662135967733391104 +1662135967775392000 +1662135967817392896 +1662135967874394112 +1662135967919395072 +1662135967961395968 +1662135968012397056 +1662135968054397952 +1662135968096398848 +1662135968141399808 +1662135968186400768 +1662135968225401600 +1662135968264402432 +1662135968312403456 +1662135968360404480 +1662135968402405376 +1662135968447406336 +1662135968492407296 +1662135968534408192 +1662135968582409216 +1662135968624410112 +1662135968666411008 +1662135968708411904 +1662135968747412736 +1662135968789413632 +1662135968834414592 +1662135968879415552 +1662135968921416448 +1662135968963417344 +1662135969008418304 +1662135969050419200 +1662135969092420096 +1662135969137421056 +1662135969182422016 +1662135969227422976 +1662135969269423872 +1662135969311424768 +1662135969356425728 +1662135969404426752 +1662135969452427776 +1662135969497428736 +1662135969548429824 +1662135969596430848 +1662135969641431808 +1662135969695432960 +1662135969740433920 +1662135969779434752 +1662135969821435648 +1662135969863436544 +1662135969908437504 +1662135969953438464 +1662135970004439552 +1662135970043440384 +1662135970088441344 +1662135970130442240 +1662135970178443264 +1662135970223444224 +1662135970265445120 +1662135970307446016 +1662135970358447104 +1662135970400448000 +1662135970445448960 +1662135970487449856 +1662135970526450688 +1662135970565451520 +1662135970607452416 +1662135970649453312 +1662135970691454208 +1662135970736455168 +1662135970781456128 +1662135970829457152 +1662135970871458048 +1662135970913458944 +1662135970958459904 +1662135971006460928 +1662135971063462144 +1662135971105463040 +1662135971150464000 +1662135971198465024 +1662135971240465920 +1662135971285466880 +1662135971336467968 +1662135971381468928 +1662135971426469888 +1662135971468470784 +1662135971510471680 +1662135971552472576 +1662135971600473600 +1662135971642474496 +1662135971690475520 +1662135971741476608 +1662135971786477568 +1662135971831478528 +1662135971876479488 +1662135971918480384 +1662135971960481280 +1662135972014482432 +1662135972068483584 +1662135972116484608 +1662135972164485632 +1662135972209486592 +1662135972254487552 +1662135972296488448 +1662135972344489472 +1662135972395490560 +1662135972443491584 +1662135972488492544 +1662135972533493504 +1662135972575494400 +1662135972620495360 +1662135972662496256 +1662135972704497152 +1662135972749498112 +1662135972797499136 +1662135972842500096 +1662135972887501056 +1662135972926501888 +1662135972974502912 +1662135973016503808 +1662135973070504960 +1662135973115505920 +1662135973160506880 +1662135973205507840 +1662135973262509056 +1662135973304509952 +1662135973346510848 +1662135973391511808 +1662135973433512704 +1662135973472513536 +1662135973514514432 +1662135973556515328 +1662135973598516224 +1662135973649517312 +1662135973700518400 +1662135973748519424 +1662135973793520384 +1662135973835521280 +1662135973883522304 +1662135973928523264 +1662135973976524288 +1662135974018525184 +1662135974060526080 +1662135974108527104 +1662135974150528000 +1662135974192528896 +1662135974237529856 +1662135974282530816 +1662135974324531712 +1662135974369532672 +1662135974411533568 +1662135974456534528 +1662135974501535488 +1662135974543536384 +1662135974585537280 +1662135974627538176 +1662135974681539328 +1662135974729540352 +1662135974771541248 +1662135974813542144 +1662135974858543104 +1662135974906544128 +1662135974945544960 +1662135974987545856 +1662135975035546880 +1662135975083547904 +1662135975134548992 +1662135975176549888 +1662135975218550784 +1662135975263551744 +1662135975311552768 +1662135975359553792 +1662135975401554688 +1662135975452555776 +1662135975494556672 +1662135975542557696 +1662135975587558656 +1662135975632559616 +1662135975677560576 +1662135975725561600 +1662135975767562496 +1662135975818563584 +1662135975866564608 +1662135975908565504 +1662135975950566400 +1662135975995567360 +1662135976040568320 +1662135976085569280 +1662135976127570176 +1662135976169571072 +1662135976211571968 +1662135976256572928 +1662135976295573760 +1662135976340574720 +1662135976385575680 +1662135976430576640 +1662135976472577536 +1662135976520578560 +1662135976559579392 +1662135976607580416 +1662135976649581312 +1662135976697582336 +1662135976745583360 +1662135976787584256 +1662135976829585152 +1662135976871586048 +1662135976913586944 +1662135976955587840 +1662135977006588928 +1662135977048589824 +1662135977093590784 +1662135977138591744 +1662135977183592704 +1662135977228593664 +1662135977276594688 +1662135977318595584 +1662135977360596480 +1662135977405597440 +1662135977453598464 +1662135977495599360 +1662135977540600320 +1662135977582601216 +1662135977624602112 +1662135977681603328 +1662135977723604224 +1662135977765605120 +1662135977810606080 +1662135977858607104 +1662135977900608000 +1662135977945608960 +1662135977996610048 +1662135978041611008 +1662135978086611968 +1662135978131612928 +1662135978173613824 +1662135978212614656 +1662135978257615616 +1662135978299616512 +1662135978341617408 +1662135978383618304 +1662135978425619200 +1662135978470620160 +1662135978509620992 +1662135978563622144 +1662135978608623104 +1662135978650624000 +1662135978698625024 +1662135978737625856 +1662135978785626880 +1662135978824627712 +1662135978869628672 +1662135978911629568 +1662135978956630528 +1662135978998631424 +1662135979043632384 +1662135979091633408 +1662135979133634304 +1662135979175635200 +1662135979220636160 +1662135979262637056 +1662135979304637952 +1662135979346638848 +1662135979388639744 +1662135979439640832 +1662135979484641792 +1662135979529642752 +1662135979571643648 +1662135979613644544 +1662135979658645504 +1662135979700646400 +1662135979742647296 +1662135979784648192 +1662135979829649152 +1662135979877650176 +1662135979919651072 +1662135979964652032 +1662135980009652992 +1662135980054653952 +1662135980105655040 +1662135980147655936 +1662135980189656832 +1662135980234657792 +1662135980276658688 +1662135980318659584 +1662135980363660544 +1662135980408661504 +1662135980465662720 +1662135980507663616 +1662135980549664512 +1662135980606665728 +1662135980651666688 +1662135980696667648 +1662135980738668544 +1662135980780669440 +1662135980822670336 +1662135980867671296 +1662135980909672192 +1662135980954673152 +1662135980996674048 +1662135981041675008 +1662135981083675904 +1662135981131676928 +1662135981179677952 +1662135981221678848 +1662135981293680384 +1662135981335681280 +1662135981383682304 +1662135981425683200 +1662135981470684160 +1662135981515685120 +1662135981560686080 +1662135981608687104 +1662135981659688192 +1662135981701689088 +1662135981740689920 +1662135981782690816 +1662135981824691712 +1662135981869692672 +1662135981920693760 +1662135981965694720 +1662135982016695808 +1662135982058696704 +1662135982100697600 +1662135982142698496 +1662135982184699392 +1662135982226700288 +1662135982271701248 +1662135982319702272 +1662135982361703168 +1662135982400704000 +1662135982442704896 +1662135982490705920 +1662135982541707008 +1662135982583707904 +1662135982625708800 +1662135982667709696 +1662135982715710720 +1662135982757711616 +1662135982796712448 +1662135982841713408 +1662135982883714304 +1662135982922715136 +1662135982967716096 +1662135983009716992 +1662135983048717824 +1662135983093718784 +1662135983135719680 +1662135983183720704 +1662135983228721664 +1662135983270722560 +1662135983321723648 +1662135983366724608 +1662135983408725504 +1662135983456726528 +1662135983501727488 +1662135983549728512 +1662135983594729472 +1662135983642730496 +1662135983687731456 +1662135983729732352 +1662135983771733248 +1662135983819734272 +1662135983864735232 +1662135983909736192 +1662135983954737152 +1662135983999738112 +1662135984041739008 +1662135984083739904 +1662135984125740800 +1662135984179741952 +1662135984224742912 +1662135984269743872 +1662135984317744896 +1662135984362745856 +1662135984404746752 +1662135984446747648 +1662135984491748608 +1662135984533749504 +1662135984572750336 +1662135984614751232 +1662135984656752128 +1662135984701753088 +1662135984743753984 +1662135984782754816 +1662135984833755904 +1662135984884756992 +1662135984929757952 +1662135984980759040 +1662135985031760128 +1662135985076761088 +1662135985115761920 +1662135985166763008 +1662135985217764096 +1662135985265765120 +1662135985304765952 +1662135985346766848 +1662135985388767744 +1662135985427768576 +1662135985469769472 +1662135985508770304 +1662135985547771136 +1662135985589772032 +1662135985634772992 +1662135985676773888 +1662135985721774848 +1662135985769775872 +1662135985817776896 +1662135985865777920 +1662135985907778816 +1662135985955779840 +1662135986003780864 +1662135986051781888 +1662135986096782848 +1662135986141783808 +1662135986186784768 +1662135986234785792 +1662135986279786752 +1662135986321787648 +1662135986363788544 +1662135986414789632 +1662135986462790656 +1662135986501791488 +1662135986546792448 +1662135986591793408 +1662135986636794368 +1662135986687795456 +1662135986729796352 +1662135986780797440 +1662135986828798464 +1662135986876799488 +1662135986918800384 +1662135986963801344 +1662135987014802432 +1662135987059803392 +1662135987107804416 +1662135987152805376 +1662135987197806336 +1662135987245807360 +1662135987290808320 +1662135987332809216 +1662135987374810112 +1662135987416811008 +1662135987461811968 +1662135987500812800 +1662135987542813696 +1662135987584814592 +1662135987632815616 +1662135987674816512 +1662135987716817408 +1662135987758818304 +1662135987803819264 +1662135987845820160 +1662135987890821120 +1662135987935822080 +1662135987980823040 +1662135988022823936 +1662135988067824896 +1662135988112825856 +1662135988154826752 +1662135988196827648 +1662135988235828480 +1662135988277829376 +1662135988319830272 +1662135988361831168 +1662135988406832128 +1662135988448833024 +1662135988493833984 +1662135988535834880 +1662135988583835904 +1662135988625836800 +1662135988670837760 +1662135988715838720 +1662135988760839680 +1662135988799840512 +1662135988838841344 +1662135988880842240 +1662135988919843072 +1662135988961843968 +1662135989003844864 +1662135989042845696 +1662135989084846592 +1662135989129847552 +1662135989171848448 +1662135989210849280 +1662135989258850304 +1662135989300851200 +1662135989342852096 +1662135989384852992 +1662135989429853952 +1662135989468854784 +1662135989510855680 +1662135989552856576 +1662135989594857472 +1662135989639858432 +1662135989681859328 +1662135989723860224 +1662135989765861120 +1662135989807862016 +1662135989852862976 +1662135989897863936 +1662135989942864896 +1662135989984865792 +1662135990029866752 +1662135990065867520 +1662135990113868544 +1662135990161869568 +1662135990203870464 +1662135990245871360 +1662135990287872256 +1662135990329873152 +1662135990374874112 +1662135990422875136 +1662135990464876032 +1662135990509876992 +1662135990551877888 +1662135990605879040 +1662135990650880000 +1662135990695880960 +1662135990743881984 +1662135990785882880 +1662135990836883968 +1662135990884884992 +1662135990935886080 +1662135990980887040 +1662135991025888000 +1662135991067888896 +1662135991109889792 +1662135991151890688 +1662135991199891712 +1662135991238892544 +1662135991283893504 +1662135991328894464 +1662135991370895360 +1662135991415896320 +1662135991457897216 +1662135991502898176 +1662135991544899072 +1662135991586899968 +1662135991628900864 +1662135991670901760 +1662135991712902656 +1662135991760903680 +1662135991802904576 +1662135991844905472 +1662135991889906432 +1662135991931907328 +1662135991979908352 +1662135992021909248 +1662135992075910400 +1662135992114911232 +1662135992156912128 +1662135992195912960 +1662135992240913920 +1662135992282914816 +1662135992330915840 +1662135992378916864 +1662135992417917696 +1662135992462918656 +1662135992510919680 +1662135992552920576 +1662135992603921664 +1662135992645922560 +1662135992687923456 +1662135992729924352 +1662135992771925248 +1662135992813926144 +1662135992855927040 +1662135992909928192 +1662135992951929088 +1662135992990929920 +1662135993032930816 +1662135993083931904 +1662135993128932864 +1662135993182934016 +1662135993224934912 +1662135993281936128 +1662135993329937152 +1662135993371938048 +1662135993413938944 +1662135993458939904 +1662135993503940864 +1662135993545941760 +1662135993590942720 +1662135993632943616 +1662135993677944576 +1662135993722945536 +1662135993761946368 +1662135993806947328 +1662135993851948288 +1662135993893949184 +1662135993935950080 +1662135993980951040 +1662135994025952000 +1662135994070952960 +1662135994112953856 +1662135994157954816 +1662135994202955776 +1662135994253956864 +1662135994298957824 +1662135994340958720 +1662135994382959616 +1662135994427960576 +1662135994469961472 +1662135994514962432 +1662135994565963520 +1662135994610964480 +1662135994655965440 +1662135994694966272 +1662135994739967232 +1662135994781968128 +1662135994838969344 +1662135994883970304 +1662135994931971328 +1662135994976972288 +1662135995018973184 +1662135995060974080 +1662135995111975168 +1662135995156976128 +1662135995201977088 +1662135995243977984 +1662135995291979008 +1662135995333979904 +1662135995381980928 +1662135995429981952 +1662135995480983040 +1662135995525984000 +1662135995573985024 +1662135995615985920 +1662135995672987136 +1662135995717988096 +1662135995777989376 +1662135995822990336 +1662135995864991232 +1662135995918992384 +1662135995960993280 +1662135995999994112 +1662135996044995072 +1662135996086995968 +1662135996128996864 +1662135996179997952 +1662135996224998912 +1662135996266999808 +1662135996315000832 +1662135996357001728 +1662135996402002688 +1662135996444003584 +1662135996489004544 +1662135996528005376 +1662135996579006464 +1662135996621007360 +1662135996666008320 +1662135996705009152 +1662135996747010048 +1662135996789010944 +1662135996837011968 +1662135996888013056 +1662135996939014144 +1662135996990015232 +1662135997038016256 +1662135997086017280 +1662135997128018176 +1662135997176019200 +1662135997218020096 +1662135997260020992 +1662135997305021952 +1662135997350022912 +1662135997398023936 +1662135997437024768 +1662135997479025664 +1662135997521026560 +1662135997572027648 +1662135997620028672 +1662135997659029504 +1662135997710030592 +1662135997752031488 +1662135997794032384 +1662135997836033280 +1662135997878034176 +1662135997920035072 +1662135997965036032 +1662135998007036928 +1662135998052037888 +1662135998097038848 +1662135998139039744 +1662135998184040704 +1662135998226041600 +1662135998271042560 +1662135998316043520 +1662135998361044480 +1662135998412045568 +1662135998457046528 +1662135998499047424 +1662135998550048512 +1662135998595049472 +1662135998640050432 +1662135998682051328 +1662135998727052288 +1662135998772053248 +1662135998820054272 +1662135998865055232 +1662135998907056128 +1662135998949057024 +1662135998997058048 +1662135999039058944 +1662135999081059840 +1662135999123060736 +1662135999168061696 +1662135999216062720 +1662135999264063744 +1662135999309064704 +1662135999360065792 +1662135999402066688 +1662135999447067648 +1662135999489068544 +1662135999528069376 +1662135999579070464 +1662135999630071552 +1662135999678072576 +1662135999720073472 +1662135999759074304 +1662135999804075264 +1662135999846076160 +1662135999894077184 +1662135999939078144 +1662135999981079040 +1662136000029080064 +1662136000077081088 +1662136000125082112 +1662136000173083136 +1662136000215084032 +1662136000257084928 +1662136000299085824 +1662136000341086720 +1662136000383087616 +1662136000425088512 +1662136000473089536 +1662136000518090496 +1662136000557091328 +1662136000605092352 +1662136000650093312 +1662136000701094400 +1662136000740095232 +1662136000782096128 +1662136000827097088 +1662136000869097984 +1662136000911098880 +1662136000953099776 +1662136000992100608 +1662136001034101504 +1662136001088102656 +1662136001130103552 +1662136001172104448 +1662136001217105408 +1662136001256106240 +1662136001307107328 +1662136001352108288 +1662136001400109312 +1662136001442110208 +1662136001490111232 +1662136001535112192 +1662136001580113152 +1662136001622114048 +1662136001670115072 +1662136001709115904 +1662136001751116800 +1662136001796117760 +1662136001841118720 +1662136001895119872 +1662136001946120960 +1662136001991121920 +1662136002042123008 +1662136002084123904 +1662136002132124928 +1662136002180125952 +1662136002222126848 +1662136002267127808 +1662136002306128640 +1662136002348129536 +1662136002396130560 +1662136002441131520 +1662136002495132672 +1662136002540133632 +1662136002585134592 +1662136002633135616 +1662136002678136576 +1662136002723137536 +1662136002768138496 +1662136002813139456 +1662136002852140288 +1662136002894141184 +1662136002939142144 +1662136002990143232 +1662136003041144320 +1662136003083145216 +1662136003128146176 +1662136003179147264 +1662136003239148544 +1662136003284149504 +1662136003323150336 +1662136003371151360 +1662136003416152320 +1662136003458153216 +1662136003503154176 +1662136003545155072 +1662136003590156032 +1662136003638157056 +1662136003680157952 +1662136003722158848 +1662136003761159680 +1662136003803160576 +1662136003848161536 +1662136003899162624 +1662136003941163520 +1662136003992164608 +1662136004034165504 +1662136004088166656 +1662136004139167744 +1662136004184168704 +1662136004229169664 +1662136004268170496 +1662136004313171456 +1662136004352172288 +1662136004400173312 +1662136004439174144 +1662136004484175104 +1662136004529176064 +1662136004571176960 +1662136004619177984 +1662136004658178816 +1662136004703179776 +1662136004748180736 +1662136004793181696 +1662136004835182592 +1662136004880183552 +1662136004928184576 +1662136004985185792 +1662136005030186752 +1662136005072187648 +1662136005120188672 +1662136005168189696 +1662136005213190656 +1662136005255191552 +1662136005297192448 +1662136005339193344 +1662136005381194240 +1662136005426195200 +1662136005465196032 +1662136005507196928 +1662136005552197888 +1662136005594198784 +1662136005639199744 +1662136005681200640 +1662136005729201664 +1662136005774202624 +1662136005816203520 +1662136005861204480 +1662136005903205376 +1662136005945206272 +1662136005984207104 +1662136006029208064 +1662136006080209152 +1662136006131210240 +1662136006185211392 +1662136006230212352 +1662136006272213248 +1662136006317214208 +1662136006359215104 +1662136006401216000 +1662136006452217088 +1662136006494217984 +1662136006539218944 +1662136006581219840 +1662136006632220928 +1662136006668221696 +1662136006713222656 +1662136006755223552 +1662136006800224512 +1662136006845225472 +1662136006887226368 +1662136006929227264 +1662136006971228160 +1662136007016229120 +1662136007067230208 +1662136007118231296 +1662136007160232192 +1662136007202233088 +1662136007244233984 +1662136007286234880 +1662136007328235776 +1662136007373236736 +1662136007421237760 +1662136007466238720 +1662136007517239808 +1662136007562240768 +1662136007604241664 +1662136007652242688 +1662136007697243648 +1662136007739244544 +1662136007781245440 +1662136007826246400 +1662136007868247296 +1662136007910248192 +1662136007952249088 +1662136008000250112 +1662136008042251008 +1662136008084251904 +1662136008126252800 +1662136008174253824 +1662136008216254720 +1662136008261255680 +1662136008303256576 +1662136008342257408 +1662136008384258304 +1662136008426259200 +1662136008468260096 +1662136008513261056 +1662136008561262080 +1662136008603262976 +1662136008648263936 +1662136008696264960 +1662136008741265920 +1662136008783266816 +1662136008831267840 +1662136008873268736 +1662136008918269696 +1662136008960270592 +1662136008999271424 +1662136009041272320 +1662136009089273344 +1662136009140274432 +1662136009182275328 +1662136009224276224 +1662136009266277120 +1662136009311278080 +1662136009356279040 +1662136009395279872 +1662136009440280832 +1662136009482281728 +1662136009527282688 +1662136009578283776 +1662136009617284608 +1662136009662285568 +1662136009704286464 +1662136009752287488 +1662136009797288448 +1662136009842289408 +1662136009884290304 +1662136009926291200 +1662136009974292224 +1662136010016293120 +1662136010061294080 +1662136010109295104 +1662136010154296064 +1662136010196296960 +1662136010235297792 +1662136010280298752 +1662136010322299648 +1662136010364300544 +1662136010409301504 +1662136010451302400 +1662136010499303424 +1662136010547304448 +1662136010592305408 +1662136010637306368 +1662136010676307200 +1662136010718308096 +1662136010760308992 +1662136010808310016 +1662136010850310912 +1662136010892311808 +1662136010934312704 +1662136010982313728 +1662136011027314688 +1662136011072315648 +1662136011114316544 +1662136011159317504 +1662136011201318400 +1662136011243319296 +1662136011285320192 +1662136011327321088 +1662136011372322048 +1662136011420323072 +1662136011462323968 +1662136011507324928 +1662136011549325824 +1662136011591326720 +1662136011633327616 +1662136011687328768 +1662136011732329728 +1662136011780330752 +1662136011822331648 +1662136011870332672 +1662136011918333696 +1662136011960334592 +1662136012002335488 +1662136012047336448 +1662136012092337408 +1662136012134338304 +1662136012176339200 +1662136012218340096 +1662136012260340992 +1662136012302341888 +1662136012350342912 +1662136012395343872 +1662136012437344768 +1662136012482345728 +1662136012527346688 +1662136012575347712 +1662136012614348544 +1662136012656349440 +1662136012701350400 +1662136012740351232 +1662136012782352128 +1662136012824353024 +1662136012866353920 +1662136012914354944 +1662136012959355904 +1662136013004356864 +1662136013046357760 +1662136013091358720 +1662136013136359680 +1662136013178360576 +1662136013223361536 +1662136013262362368 +1662136013307363328 +1662136013352364288 +1662136013394365184 +1662136013436366080 +1662136013481367040 +1662136013523367936 +1662136013565368832 +1662136013607369728 +1662136013652370688 +1662136013694371584 +1662136013736372480 +1662136013790373632 +1662136013832374528 +1662136013874375424 +1662136013916376320 +1662136013961377280 +1662136014006378240 +1662136014051379200 +1662136014096380160 +1662136014144381184 +1662136014189382144 +1662136014231383040 +1662136014276384000 +1662136014321384960 +1662136014369385984 +1662136014411386880 +1662136014453387776 +1662136014501388800 +1662136014543389696 +1662136014591390720 +1662136014630391552 +1662136014672392448 +1662136014717393408 +1662136014765394432 +1662136014807395328 +1662136014858396416 +1662136014903397376 +1662136014948398336 +1662136014996399360 +1662136015041400320 +1662136015086401280 +1662136015128402176 +1662136015170403072 +1662136015218404096 +1662136015263405056 +1662136015305405952 +1662136015347406848 +1662136015404408064 +1662136015449409024 +1662136015500410112 +1662136015545411072 +1662136015584411904 +1662136015629412864 +1662136015671413760 +1662136015716414720 +1662136015761415680 +1662136015806416640 +1662136015848417536 +1662136015893418496 +1662136015938419456 +1662136015986420480 +1662136016028421376 +1662136016076422400 +1662136016121423360 +1662136016163424256 +1662136016208425216 +1662136016253426176 +1662136016295427072 +1662136016340428032 +1662136016382428928 +1662136016427429888 +1662136016484431104 +1662136016529432064 +1662136016574433024 +1662136016625434112 +1662136016667435008 +1662136016715436032 +1662136016760436992 +1662136016808438016 +1662136016850438912 +1662136016892439808 +1662136016937440768 +1662136016985441792 +1662136017027442688 +1662136017075443712 +1662136017129444864 +1662136017174445824 +1662136017222446848 +1662136017264447744 +1662136017309448704 +1662136017351449600 +1662136017402450688 +1662136017441451520 +1662136017486452480 +1662136017534453504 +1662136017579454464 +1662136017624455424 +1662136017663456256 +1662136017708457216 +1662136017750458112 +1662136017792459008 +1662136017843460096 +1662136017882460928 +1662136017924461824 +1662136017966462720 +1662136018011463680 +1662136018056464640 +1662136018107465728 +1662136018152466688 +1662136018200467712 +1662136018248468736 +1662136018290469632 +1662136018332470528 +1662136018377471488 +1662136018425472512 +1662136018467473408 +1662136018509474304 +1662136018557475328 +1662136018605476352 +1662136018647477248 +1662136018689478144 +1662136018737479168 +1662136018791480320 +1662136018833481216 +1662136018878482176 +1662136018920483072 +1662136018962483968 +1662136019010484992 +1662136019052485888 +1662136019097486848 +1662136019136487680 +1662136019190488832 +1662136019232489728 diff --git a/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track1_light.txt b/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track1_light.txt new file mode 100644 index 0000000000..fc436ed12e --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track1_light.txt @@ -0,0 +1,6263 @@ +1662129779504666880 +1662129779546667776 +1662129779588668672 +1662129779630669568 +1662129779675670528 +1662129779717671424 +1662129779762672384 +1662129779804673280 +1662129779849674240 +1662129779894675200 +1662129779936676096 +1662129779984677120 +1662129780026678016 +1662129780068678912 +1662129780110679808 +1662129780152680704 +1662129780194681600 +1662129780236682496 +1662129780278683392 +1662129780326684416 +1662129780368685312 +1662129780413686272 +1662129780455687168 +1662129780506688256 +1662129780548689152 +1662129780596690176 +1662129780641691136 +1662129780683692032 +1662129780728692992 +1662129780773693952 +1662129780815694848 +1662129780857695744 +1662129780911696896 +1662129780956697856 +1662129781001698816 +1662129781052699904 +1662129781097700864 +1662129781139701760 +1662129781181702656 +1662129781223703552 +1662129781268704512 +1662129781310705408 +1662129781358706432 +1662129781400707328 +1662129781442708224 +1662129781490709248 +1662129781532710144 +1662129781574711040 +1662129781616711936 +1662129781661712896 +1662129781703713792 +1662129781751714816 +1662129781796715776 +1662129781838716672 +1662129781883717632 +1662129781922718464 +1662129781970719488 +1662129782012720384 +1662129782054721280 +1662129782099722240 +1662129782141723136 +1662129782192724224 +1662129782234725120 +1662129782279726080 +1662129782324727040 +1662129782378728192 +1662129782423729152 +1662129782471730176 +1662129782513731072 +1662129782558732032 +1662129782600732928 +1662129782642733824 +1662129782687734784 +1662129782729735680 +1662129782777736704 +1662129782834737920 +1662129782876738816 +1662129782918739712 +1662129782966740736 +1662129783008741632 +1662129783053742592 +1662129783101743616 +1662129783143744512 +1662129783188745472 +1662129783233746432 +1662129783275747328 +1662129783323748352 +1662129783371749376 +1662129783410750208 +1662129783452751104 +1662129783497752064 +1662129783539752960 +1662129783584753920 +1662129783626754816 +1662129783668755712 +1662129783713756672 +1662129783761757696 +1662129783803758592 +1662129783845759488 +1662129783887760384 +1662129783932761344 +1662129783977762304 +1662129784019763200 +1662129784064764160 +1662129784106765056 +1662129784154766080 +1662129784199767040 +1662129784241767936 +1662129784292769024 +1662129784334769920 +1662129784382770944 +1662129784430771968 +1662129784472772864 +1662129784514773760 +1662129784562774784 +1662129784613775872 +1662129784655776768 +1662129784706777856 +1662129784751778816 +1662129784793779712 +1662129784838780672 +1662129784883781632 +1662129784931782656 +1662129784976783616 +1662129785018784512 +1662129785063785472 +1662129785111786496 +1662129785162787584 +1662129785210788608 +1662129785255789568 +1662129785300790528 +1662129785342791424 +1662129785387792384 +1662129785432793344 +1662129785483794432 +1662129785528795392 +1662129785576796416 +1662129785621797376 +1662129785666798336 +1662129785717799424 +1662129785762800384 +1662129785810801408 +1662129785852802304 +1662129785894803200 +1662129785936804096 +1662129785978804992 +1662129786026806016 +1662129786068806912 +1662129786113807872 +1662129786161808896 +1662129786209809920 +1662129786251810816 +1662129786296811776 +1662129786341812736 +1662129786386813696 +1662129786437814784 +1662129786485815808 +1662129786530816768 +1662129786584817920 +1662129786629818880 +1662129786671819776 +1662129786719820800 +1662129786761821696 +1662129786803822592 +1662129786845823488 +1662129786890824448 +1662129786929825280 +1662129786977826304 +1662129787025827328 +1662129787070828288 +1662129787115829248 +1662129787157830144 +1662129787205831168 +1662129787250832128 +1662129787295833088 +1662129787340834048 +1662129787388835072 +1662129787436836096 +1662129787481837056 +1662129787529838080 +1662129787574839040 +1662129787619840000 +1662129787658840832 +1662129787703841792 +1662129787748842752 +1662129787793843712 +1662129787841844736 +1662129787886845696 +1662129787931846656 +1662129787976847616 +1662129788021848576 +1662129788069849600 +1662129788111850496 +1662129788159851520 +1662129788201852416 +1662129788243853312 +1662129788288854272 +1662129788342855424 +1662129788390856448 +1662129788432857344 +1662129788480858368 +1662129788522859264 +1662129788567860224 +1662129788615861248 +1662129788660862208 +1662129788705863168 +1662129788747864064 +1662129788786864896 +1662129788831865856 +1662129788885867008 +1662129788933868032 +1662129788972868864 +1662129789020869888 +1662129789068870912 +1662129789110871808 +1662129789152872704 +1662129789197873664 +1662129789239874560 +1662129789287875584 +1662129789335876608 +1662129789377877504 +1662129789425878528 +1662129789467879424 +1662129789512880384 +1662129789563881472 +1662129789605882368 +1662129789647883264 +1662129789692884224 +1662129789737885184 +1662129789779886080 +1662129789821886976 +1662129789863887872 +1662129789908888832 +1662129789956889856 +1662129790001890816 +1662129790046891776 +1662129790085892608 +1662129790130893568 +1662129790175894528 +1662129790217895424 +1662129790259896320 +1662129790304897280 +1662129790352898304 +1662129790397899264 +1662129790442900224 +1662129790484901120 +1662129790526902016 +1662129790568902912 +1662129790610903808 +1662129790649904640 +1662129790691905536 +1662129790733906432 +1662129790775907328 +1662129790820908288 +1662129790862909184 +1662129790910910208 +1662129790949911040 +1662129790994912000 +1662129791033912832 +1662129791075913728 +1662129791120914688 +1662129791162915584 +1662129791207916544 +1662129791252917504 +1662129791294918400 +1662129791336919296 +1662129791378920192 +1662129791420921088 +1662129791465922048 +1662129791504922880 +1662129791549923840 +1662129791594924800 +1662129791636925696 +1662129791678926592 +1662129791720927488 +1662129791762928384 +1662129791804929280 +1662129791843930112 +1662129791888931072 +1662129791936932096 +1662129791981933056 +1662129792029934080 +1662129792077935104 +1662129792119936000 +1662129792155936768 +1662129792197937664 +1662129792245938688 +1662129792287939584 +1662129792338940672 +1662129792380941568 +1662129792425942528 +1662129792470943488 +1662129792512944384 +1662129792557945344 +1662129792599946240 +1662129792644947200 +1662129792683948032 +1662129792728948992 +1662129792773949952 +1662129792821950976 +1662129792866951936 +1662129792908952832 +1662129792959953920 +1662129793004954880 +1662129793049955840 +1662129793088956672 +1662129793133957632 +1662129793181958656 +1662129793223959552 +1662129793265960448 +1662129793313961472 +1662129793358962432 +1662129793409963520 +1662129793451964416 +1662129793496965376 +1662129793544966400 +1662129793586967296 +1662129793628968192 +1662129793670969088 +1662129793712969984 +1662129793754970880 +1662129793796971776 +1662129793841972736 +1662129793895973888 +1662129793937974784 +1662129793979975680 +1662129794027976704 +1662129794075977728 +1662129794117978624 +1662129794162979584 +1662129794207980544 +1662129794249981440 +1662129794291982336 +1662129794333983232 +1662129794375984128 +1662129794417985024 +1662129794459985920 +1662129794513987072 +1662129794555987968 +1662129794597988864 +1662129794639989760 +1662129794684990720 +1662129794732991744 +1662129794777992704 +1662129794822993664 +1662129794873994752 +1662129794915995648 +1662129794957996544 +1662129795002997504 +1662129795044998400 +1662129795083999232 +1662129795135000320 +1662129795177001216 +1662129795225002240 +1662129795267003136 +1662129795315004160 +1662129795366005248 +1662129795408006144 +1662129795456007168 +1662129795501008128 +1662129795543009024 +1662129795585009920 +1662129795624010752 +1662129795672011776 +1662129795717012736 +1662129795762013696 +1662129795804014592 +1662129795855015680 +1662129795903016704 +1662129795957017856 +1662129796008018944 +1662129796050019840 +1662129796098020864 +1662129796146021888 +1662129796191022848 +1662129796239023872 +1662129796284024832 +1662129796335025920 +1662129796380026880 +1662129796428027904 +1662129796470028800 +1662129796512029696 +1662129796557030656 +1662129796599031552 +1662129796641032448 +1662129796683033344 +1662129796725034240 +1662129796767035136 +1662129796812036096 +1662129796851036928 +1662129796896037888 +1662129796941038848 +1662129796992039936 +1662129797034040832 +1662129797076041728 +1662129797118042624 +1662129797163043584 +1662129797208044544 +1662129797253045504 +1662129797295046400 +1662129797337047296 +1662129797388048384 +1662129797430049280 +1662129797475050240 +1662129797526051328 +1662129797580052480 +1662129797628053504 +1662129797679054592 +1662129797718055424 +1662129797766056448 +1662129797814057472 +1662129797862058496 +1662129797907059456 +1662129797949060352 +1662129797991061248 +1662129798033062144 +1662129798075063040 +1662129798117063936 +1662129798162064896 +1662129798204065792 +1662129798246066688 +1662129798288067584 +1662129798333068544 +1662129798372069376 +1662129798420070400 +1662129798462071296 +1662129798504072192 +1662129798561073408 +1662129798609074432 +1662129798651075328 +1662129798690076160 +1662129798735077120 +1662129798777078016 +1662129798819078912 +1662129798870080000 +1662129798921081088 +1662129798966082048 +1662129799008082944 +1662129799053083904 +1662129799098084864 +1662129799140085760 +1662129799182086656 +1662129799230087680 +1662129799284088832 +1662129799329089792 +1662129799371090688 +1662129799428091904 +1662129799473092864 +1662129799515093760 +1662129799560094720 +1662129799605095680 +1662129799650096640 +1662129799692097536 +1662129799734098432 +1662129799776099328 +1662129799818100224 +1662129799863101184 +1662129799911102208 +1662129799956103168 +1662129800004104192 +1662129800046105088 +1662129800088105984 +1662129800133106944 +1662129800175107840 +1662129800223108864 +1662129800268109824 +1662129800319110912 +1662129800358111744 +1662129800400112640 +1662129800442113536 +1662129800493114624 +1662129800541115648 +1662129800589116672 +1662129800631117568 +1662129800676118528 +1662129800718119424 +1662129800772120576 +1662129800820121600 +1662129800862122496 +1662129800910123520 +1662129800955124480 +1662129801000125440 +1662129801048126464 +1662129801090127360 +1662129801150128640 +1662129801192129536 +1662129801234130432 +1662129801276131328 +1662129801321132288 +1662129801363133184 +1662129801405134080 +1662129801447134976 +1662129801495136000 +1662129801543137024 +1662129801588137984 +1662129801636139008 +1662129801681139968 +1662129801723140864 +1662129801765141760 +1662129801807142656 +1662129801855143680 +1662129801900144640 +1662129801948145664 +1662129801993146624 +1662129802044147712 +1662129802083148544 +1662129802131149568 +1662129802176150528 +1662129802224151552 +1662129802272152576 +1662129802311153408 +1662129802353154304 +1662129802398155264 +1662129802443156224 +1662129802488157184 +1662129802533158144 +1662129802584159232 +1662129802635160320 +1662129802677161216 +1662129802728162304 +1662129802773163264 +1662129802818164224 +1662129802860165120 +1662129802911166208 +1662129802950167040 +1662129802992167936 +1662129803040168960 +1662129803085169920 +1662129803136171008 +1662129803178171904 +1662129803220172800 +1662129803274173952 +1662129803316174848 +1662129803364175872 +1662129803415176960 +1662129803460177920 +1662129803499178752 +1662129803547179776 +1662129803592180736 +1662129803634181632 +1662129803676182528 +1662129803721183488 +1662129803760184320 +1662129803814185472 +1662129803856186368 +1662129803898187264 +1662129803943188224 +1662129803997189376 +1662129804039190272 +1662129804084191232 +1662129804126192128 +1662129804171193088 +1662129804216194048 +1662129804258194944 +1662129804312196096 +1662129804354196992 +1662129804402198016 +1662129804444198912 +1662129804495200000 +1662129804540200960 +1662129804582201856 +1662129804636203008 +1662129804678203904 +1662129804726204928 +1662129804768205824 +1662129804813206784 +1662129804855207680 +1662129804900208640 +1662129804951209728 +1662129804996210688 +1662129805041211648 +1662129805089212672 +1662129805140213760 +1662129805182214656 +1662129805227215616 +1662129805272216576 +1662129805314217472 +1662129805356218368 +1662129805398219264 +1662129805449220352 +1662129805494221312 +1662129805533222144 +1662129805575223040 +1662129805620224000 +1662129805662224896 +1662129805707225856 +1662129805764227072 +1662129805803227904 +1662129805842228736 +1662129805893229824 +1662129805938230784 +1662129805989231872 +1662129806031232768 +1662129806076233728 +1662129806124234752 +1662129806166235648 +1662129806205236480 +1662129806256237568 +1662129806295238400 +1662129806337239296 +1662129806379240192 +1662129806433241344 +1662129806475242240 +1662129806520243200 +1662129806565244160 +1662129806610245120 +1662129806652246016 +1662129806691246848 +1662129806736247808 +1662129806787248896 +1662129806826249728 +1662129806871250688 +1662129806916251648 +1662129806970252800 +1662129807012253696 +1662129807054254592 +1662129807096255488 +1662129807144256512 +1662129807189257472 +1662129807234258432 +1662129807282259456 +1662129807336260608 +1662129807378261504 +1662129807432262656 +1662129807480263680 +1662129807528264704 +1662129807576265728 +1662129807618266624 +1662129807657267456 +1662129807702268416 +1662129807753269504 +1662129807798270464 +1662129807840271360 +1662129807885272320 +1662129807927273216 +1662129807978274304 +1662129808017275136 +1662129808059276032 +1662129808104276992 +1662129808146277888 +1662129808197278976 +1662129808239279872 +1662129808278280704 +1662129808323281664 +1662129808374282752 +1662129808419283712 +1662129808470284800 +1662129808515285760 +1662129808557286656 +1662129808602287616 +1662129808644288512 +1662129808689289472 +1662129808734290432 +1662129808779291392 +1662129808824292352 +1662129808878293504 +1662129808920294400 +1662129808965295360 +1662129809007296256 +1662129809052297216 +1662129809094298112 +1662129809142299136 +1662129809190300160 +1662129809232301056 +1662129809277302016 +1662129809322302976 +1662129809367303936 +1662129809418305024 +1662129809460305920 +1662129809508306944 +1662129809553307904 +1662129809598308864 +1662129809646309888 +1662129809688310784 +1662129809733311744 +1662129809784312832 +1662129809832313856 +1662129809877314816 +1662129809925315840 +1662129809967316736 +1662129810012317696 +1662129810057318656 +1662129810099319552 +1662129810144320512 +1662129810186321408 +1662129810231322368 +1662129810276323328 +1662129810318324224 +1662129810360325120 +1662129810405326080 +1662129810447326976 +1662129810489327872 +1662129810543329024 +1662129810588329984 +1662129810639331072 +1662129810687332096 +1662129810732333056 +1662129810780334080 +1662129810819334912 +1662129810864335872 +1662129810909336832 +1662129810954337792 +1662129810999338752 +1662129811041339648 +1662129811086340608 +1662129811128341504 +1662129811170342400 +1662129811209343232 +1662129811263344384 +1662129811308345344 +1662129811359346432 +1662129811401347328 +1662129811446348288 +1662129811491349248 +1662129811533350144 +1662129811578351104 +1662129811626352128 +1662129811668353024 +1662129811710353920 +1662129811752354816 +1662129811794355712 +1662129811839356672 +1662129811881357568 +1662129811923358464 +1662129811974359552 +1662129812019360512 +1662129812067361536 +1662129812109362432 +1662129812151363328 +1662129812193364224 +1662129812235365120 +1662129812277366016 +1662129812322366976 +1662129812364367872 +1662129812409368832 +1662129812451369728 +1662129812499370752 +1662129812547371776 +1662129812589372672 +1662129812634373632 +1662129812679374592 +1662129812724375552 +1662129812778376704 +1662129812829377792 +1662129812874378752 +1662129812922379776 +1662129812967380736 +1662129813009381632 +1662129813057382656 +1662129813099383552 +1662129813147384576 +1662129813189385472 +1662129813231386368 +1662129813273387264 +1662129813318388224 +1662129813357389056 +1662129813402390016 +1662129813444390912 +1662129813489391872 +1662129813531392768 +1662129813579393792 +1662129813624394752 +1662129813666395648 +1662129813705396480 +1662129813747397376 +1662129813792398336 +1662129813834399232 +1662129813876400128 +1662129813918401024 +1662129813966402048 +1662129814011403008 +1662129814059404032 +1662129814104404992 +1662129814146405888 +1662129814191406848 +1662129814242407936 +1662129814284408832 +1662129814332409856 +1662129814371410688 +1662129814416411648 +1662129814467412736 +1662129814509413632 +1662129814551414528 +1662129814593415424 +1662129814635416320 +1662129814674417152 +1662129814722418176 +1662129814764419072 +1662129814818420224 +1662129814863421184 +1662129814908422144 +1662129814953423104 +1662129815001424128 +1662129815046425088 +1662129815091426048 +1662129815136427008 +1662129815181427968 +1662129815223428864 +1662129815265429760 +1662129815310430720 +1662129815352431616 +1662129815394432512 +1662129815436433408 +1662129815481434368 +1662129815526435328 +1662129815574436352 +1662129815625437440 +1662129815676438528 +1662129815721439488 +1662129815769440512 +1662129815814441472 +1662129815856442368 +1662129815910443520 +1662129815952444416 +1662129815997445376 +1662129816039446272 +1662129816087447296 +1662129816129448192 +1662129816171449088 +1662129816216450048 +1662129816264451072 +1662129816315452160 +1662129816360453120 +1662129816411454208 +1662129816456455168 +1662129816498456064 +1662129816540456960 +1662129816582457856 +1662129816627458816 +1662129816669459712 +1662129816717460736 +1662129816759461632 +1662129816813462784 +1662129816858463744 +1662129816900464640 +1662129816945465600 +1662129816996466688 +1662129817041467648 +1662129817083468544 +1662129817125469440 +1662129817179470592 +1662129817218471424 +1662129817266472448 +1662129817311473408 +1662129817359474432 +1662129817401475328 +1662129817443476224 +1662129817485477120 +1662129817527478016 +1662129817569478912 +1662129817611479808 +1662129817668481024 +1662129817713481984 +1662129817764483072 +1662129817812484096 +1662129817866485248 +1662129817908486144 +1662129817950487040 +1662129817992487936 +1662129818043489024 +1662129818094490112 +1662129818139491072 +1662129818181491968 +1662129818223492864 +1662129818268493824 +1662129818313494784 +1662129818367495936 +1662129818412496896 +1662129818454497792 +1662129818499498752 +1662129818544499712 +1662129818586500608 +1662129818631501568 +1662129818673502464 +1662129818718503424 +1662129818760504320 +1662129818802505216 +1662129818850506240 +1662129818892507136 +1662129818934508032 +1662129818982509056 +1662129819030510080 +1662129819075511040 +1662129819120512000 +1662129819162512896 +1662129819207513856 +1662129819261515008 +1662129819306515968 +1662129819354516992 +1662129819399517952 +1662129819447518976 +1662129819495520000 +1662129819534520832 +1662129819579521792 +1662129819621522688 +1662129819669523712 +1662129819714524672 +1662129819756525568 +1662129819801526528 +1662129819846527488 +1662129819888528384 +1662129819933529344 +1662129819978530304 +1662129820020531200 +1662129820062532096 +1662129820104532992 +1662129820152534016 +1662129820197534976 +1662129820239535872 +1662129820281536768 +1662129820323537664 +1662129820365538560 +1662129820410539520 +1662129820458540544 +1662129820500541440 +1662129820542542336 +1662129820587543296 +1662129820638544384 +1662129820689545472 +1662129820737546496 +1662129820782547456 +1662129820830548480 +1662129820881549568 +1662129820932550656 +1662129820983551744 +1662129821028552704 +1662129821070553600 +1662129821112554496 +1662129821157555456 +1662129821205556480 +1662129821256557568 +1662129821301558528 +1662129821343559424 +1662129821394560512 +1662129821451561728 +1662129821493562624 +1662129821535563520 +1662129821589564672 +1662129821634565632 +1662129821682566656 +1662129821724567552 +1662129821778568704 +1662129821826569728 +1662129821871570688 +1662129821913571584 +1662129821955572480 +1662129821997573376 +1662129822039574272 +1662129822084575232 +1662129822144576512 +1662129822192577536 +1662129822234578432 +1662129822276579328 +1662129822318580224 +1662129822363581184 +1662129822411582208 +1662129822453583104 +1662129822498584064 +1662129822540584960 +1662129822582585856 +1662129822624586752 +1662129822669587712 +1662129822708588544 +1662129822750589440 +1662129822792590336 +1662129822843591424 +1662129822885592320 +1662129822939593472 +1662129822981594368 +1662129823023595264 +1662129823062596096 +1662129823101596928 +1662129823143597824 +1662129823185598720 +1662129823233599744 +1662129823278600704 +1662129823332601856 +1662129823380602880 +1662129823425603840 +1662129823473604864 +1662129823521605888 +1662129823560606720 +1662129823605607680 +1662129823650608640 +1662129823698609664 +1662129823740610560 +1662129823791611648 +1662129823836612608 +1662129823878613504 +1662129823923614464 +1662129823971615488 +1662129824016616448 +1662129824067617536 +1662129824112618496 +1662129824154619392 +1662129824208620544 +1662129824253621504 +1662129824298622464 +1662129824340623360 +1662129824388624384 +1662129824430625280 +1662129824475626240 +1662129824514627072 +1662129824556627968 +1662129824607629056 +1662129824655630080 +1662129824703631104 +1662129824745632000 +1662129824790632960 +1662129824832633856 +1662129824880634880 +1662129824925635840 +1662129824970636800 +1662129825018637824 +1662129825063638784 +1662129825108639744 +1662129825153640704 +1662129825195641600 +1662129825249642752 +1662129825300643840 +1662129825345644800 +1662129825387645696 +1662129825435646720 +1662129825477647616 +1662129825522648576 +1662129825570649600 +1662129825615650560 +1662129825660651520 +1662129825702652416 +1662129825747653376 +1662129825792654336 +1662129825837655296 +1662129825876656128 +1662129825918657024 +1662129825960657920 +1662129826005658880 +1662129826047659776 +1662129826104660992 +1662129826152662016 +1662129826197662976 +1662129826236663808 +1662129826278664704 +1662129826323665664 +1662129826365666560 +1662129826416667648 +1662129826458668544 +1662129826506669568 +1662129826551670528 +1662129826599671552 +1662129826644672512 +1662129826695673600 +1662129826743674624 +1662129826785675520 +1662129826836676608 +1662129826887677696 +1662129826941678848 +1662129826992679936 +1662129827031680768 +1662129827079681792 +1662129827121682688 +1662129827166683648 +1662129827217684736 +1662129827262685696 +1662129827304686592 +1662129827349687552 +1662129827400688640 +1662129827451689728 +1662129827490690560 +1662129827544691712 +1662129827589692672 +1662129827631693568 +1662129827676694528 +1662129827730695680 +1662129827769696512 +1662129827811697408 +1662129827856698368 +1662129827901699328 +1662129827943700224 +1662129827985701120 +1662129828027702016 +1662129828072702976 +1662129828114703872 +1662129828162704896 +1662129828204705792 +1662129828246706688 +1662129828303707904 +1662129828345708800 +1662129828387709696 +1662129828432710656 +1662129828471711488 +1662129828513712384 +1662129828558713344 +1662129828612714496 +1662129828657715456 +1662129828699716352 +1662129828738717184 +1662129828780718080 +1662129828831719168 +1662129828876720128 +1662129828918721024 +1662129828963721984 +1662129829008722944 +1662129829050723840 +1662129829095724800 +1662129829134725632 +1662129829176726528 +1662129829224727552 +1662129829266728448 +1662129829311729408 +1662129829350730240 +1662129829392731136 +1662129829437732096 +1662129829479732992 +1662129829533734144 +1662129829578735104 +1662129829620736000 +1662129829671737088 +1662129829719738112 +1662129829761739008 +1662129829806739968 +1662129829854740992 +1662129829899741952 +1662129829947742976 +1662129829989743872 +1662129830034744832 +1662129830079745792 +1662129830121746688 +1662129830163747584 +1662129830205748480 +1662129830247749376 +1662129830289750272 +1662129830328751104 +1662129830376752128 +1662129830427753216 +1662129830469754112 +1662129830514755072 +1662129830565756160 +1662129830610757120 +1662129830652758016 +1662129830703759104 +1662129830745760000 +1662129830793761024 +1662129830844762112 +1662129830886763008 +1662129830928763904 +1662129830973764864 +1662129831015765760 +1662129831057766656 +1662129831099767552 +1662129831144768512 +1662129831186769408 +1662129831231770368 +1662129831276771328 +1662129831318772224 +1662129831357773056 +1662129831405774080 +1662129831447774976 +1662129831495776000 +1662129831537776896 +1662129831591778048 +1662129831636779008 +1662129831681779968 +1662129831729780992 +1662129831786782208 +1662129831834783232 +1662129831882784256 +1662129831921785088 +1662129831963785984 +1662129832005786880 +1662129832050787840 +1662129832101788928 +1662129832149789952 +1662129832188790784 +1662129832233791744 +1662129832275792640 +1662129832323793664 +1662129832368794624 +1662129832410795520 +1662129832452796416 +1662129832494797312 +1662129832536798208 +1662129832581799168 +1662129832626800128 +1662129832668801024 +1662129832710801920 +1662129832758802944 +1662129832800803840 +1662129832854804992 +1662129832896805888 +1662129832941806848 +1662129832989807872 +1662129833034808832 +1662129833076809728 +1662129833124810752 +1662129833166811648 +1662129833223812864 +1662129833265813760 +1662129833310814720 +1662129833355815680 +1662129833406816768 +1662129833448817664 +1662129833493818624 +1662129833541819648 +1662129833583820544 +1662129833628821504 +1662129833673822464 +1662129833715823360 +1662129833760824320 +1662129833799825152 +1662129833841826048 +1662129833889827072 +1662129833937828096 +1662129833985829120 +1662129834030830080 +1662129834069830912 +1662129834117831936 +1662129834162832896 +1662129834210833920 +1662129834255834880 +1662129834303835904 +1662129834348836864 +1662129834387837696 +1662129834432838656 +1662129834480839680 +1662129834528840704 +1662129834570841600 +1662129834609842432 +1662129834651843328 +1662129834693844224 +1662129834735845120 +1662129834786846208 +1662129834834847232 +1662129834876848128 +1662129834924849152 +1662129834966850048 +1662129835011851008 +1662129835056851968 +1662129835101852928 +1662129835158854144 +1662129835200855040 +1662129835245856000 +1662129835287856896 +1662129835341858048 +1662129835383858944 +1662129835428859904 +1662129835476860928 +1662129835521861888 +1662129835566862848 +1662129835605863680 +1662129835647864576 +1662129835698865664 +1662129835746866688 +1662129835788867584 +1662129835836868608 +1662129835878869504 +1662129835920870400 +1662129835965871360 +1662129836013872384 +1662129836052873216 +1662129836094874112 +1662129836142875136 +1662129836190876160 +1662129836238877184 +1662129836280878080 +1662129836328879104 +1662129836367879936 +1662129836415880960 +1662129836457881856 +1662129836499882752 +1662129836544883712 +1662129836586884608 +1662129836628885504 +1662129836679886592 +1662129836730887680 +1662129836772888576 +1662129836817889536 +1662129836862890496 +1662129836913891584 +1662129836958892544 +1662129837006893568 +1662129837057894656 +1662129837096895488 +1662129837135896320 +1662129837177897216 +1662129837219898112 +1662129837264899072 +1662129837309900032 +1662129837351900928 +1662129837393901824 +1662129837444902912 +1662129837483903744 +1662129837528904704 +1662129837573905664 +1662129837615906560 +1662129837657907456 +1662129837702908416 +1662129837747909376 +1662129837792910336 +1662129837843911424 +1662129837885912320 +1662129837930913280 +1662129837975914240 +1662129838020915200 +1662129838062916096 +1662129838104916992 +1662129838149917952 +1662129838191918848 +1662129838236919808 +1662129838278920704 +1662129838320921600 +1662129838374922752 +1662129838419923712 +1662129838464924672 +1662129838512925696 +1662129838554926592 +1662129838596927488 +1662129838638928384 +1662129838686929408 +1662129838728930304 +1662129838770931200 +1662129838812932096 +1662129838854932992 +1662129838896933888 +1662129838941934848 +1662129838983935744 +1662129839028936704 +1662129839070937600 +1662129839112938496 +1662129839154939392 +1662129839199940352 +1662129839244941312 +1662129839286942208 +1662129839328943104 +1662129839370944000 +1662129839421945088 +1662129839463945984 +1662129839508946944 +1662129839550947840 +1662129839589948672 +1662129839631949568 +1662129839673950464 +1662129839715951360 +1662129839757952256 +1662129839802953216 +1662129839844954112 +1662129839895955200 +1662129839940956160 +1662129839982957056 +1662129840024957952 +1662129840075959040 +1662129840126960128 +1662129840171961088 +1662129840213961984 +1662129840255962880 +1662129840297963776 +1662129840339964672 +1662129840381965568 +1662129840426966528 +1662129840468967424 +1662129840513968384 +1662129840564969472 +1662129840609970432 +1662129840660971520 +1662129840708972544 +1662129840759973632 +1662129840801974528 +1662129840843975424 +1662129840888976384 +1662129840933977344 +1662129840975978240 +1662129841020979200 +1662129841071980288 +1662129841116981248 +1662129841164982272 +1662129841203983104 +1662129841248984064 +1662129841302985216 +1662129841344986112 +1662129841392987136 +1662129841434988032 +1662129841479988992 +1662129841527990016 +1662129841569990912 +1662129841617991936 +1662129841662992896 +1662129841707993856 +1662129841749994752 +1662129841791995648 +1662129841833996544 +1662129841875997440 +1662129841914998272 +1662129841956999168 +1662129841999000064 +1662129842041000960 +1662129842086001920 +1662129842131002880 +1662129842188004096 +1662129842233005056 +1662129842278006016 +1662129842326007040 +1662129842368007936 +1662129842419009024 +1662129842458009856 +1662129842500010752 +1662129842542011648 +1662129842584012544 +1662129842626013440 +1662129842680014592 +1662129842719015424 +1662129842773016576 +1662129842818017536 +1662129842860018432 +1662129842905019392 +1662129842947020288 +1662129842992021248 +1662129843040022272 +1662129843079023104 +1662129843121024000 +1662129843166024960 +1662129843208025856 +1662129843250026752 +1662129843292027648 +1662129843337028608 +1662129843382029568 +1662129843433030656 +1662129843481031680 +1662129843526032640 +1662129843574033664 +1662129843625034752 +1662129843667035648 +1662129843709036544 +1662129843751037440 +1662129843793038336 +1662129843835039232 +1662129843880040192 +1662129843922041088 +1662129843973042176 +1662129844018043136 +1662129844066044160 +1662129844108045056 +1662129844150045952 +1662129844204047104 +1662129844255048192 +1662129844297049088 +1662129844339049984 +1662129844381050880 +1662129844423051776 +1662129844462052608 +1662129844504053504 +1662129844552054528 +1662129844597055488 +1662129844642056448 +1662129844687057408 +1662129844732058368 +1662129844771059200 +1662129844813060096 +1662129844855060992 +1662129844906062080 +1662129844948062976 +1662129844996064000 +1662129845035064832 +1662129845083065856 +1662129845137067008 +1662129845179067904 +1662129845227068928 +1662129845272069888 +1662129845314070784 +1662129845356071680 +1662129845401072640 +1662129845443073536 +1662129845485074432 +1662129845527075328 +1662129845572076288 +1662129845617077248 +1662129845662078208 +1662129845704079104 +1662129845746080000 +1662129845788080896 +1662129845836081920 +1662129845878082816 +1662129845926083840 +1662129845974084864 +1662129846019085824 +1662129846067086848 +1662129846112087808 +1662129846157088768 +1662129846202089728 +1662129846244090624 +1662129846286091520 +1662129846328092416 +1662129846385093632 +1662129846424094464 +1662129846469095424 +1662129846508096256 +1662129846553097216 +1662129846598098176 +1662129846649099264 +1662129846697100288 +1662129846739101184 +1662129846787102208 +1662129846832103168 +1662129846874104064 +1662129846919105024 +1662129846964105984 +1662129847006106880 +1662129847051107840 +1662129847105108992 +1662129847156110080 +1662129847201111040 +1662129847246112000 +1662129847288112896 +1662129847336113920 +1662129847384114944 +1662129847423115776 +1662129847468116736 +1662129847519117824 +1662129847567118848 +1662129847612119808 +1662129847654120704 +1662129847702121728 +1662129847744122624 +1662129847783123456 +1662129847831124480 +1662129847873125376 +1662129847921126400 +1662129847963127296 +1662129848005128192 +1662129848053129216 +1662129848107130368 +1662129848152131328 +1662129848197132288 +1662129848242133248 +1662129848284134144 +1662129848332135168 +1662129848380136192 +1662129848422137088 +1662129848467138048 +1662129848509138944 +1662129848551139840 +1662129848593140736 +1662129848632141568 +1662129848674142464 +1662129848719143424 +1662129848764144384 +1662129848812145408 +1662129848857146368 +1662129848896147200 +1662129848941148160 +1662129848992149248 +1662129849034150144 +1662129849076151040 +1662129849127152128 +1662129849169153024 +1662129849223154176 +1662129849277155328 +1662129849325156352 +1662129849367157248 +1662129849418158336 +1662129849466159360 +1662129849514160384 +1662129849556161280 +1662129849604162304 +1662129849652163328 +1662129849694164224 +1662129849736165120 +1662129849781166080 +1662129849832167168 +1662129849877168128 +1662129849922169088 +1662129849964169984 +1662129850009170944 +1662129850051171840 +1662129850093172736 +1662129850138173696 +1662129850180174592 +1662129850222175488 +1662129850264176384 +1662129850315177472 +1662129850360178432 +1662129850399179264 +1662129850444180224 +1662129850489181184 +1662129850531182080 +1662129850576183040 +1662129850621184000 +1662129850669185024 +1662129850714185984 +1662129850759186944 +1662129850804187904 +1662129850846188800 +1662129850894189824 +1662129850936190720 +1662129850987191808 +1662129851029192704 +1662129851074193664 +1662129851119194624 +1662129851164195584 +1662129851209196544 +1662129851254197504 +1662129851299198464 +1662129851338199296 +1662129851380200192 +1662129851422201088 +1662129851470202112 +1662129851515203072 +1662129851554203904 +1662129851596204800 +1662129851647205888 +1662129851695206912 +1662129851737207808 +1662129851785208832 +1662129851830209792 +1662129851872210688 +1662129851917211648 +1662129851959212544 +1662129852001213440 +1662129852049214464 +1662129852100215552 +1662129852148216576 +1662129852190217472 +1662129852229218304 +1662129852271219200 +1662129852313220096 +1662129852355220992 +1662129852409222144 +1662129852451223040 +1662129852496224000 +1662129852538224896 +1662129852583225856 +1662129852625226752 +1662129852676227840 +1662129852724228864 +1662129852766229760 +1662129852811230720 +1662129852859231744 +1662129852907232768 +1662129852955233792 +1662129852997234688 +1662129853042235648 +1662129853090236672 +1662129853138237696 +1662129853189238784 +1662129853237239808 +1662129853279240704 +1662129853324241664 +1662129853366242560 +1662129853408243456 +1662129853453244416 +1662129853501245440 +1662129853543246336 +1662129853591247360 +1662129853636248320 +1662129853678249216 +1662129853723250176 +1662129853771251200 +1662129853816252160 +1662129853873253376 +1662129853924254464 +1662129853969255424 +1662129854011256320 +1662129854056257280 +1662129854098258176 +1662129854140259072 +1662129854185260032 +1662129854233261056 +1662129854284262144 +1662129854329263104 +1662129854374264064 +1662129854422265088 +1662129854473266176 +1662129854521267200 +1662129854560268032 +1662129854605268992 +1662129854644269824 +1662129854686270720 +1662129854728271616 +1662129854782272768 +1662129854827273728 +1662129854869274624 +1662129854911275520 +1662129854962276608 +1662129855010277632 +1662129855055278592 +1662129855100279552 +1662129855142280448 +1662129855187281408 +1662129855235282432 +1662129855283283456 +1662129855328284416 +1662129855370285312 +1662129855409286144 +1662129855454287104 +1662129855499288064 +1662129855541288960 +1662129855580289792 +1662129855625290752 +1662129855670291712 +1662129855712292608 +1662129855754293504 +1662129855799294464 +1662129855841295360 +1662129855886296320 +1662129855937297408 +1662129855976298240 +1662129856018299136 +1662129856066300160 +1662129856111301120 +1662129856156302080 +1662129856204303104 +1662129856255304192 +1662129856297305088 +1662129856339305984 +1662129856381306880 +1662129856426307840 +1662129856465308672 +1662129856507309568 +1662129856549310464 +1662129856594311424 +1662129856636312320 +1662129856678313216 +1662129856720314112 +1662129856768315136 +1662129856813316096 +1662129856855316992 +1662129856897317888 +1662129856939318784 +1662129856984319744 +1662129857029320704 +1662129857074321664 +1662129857122322688 +1662129857167323648 +1662129857215324672 +1662129857260325632 +1662129857302326528 +1662129857350327552 +1662129857395328512 +1662129857437329408 +1662129857479330304 +1662129857521331200 +1662129857566332160 +1662129857614333184 +1662129857656334080 +1662129857698334976 +1662129857743335936 +1662129857785336832 +1662129857827337728 +1662129857875338752 +1662129857917339648 +1662129857959340544 +1662129858001341440 +1662129858049342464 +1662129858088343296 +1662129858127344128 +1662129858169345024 +1662129858211345920 +1662129858259346944 +1662129858301347840 +1662129858352348928 +1662129858403350016 +1662129858448350976 +1662129858496352000 +1662129858541352960 +1662129858589353984 +1662129858637355008 +1662129858688356096 +1662129858727356928 +1662129858769357824 +1662129858814358784 +1662129858856359680 +1662129858898360576 +1662129858943361536 +1662129858985362432 +1662129859042363648 +1662129859087364608 +1662129859126365440 +1662129859171366400 +1662129859213367296 +1662129859255368192 +1662129859300369152 +1662129859342370048 +1662129859390371072 +1662129859432371968 +1662129859477372928 +1662129859528374016 +1662129859570374912 +1662129859615375872 +1662129859657376768 +1662129859699377664 +1662129859750378752 +1662129859792379648 +1662129859834380544 +1662129859879381504 +1662129859921382400 +1662129859963383296 +1662129860008384256 +1662129860053385216 +1662129860095386112 +1662129860140387072 +1662129860182387968 +1662129860233389056 +1662129860275389952 +1662129860320390912 +1662129860368391936 +1662129860419393024 +1662129860464393984 +1662129860506394880 +1662129860548395776 +1662129860590396672 +1662129860641397760 +1662129860683398656 +1662129860731399680 +1662129860776400640 +1662129860818401536 +1662129860869402624 +1662129860917403648 +1662129860959404544 +1662129861007405568 +1662129861055406592 +1662129861097407488 +1662129861142408448 +1662129861184409344 +1662129861229410304 +1662129861274411264 +1662129861319412224 +1662129861364413184 +1662129861415414272 +1662129861457415168 +1662129861496416000 +1662129861538416896 +1662129861586417920 +1662129861625418752 +1662129861667419648 +1662129861712420608 +1662129861754421504 +1662129861796422400 +1662129861838423296 +1662129861886424320 +1662129861937425408 +1662129861982426368 +1662129862024427264 +1662129862066428160 +1662129862114429184 +1662129862159430144 +1662129862201431040 +1662129862243431936 +1662129862291432960 +1662129862336433920 +1662129862378434816 +1662129862423435776 +1662129862465436672 +1662129862516437760 +1662129862561438720 +1662129862603439616 +1662129862648440576 +1662129862687441408 +1662129862729442304 +1662129862777443328 +1662129862825444352 +1662129862867445248 +1662129862912446208 +1662129862960447232 +1662129863005448192 +1662129863056449280 +1662129863101450240 +1662129863140451072 +1662129863182451968 +1662129863224452864 +1662129863266453760 +1662129863317454848 +1662129863359455744 +1662129863407456768 +1662129863455457792 +1662129863497458688 +1662129863542459648 +1662129863584460544 +1662129863626461440 +1662129863674462464 +1662129863722463488 +1662129863764464384 +1662129863806465280 +1662129863845466112 +1662129863890467072 +1662129863932467968 +1662129863977468928 +1662129864019469824 +1662129864061470720 +1662129864106471680 +1662129864154472704 +1662129864202473728 +1662129864244474624 +1662129864286475520 +1662129864331476480 +1662129864382477568 +1662129864427478528 +1662129864472479488 +1662129864517480448 +1662129864559481344 +1662129864601482240 +1662129864646483200 +1662129864694484224 +1662129864733485056 +1662129864778486016 +1662129864829487104 +1662129864880488192 +1662129864922489088 +1662129864964489984 +1662129865006490880 +1662129865054491904 +1662129865099492864 +1662129865141493760 +1662129865183494656 +1662129865222495488 +1662129865270496512 +1662129865312497408 +1662129865351498240 +1662129865393499136 +1662129865438500096 +1662129865489501184 +1662129865534502144 +1662129865579503104 +1662129865624504064 +1662129865666504960 +1662129865708505856 +1662129865753506816 +1662129865804507904 +1662129865846508800 +1662129865894509824 +1662129865939510784 +1662129865981511680 +1662129866023512576 +1662129866077513728 +1662129866125514752 +1662129866167515648 +1662129866212516608 +1662129866257517568 +1662129866308518656 +1662129866353519616 +1662129866398520576 +1662129866440521472 +1662129866485522432 +1662129866530523392 +1662129866578524416 +1662129866620525312 +1662129866662526208 +1662129866707527168 +1662129866752528128 +1662129866794529024 +1662129866836529920 +1662129866875530752 +1662129866920531712 +1662129866974532864 +1662129867022533888 +1662129867064534784 +1662129867106535680 +1662129867151536640 +1662129867190537472 +1662129867244538624 +1662129867289539584 +1662129867331540480 +1662129867385541632 +1662129867427542528 +1662129867472543488 +1662129867517544448 +1662129867562545408 +1662129867607546368 +1662129867649547264 +1662129867697548288 +1662129867742549248 +1662129867787550208 +1662129867829551104 +1662129867868551936 +1662129867916552960 +1662129867961553920 +1662129868009554944 +1662129868054555904 +1662129868096556800 +1662129868150557952 +1662129868192558848 +1662129868234559744 +1662129868279560704 +1662129868327561728 +1662129868378562816 +1662129868423563776 +1662129868465564672 +1662129868507565568 +1662129868549566464 +1662129868591567360 +1662129868633568256 +1662129868675569152 +1662129868723570176 +1662129868768571136 +1662129868822572288 +1662129868867573248 +1662129868909574144 +1662129868957575168 +1662129869002576128 +1662129869050577152 +1662129869092578048 +1662129869137579008 +1662129869182579968 +1662129869224580864 +1662129869266581760 +1662129869314582784 +1662129869356583680 +1662129869401584640 +1662129869449585664 +1662129869491586560 +1662129869533587456 +1662129869575588352 +1662129869614589184 +1662129869659590144 +1662129869701591040 +1662129869749592064 +1662129869788592896 +1662129869830593792 +1662129869875594752 +1662129869917595648 +1662129869962596608 +1662129870010597632 +1662129870055598592 +1662129870097599488 +1662129870142600448 +1662129870184601344 +1662129870226602240 +1662129870271603200 +1662129870316604160 +1662129870355604992 +1662129870409606144 +1662129870451607040 +1662129870502608128 +1662129870541608960 +1662129870586609920 +1662129870628610816 +1662129870673611776 +1662129870718612736 +1662129870763613696 +1662129870808614656 +1662129870850615552 +1662129870892616448 +1662129870943617536 +1662129870985618432 +1662129871033619456 +1662129871078620416 +1662129871129621504 +1662129871171622400 +1662129871216623360 +1662129871258624256 +1662129871306625280 +1662129871348626176 +1662129871390627072 +1662129871432627968 +1662129871474628864 +1662129871525629952 +1662129871573630976 +1662129871615631872 +1662129871657632768 +1662129871702633728 +1662129871744634624 +1662129871789635584 +1662129871837636608 +1662129871885637632 +1662129871930638592 +1662129871972639488 +1662129872020640512 +1662129872065641472 +1662129872107642368 +1662129872149643264 +1662129872191644160 +1662129872239645184 +1662129872287646208 +1662129872332647168 +1662129872374648064 +1662129872419649024 +1662129872464649984 +1662129872509650944 +1662129872557651968 +1662129872602652928 +1662129872644653824 +1662129872689654784 +1662129872731655680 +1662129872773656576 +1662129872827657728 +1662129872875658752 +1662129872926659840 +1662129872977660928 +1662129873025661952 +1662129873070662912 +1662129873124664064 +1662129873178665216 +1662129873223666176 +1662129873271667200 +1662129873328668416 +1662129873370669312 +1662129873415670272 +1662129873460671232 +1662129873505672192 +1662129873547673088 +1662129873592674048 +1662129873634674944 +1662129873679675904 +1662129873721676800 +1662129873763677696 +1662129873808678656 +1662129873853679616 +1662129873898680576 +1662129873940681472 +1662129873982682368 +1662129874024683264 +1662129874072684288 +1662129874123685376 +1662129874168686336 +1662129874210687232 +1662129874255688192 +1662129874297689088 +1662129874348690176 +1662129874393691136 +1662129874435692032 +1662129874477692928 +1662129874522693888 +1662129874567694848 +1662129874609695744 +1662129874651696640 +1662129874693697536 +1662129874735698432 +1662129874780699392 +1662129874822700288 +1662129874867701248 +1662129874921702400 +1662129874966703360 +1662129875011704320 +1662129875053705216 +1662129875095706112 +1662129875137707008 +1662129875179707904 +1662129875221708800 +1662129875266709760 +1662129875311710720 +1662129875356711680 +1662129875395712512 +1662129875437713408 +1662129875482714368 +1662129875524715264 +1662129875569716224 +1662129875611717120 +1662129875650717952 +1662129875692718848 +1662129875743719936 +1662129875788720896 +1662129875830721792 +1662129875872722688 +1662129875917723648 +1662129875959724544 +1662129876001725440 +1662129876052726528 +1662129876103727616 +1662129876148728576 +1662129876190729472 +1662129876238730496 +1662129876286731520 +1662129876328732416 +1662129876373733376 +1662129876415734272 +1662129876463735296 +1662129876508736256 +1662129876550737152 +1662129876592738048 +1662129876634738944 +1662129876679739904 +1662129876727740928 +1662129876775741952 +1662129876817742848 +1662129876859743744 +1662129876904744704 +1662129876943745536 +1662129876985746432 +1662129877030747392 +1662129877075748352 +1662129877120749312 +1662129877165750272 +1662129877222751488 +1662129877270752512 +1662129877312753408 +1662129877357754368 +1662129877399755264 +1662129877441756160 +1662129877483757056 +1662129877528758016 +1662129877567758848 +1662129877609759744 +1662129877651760640 +1662129877696761600 +1662129877735762432 +1662129877783763456 +1662129877831764480 +1662129877873765376 +1662129877924766464 +1662129877969767424 +1662129878014768384 +1662129878053769216 +1662129878095770112 +1662129878140771072 +1662129878185772032 +1662129878227772928 +1662129878266773760 +1662129878311774720 +1662129878353775616 +1662129878401776640 +1662129878446777600 +1662129878488778496 +1662129878530779392 +1662129878578780416 +1662129878617781248 +1662129878665782272 +1662129878707783168 +1662129878752784128 +1662129878794785024 +1662129878845786112 +1662129878890787072 +1662129878932787968 +1662129878974788864 +1662129879025789952 +1662129879073790976 +1662129879115791872 +1662129879166792960 +1662129879214793984 +1662129879256794880 +1662129879295795712 +1662129879337796608 +1662129879382797568 +1662129879427798528 +1662129879469799424 +1662129879514800384 +1662129879559801344 +1662129879604802304 +1662129879652803328 +1662129879700804352 +1662129879742805248 +1662129879784806144 +1662129879832807168 +1662129879877808128 +1662129879925809152 +1662129879967810048 +1662129880009810944 +1662129880060812032 +1662129880105812992 +1662129880144813824 +1662129880189814784 +1662129880231815680 +1662129880279816704 +1662129880321817600 +1662129880366818560 +1662129880408819456 +1662129880456820480 +1662129880498821376 +1662129880540822272 +1662129880585823232 +1662129880624824064 +1662129880669825024 +1662129880711825920 +1662129880756826880 +1662129880801827840 +1662129880843828736 +1662129880885829632 +1662129880933830656 +1662129880981831680 +1662129881029832704 +1662129881074833664 +1662129881116834560 +1662129881158835456 +1662129881203836416 +1662129881245837312 +1662129881293838336 +1662129881335839232 +1662129881383840256 +1662129881425841152 +1662129881470842112 +1662129881524843264 +1662129881569844224 +1662129881611845120 +1662129881656846080 +1662129881704847104 +1662129881749848064 +1662129881794849024 +1662129881836849920 +1662129881887851008 +1662129881929851904 +1662129881977852928 +1662129882019853824 +1662129882064854784 +1662129882118855936 +1662129882163856896 +1662129882211857920 +1662129882253858816 +1662129882298859776 +1662129882340860672 +1662129882382861568 +1662129882421862400 +1662129882463863296 +1662129882508864256 +1662129882553865216 +1662129882601866240 +1662129882643867136 +1662129882685868032 +1662129882733869056 +1662129882781870080 +1662129882826871040 +1662129882871872000 +1662129882913872896 +1662129882955873792 +1662129882997874688 +1662129883036875520 +1662129883078876416 +1662129883132877568 +1662129883174878464 +1662129883216879360 +1662129883267880448 +1662129883309881344 +1662129883351882240 +1662129883399883264 +1662129883444884224 +1662129883483885056 +1662129883525885952 +1662129883576887040 +1662129883624888064 +1662129883675889152 +1662129883723890176 +1662129883762891008 +1662129883810892032 +1662129883861893120 +1662129883903894016 +1662129883948894976 +1662129883996896000 +1662129884038896896 +1662129884092898048 +1662129884137899008 +1662129884185900032 +1662129884230900992 +1662129884281902080 +1662129884320902912 +1662129884368903936 +1662129884407904768 +1662129884452905728 +1662129884497906688 +1662129884548907776 +1662129884593908736 +1662129884635909632 +1662129884686910720 +1662129884737911808 +1662129884782912768 +1662129884827913728 +1662129884872914688 +1662129884923915776 +1662129884968916736 +1662129885010917632 +1662129885049918464 +1662129885091919360 +1662129885142920448 +1662129885187921408 +1662129885229922304 +1662129885277923328 +1662129885322924288 +1662129885367925248 +1662129885409926144 +1662129885454927104 +1662129885505928192 +1662129885550929152 +1662129885595930112 +1662129885643931136 +1662129885685932032 +1662129885730932992 +1662129885772933888 +1662129885826935040 +1662129885877936128 +1662129885919937024 +1662129885961937920 +1662129886006938880 +1662129886060940032 +1662129886105940992 +1662129886147941888 +1662129886192942848 +1662129886234943744 +1662129886276944640 +1662129886318945536 +1662129886378946816 +1662129886423947776 +1662129886465948672 +1662129886510949632 +1662129886558950656 +1662129886603951616 +1662129886645952512 +1662129886687953408 +1662129886732954368 +1662129886777955328 +1662129886819956224 +1662129886861957120 +1662129886909958144 +1662129886951959040 +1662129886996960000 +1662129887038960896 +1662129887080961792 +1662129887134962944 +1662129887173963776 +1662129887218964736 +1662129887263965696 +1662129887308966656 +1662129887353967616 +1662129887398968576 +1662129887449969664 +1662129887491970560 +1662129887533971456 +1662129887578972416 +1662129887623973376 +1662129887665974272 +1662129887710975232 +1662129887758976256 +1662129887797977088 +1662129887839977984 +1662129887881978880 +1662129887929979904 +1662129887974980864 +1662129888019981824 +1662129888061982720 +1662129888112983808 +1662129888151984640 +1662129888199985664 +1662129888244986624 +1662129888286987520 +1662129888331988480 +1662129888376989440 +1662129888418990336 +1662129888460991232 +1662129888508992256 +1662129888553993216 +1662129888595994112 +1662129888637995008 +1662129888679995904 +1662129888721996800 +1662129888763997696 +1662129888808998656 +1662129888850999552 +1662129888893000448 +1662129888935001344 +1662129888980002304 +1662129889025003264 +1662129889064004096 +1662129889112005120 +1662129889157006080 +1662129889202007040 +1662129889241007872 +1662129889289008896 +1662129889331009792 +1662129889376010752 +1662129889424011776 +1662129889466012672 +1662129889508013568 +1662129889559014656 +1662129889604015616 +1662129889643016448 +1662129889685017344 +1662129889730018304 +1662129889772019200 +1662129889826020352 +1662129889865021184 +1662129889904022016 +1662129889952023040 +1662129889997024000 +1662129890039024896 +1662129890081025792 +1662129890123026688 +1662129890171027712 +1662129890213028608 +1662129890255029504 +1662129890297030400 +1662129890339031296 +1662129890381032192 +1662129890423033088 +1662129890471034112 +1662129890513035008 +1662129890558035968 +1662129890603036928 +1662129890648037888 +1662129890702039040 +1662129890750040064 +1662129890789040896 +1662129890840041984 +1662129890882042880 +1662129890927043840 +1662129890972044800 +1662129891020045824 +1662129891062046720 +1662129891116047872 +1662129891164048896 +1662129891209049856 +1662129891257050880 +1662129891299051776 +1662129891344052736 +1662129891386053632 +1662129891428054528 +1662129891467055360 +1662129891509056256 +1662129891554057216 +1662129891599058176 +1662129891644059136 +1662129891686060032 +1662129891743061248 +1662129891785062144 +1662129891824062976 +1662129891863063808 +1662129891911064832 +1662129891956065792 +1662129891998066688 +1662129892040067584 +1662129892088068608 +1662129892133069568 +1662129892175070464 +1662129892217071360 +1662129892259072256 +1662129892304073216 +1662129892346074112 +1662129892391075072 +1662129892436076032 +1662129892484077056 +1662129892523077888 +1662129892565078784 +1662129892610079744 +1662129892655080704 +1662129892697081600 +1662129892745082624 +1662129892787083520 +1662129892835084544 +1662129892880085504 +1662129892931086592 +1662129892973087488 +1662129893015088384 +1662129893057089280 +1662129893096090112 +1662129893138091008 +1662129893183091968 +1662129893228092928 +1662129893276093952 +1662129893327095040 +1662129893369095936 +1662129893414096896 +1662129893459097856 +1662129893501098752 +1662129893546099712 +1662129893600100864 +1662129893645101824 +1662129893687102720 +1662129893735103744 +1662129893774104576 +1662129893816105472 +1662129893858106368 +1662129893900107264 +1662129893948108288 +1662129893990109184 +1662129894035110144 +1662129894080111104 +1662129894128112128 +1662129894170113024 +1662129894215113984 +1662129894257114880 +1662129894299115776 +1662129894341116672 +1662129894386117632 +1662129894425118464 +1662129894467119360 +1662129894515120384 +1662129894560121344 +1662129894611122432 +1662129894650123264 +1662129894695124224 +1662129894737125120 +1662129894782126080 +1662129894833127168 +1662129894884128256 +1662129894929129216 +1662129894977130240 +1662129895034131456 +1662129895085132544 +1662129895130133504 +1662129895172134400 +1662129895214135296 +1662129895262136320 +1662129895304137216 +1662129895343138048 +1662129895385138944 +1662129895427139840 +1662129895466140672 +1662129895511141632 +1662129895568142848 +1662129895616143872 +1662129895661144832 +1662129895709145856 +1662129895760146944 +1662129895808147968 +1662129895850148864 +1662129895895149824 +1662129895934150656 +1662129895979151616 +1662129896033152768 +1662129896075153664 +1662129896126154752 +1662129896171155712 +1662129896216156672 +1662129896258157568 +1662129896303158528 +1662129896348159488 +1662129896390160384 +1662129896438161408 +1662129896486162432 +1662129896534163456 +1662129896582164480 +1662129896621165312 +1662129896669166336 +1662129896714167296 +1662129896756168192 +1662129896801169152 +1662129896849170176 +1662129896897171200 +1662129896945172224 +1662129896990173184 +1662129897032174080 +1662129897077175040 +1662129897122176000 +1662129897170177024 +1662129897212177920 +1662129897254178816 +1662129897299179776 +1662129897341180672 +1662129897380181504 +1662129897428182528 +1662129897479183616 +1662129897521184512 +1662129897566185472 +1662129897605186304 +1662129897647187200 +1662129897695188224 +1662129897734189056 +1662129897776189952 +1662129897821190912 +1662129897863191808 +1662129897908192768 +1662129897956193792 +1662129897998194688 +1662129898037195520 +1662129898085196544 +1662129898127197440 +1662129898169198336 +1662129898220199424 +1662129898262200320 +1662129898307201280 +1662129898349202176 +1662129898397203200 +1662129898448204288 +1662129898493205248 +1662129898538206208 +1662129898586207232 +1662129898646208512 +1662129898694209536 +1662129898736210432 +1662129898784211456 +1662129898829212416 +1662129898877213440 +1662129898919214336 +1662129898970215424 +1662129899015216384 +1662129899063217408 +1662129899111218432 +1662129899156219392 +1662129899204220416 +1662129899246221312 +1662129899291222272 +1662129899333223168 +1662129899378224128 +1662129899420225024 +1662129899462225920 +1662129899504226816 +1662129899549227776 +1662129899591228672 +1662129899636229632 +1662129899687230720 +1662129899732231680 +1662129899774232576 +1662129899816233472 +1662129899858234368 +1662129899900235264 +1662129899945236224 +1662129899993237248 +1662129900041238272 +1662129900083239168 +1662129900137240320 +1662129900188241408 +1662129900233242368 +1662129900284243456 +1662129900329244416 +1662129900371245312 +1662129900410246144 +1662129900449246976 +1662129900497248000 +1662129900539248896 +1662129900584249856 +1662129900635250944 +1662129900683251968 +1662129900725252864 +1662129900770253824 +1662129900821254912 +1662129900863255808 +1662129900905256704 +1662129900956257792 +1662129900998258688 +1662129901040259584 +1662129901082260480 +1662129901136261632 +1662129901178262528 +1662129901217263360 +1662129901262264320 +1662129901304265216 +1662129901352266240 +1662129901403267328 +1662129901448268288 +1662129901493269248 +1662129901535270144 +1662129901577271040 +1662129901631272192 +1662129901676273152 +1662129901715273984 +1662129901760274944 +1662129901799275776 +1662129901844276736 +1662129901886277632 +1662129901928278528 +1662129901973279488 +1662129902015280384 +1662129902057281280 +1662129902099282176 +1662129902141283072 +1662129902183283968 +1662129902225284864 +1662129902270285824 +1662129902318286848 +1662129902363287808 +1662129902408288768 +1662129902459289856 +1662129902507290880 +1662129902555291904 +1662129902597292800 +1662129902651293952 +1662129902696294912 +1662129902738295808 +1662129902789296896 +1662129902831297792 +1662129902882298880 +1662129902936300032 +1662129902978300928 +1662129903020301824 +1662129903062302720 +1662129903110303744 +1662129903155304704 +1662129903197305600 +1662129903239306496 +1662129903281307392 +1662129903323308288 +1662129903365309184 +1662129903410310144 +1662129903455311104 +1662129903494311936 +1662129903536312832 +1662129903578313728 +1662129903617314560 +1662129903662315520 +1662129903704316416 +1662129903749317376 +1662129903791318272 +1662129903833319168 +1662129903875320064 +1662129903920321024 +1662129903962321920 +1662129904019323136 +1662129904061324032 +1662129904106324992 +1662129904151325952 +1662129904199326976 +1662129904241327872 +1662129904289328896 +1662129904331329792 +1662129904379330816 +1662129904421331712 +1662129904463332608 +1662129904505333504 +1662129904547334400 +1662129904592335360 +1662129904634336256 +1662129904679337216 +1662129904721338112 +1662129904766339072 +1662129904805339904 +1662129904847340800 +1662129904889341696 +1662129904931342592 +1662129904976343552 +1662129905021344512 +1662129905063345408 +1662129905105346304 +1662129905156347392 +1662129905195348224 +1662129905231348992 +1662129905276349952 +1662129905318350848 +1662129905363351808 +1662129905405352704 +1662129905450353664 +1662129905492354560 +1662129905537355520 +1662129905591356672 +1662129905633357568 +1662129905687358720 +1662129905738359808 +1662129905780360704 +1662129905825361664 +1662129905867362560 +1662129905918363648 +1662129905960364544 +1662129906005365504 +1662129906047366400 +1662129906089367296 +1662129906131368192 +1662129906176369152 +1662129906224370176 +1662129906266371072 +1662129906311372032 +1662129906362373120 +1662129906404374016 +1662129906449374976 +1662129906494375936 +1662129906536376832 +1662129906578377728 +1662129906623378688 +1662129906668379648 +1662129906707380480 +1662129906749381376 +1662129906803382528 +1662129906845383424 +1662129906887384320 +1662129906932385280 +1662129906974386176 +1662129907019387136 +1662129907064388096 +1662129907106388992 +1662129907151389952 +1662129907196390912 +1662129907238391808 +1662129907286392832 +1662129907331393792 +1662129907370394624 +1662129907412395520 +1662129907454396416 +1662129907499397376 +1662129907541398272 +1662129907583399168 +1662129907625400064 +1662129907670401024 +1662129907712401920 +1662129907760402944 +1662129907811404032 +1662129907853404928 +1662129907898405888 +1662129907937406720 +1662129907982407680 +1662129908027408640 +1662129908072409600 +1662129908123410688 +1662129908168411648 +1662129908216412672 +1662129908258413568 +1662129908303414528 +1662129908345415424 +1662129908387416320 +1662129908441417472 +1662129908498418688 +1662129908549419776 +1662129908591420672 +1662129908639421696 +1662129908687422720 +1662129908729423616 +1662129908771424512 +1662129908816425472 +1662129908858426368 +1662129908915427584 +1662129908960428544 +1662129909005429504 +1662129909050430464 +1662129909095431424 +1662129909140432384 +1662129909179433216 +1662129909221434112 +1662129909266435072 +1662129909305435904 +1662129909347436800 +1662129909392437760 +1662129909434438656 +1662129909479439616 +1662129909521440512 +1662129909572441600 +1662129909611442432 +1662129909653443328 +1662129909698444288 +1662129909740445184 +1662129909782446080 +1662129909824446976 +1662129909866447872 +1662129909905448704 +1662129909959449856 +1662129910001450752 +1662129910049451776 +1662129910091452672 +1662129910136453632 +1662129910181454592 +1662129910223455488 +1662129910265456384 +1662129910313457408 +1662129910364458496 +1662129910409459456 +1662129910448460288 +1662129910496461312 +1662129910541462272 +1662129910589463296 +1662129910634464256 +1662129910679465216 +1662129910718466048 +1662129910760466944 +1662129910808467968 +1662129910850468864 +1662129910892469760 +1662129910934470656 +1662129910985471744 +1662129911030472704 +1662129911072473600 +1662129911114474496 +1662129911162475520 +1662129911204476416 +1662129911255477504 +1662129911306478592 +1662129911348479488 +1662129911390480384 +1662129911429481216 +1662129911474482176 +1662129911519483136 +1662129911561484032 +1662129911606484992 +1662129911651485952 +1662129911693486848 +1662129911732487680 +1662129911774488576 +1662129911828489728 +1662129911876490752 +1662129911924491776 +1662129911975492864 +1662129912020493824 +1662129912062494720 +1662129912107495680 +1662129912155496704 +1662129912197497600 +1662129912239498496 +1662129912281499392 +1662129912326500352 +1662129912368501248 +1662129912413502208 +1662129912452503040 +1662129912497504000 +1662129912539504896 +1662129912584505856 +1662129912626506752 +1662129912671507712 +1662129912710508544 +1662129912755509504 +1662129912797510400 +1662129912839511296 +1662129912881512192 +1662129912926513152 +1662129912974514176 +1662129913019515136 +1662129913067516160 +1662129913121517312 +1662129913169518336 +1662129913211519232 +1662129913253520128 +1662129913301521152 +1662129913349522176 +1662129913391523072 +1662129913436524032 +1662129913484525056 +1662129913529526016 +1662129913574526976 +1662129913616527872 +1662129913667528960 +1662129913709529856 +1662129913751530752 +1662129913793531648 +1662129913844532736 +1662129913889533696 +1662129913931534592 +1662129913979535616 +1662129914030536704 +1662129914078537728 +1662129914123538688 +1662129914168539648 +1662129914219540736 +1662129914267541760 +1662129914318542848 +1662129914363543808 +1662129914411544832 +1662129914453545728 +1662129914495546624 +1662129914540547584 +1662129914588548608 +1662129914633549568 +1662129914681550592 +1662129914729551616 +1662129914777552640 +1662129914825553664 +1662129914867554560 +1662129914909555456 +1662129914960556544 +1662129915002557440 +1662129915047558400 +1662129915089559296 +1662129915134560256 +1662129915176561152 +1662129915218562048 +1662129915260562944 +1662129915302563840 +1662129915353564928 +1662129915395565824 +1662129915440566784 +1662129915485567744 +1662129915533568768 +1662129915575569664 +1662129915617570560 +1662129915659571456 +1662129915704572416 +1662129915752573440 +1662129915797574400 +1662129915839575296 +1662129915881576192 +1662129915929577216 +1662129915971578112 +1662129916016579072 +1662129916067580160 +1662129916118581248 +1662129916160582144 +1662129916205583104 +1662129916244583936 +1662129916295585024 +1662129916349586176 +1662129916394587136 +1662129916442588160 +1662129916487589120 +1662129916535590144 +1662129916586591232 +1662129916631592192 +1662129916673593088 +1662129916721594112 +1662129916766595072 +1662129916811596032 +1662129916868597248 +1662129916913598208 +1662129916958599168 +1662129917000600064 +1662129917051601152 +1662129917096602112 +1662129917147603200 +1662129917192604160 +1662129917234605056 +1662129917276605952 +1662129917318606848 +1662129917360607744 +1662129917402608640 +1662129917450609664 +1662129917504610816 +1662129917549611776 +1662129917594612736 +1662129917639613696 +1662129917681614592 +1662129917732615680 +1662129917780616704 +1662129917825617664 +1662129917873618688 +1662129917921619712 +1662129917960620544 +1662129918005621504 +1662129918044622336 +1662129918089623296 +1662129918137624320 +1662129918182625280 +1662129918239626496 +1662129918278627328 +1662129918320628224 +1662129918362629120 +1662129918407630080 +1662129918455631104 +1662129918506632192 +1662129918554633216 +1662129918596634112 +1662129918641635072 +1662129918692636160 +1662129918740637184 +1662129918782638080 +1662129918824638976 +1662129918869639936 +1662129918917640960 +1662129918968642048 +1662129919013643008 +1662129919055643904 +1662129919100644864 +1662129919145645824 +1662129919187646720 +1662129919226647552 +1662129919280648704 +1662129919325649664 +1662129919367650560 +1662129919415651584 +1662129919463652608 +1662129919505653504 +1662129919556654592 +1662129919601655552 +1662129919649656576 +1662129919694657536 +1662129919736658432 +1662129919781659392 +1662129919823660288 +1662129919865661184 +1662129919910662144 +1662129919952663040 +1662129919991663872 +1662129920033664768 +1662129920081665792 +1662129920126666752 +1662129920168667648 +1662129920219668736 +1662129920261669632 +1662129920303670528 +1662129920348671488 +1662129920396672512 +1662129920444673536 +1662129920483674368 +1662129920534675456 +1662129920582676480 +1662129920627677440 +1662129920669678336 +1662129920711679232 +1662129920753680128 +1662129920798681088 +1662129920846682112 +1662129920891683072 +1662129920933683968 +1662129920975684864 +1662129921020685824 +1662129921062686720 +1662129921107687680 +1662129921149688576 +1662129921191689472 +1662129921233690368 +1662129921278691328 +1662129921329692416 +1662129921368693248 +1662129921410694144 +1662129921461695232 +1662129921506696192 +1662129921551697152 +1662129921593698048 +1662129921635698944 +1662129921677699840 +1662129921728700928 +1662129921773701888 +1662129921812702720 +1662129921854703616 +1662129921893704448 +1662129921941705472 +1662129921986706432 +1662129922028707328 +1662129922070708224 +1662129922115709184 +1662129922157710080 +1662129922202711040 +1662129922253712128 +1662129922298713088 +1662129922340713984 +1662129922391715072 +1662129922442716160 +1662129922490717184 +1662129922541718272 +1662129922583719168 +1662129922625720064 +1662129922670721024 +1662129922715721984 +1662129922757722880 +1662129922808723968 +1662129922850724864 +1662129922892725760 +1662129922937726720 +1662129922982727680 +1662129923027728640 +1662129923069729536 +1662129923111730432 +1662129923153731328 +1662129923201732352 +1662129923252733440 +1662129923297734400 +1662129923345735424 +1662129923396736512 +1662129923441737472 +1662129923483738368 +1662129923528739328 +1662129923570740224 +1662129923612741120 +1662129923657742080 +1662129923696742912 +1662129923738743808 +1662129923786744832 +1662129923834745856 +1662129923879746816 +1662129923930747904 +1662129923981748992 +1662129924020749824 +1662129924062750720 +1662129924101751552 +1662129924146752512 +1662129924200753664 +1662129924239754496 +1662129924287755520 +1662129924329756416 +1662129924368757248 +1662129924413758208 +1662129924461759232 +1662129924503760128 +1662129924545761024 +1662129924593762048 +1662129924641763072 +1662129924683763968 +1662129924725764864 +1662129924776765952 +1662129924827767040 +1662129924869767936 +1662129924914768896 +1662129924959769856 +1662129925001770752 +1662129925043771648 +1662129925085772544 +1662129925127773440 +1662129925172774400 +1662129925217775360 +1662129925259776256 +1662129925298777088 +1662129925343778048 +1662129925385778944 +1662129925430779904 +1662129925469780736 +1662129925511781632 +1662129925559782656 +1662129925607783680 +1662129925652784640 +1662129925697785600 +1662129925748786688 +1662129925790787584 +1662129925835788544 +1662129925883789568 +1662129925925790464 +1662129925970791424 +1662129926012792320 +1662129926054793216 +1662129926096794112 +1662129926138795008 +1662129926180795904 +1662129926225796864 +1662129926267797760 +1662129926312798720 +1662129926351799552 +1662129926393800448 +1662129926438801408 +1662129926489802496 +1662129926537803520 +1662129926579804416 +1662129926621805312 +1662129926675806464 +1662129926720807424 +1662129926762808320 +1662129926807809280 +1662129926852810240 +1662129926900811264 +1662129926951812352 +1662129926996813312 +1662129927044814336 +1662129927095815424 +1662129927146816512 +1662129927188817408 +1662129927233818368 +1662129927275819264 +1662129927320820224 +1662129927362821120 +1662129927407822080 +1662129927455823104 +1662129927497824000 +1662129927542824960 +1662129927587825920 +1662129927632826880 +1662129927680827904 +1662129927728828928 +1662129927779830016 +1662129927833831168 +1662129927878832128 +1662129927920833024 +1662129927962833920 +1662129928007834880 +1662129928049835776 +1662129928103836928 +1662129928145837824 +1662129928187838720 +1662129928229839616 +1662129928271840512 +1662129928316841472 +1662129928364842496 +1662129928409843456 +1662129928457844480 +1662129928493845248 +1662129928544846336 +1662129928586847232 +1662129928631848192 +1662129928676849152 +1662129928724850176 +1662129928763851008 +1662129928808851968 +1662129928847852800 +1662129928892853760 +1662129928940854784 +1662129928982855680 +1662129929024856576 +1662129929066857472 +1662129929108858368 +1662129929150859264 +1662129929195860224 +1662129929237861120 +1662129929279862016 +1662129929321862912 +1662129929363863808 +1662129929402864640 +1662129929447865600 +1662129929498866688 +1662129929540867584 +1662129929582868480 +1662129929627869440 +1662129929681870592 +1662129929729871616 +1662129929780872704 +1662129929825873664 +1662129929867874560 +1662129929918875648 +1662129929963876608 +1662129930008877568 +1662129930050878464 +1662129930092879360 +1662129930134880256 +1662129930182881280 +1662129930227882240 +1662129930269883136 +1662129930317884160 +1662129930362885120 +1662129930413886208 +1662129930458887168 +1662129930503888128 +1662129930551889152 +1662129930593890048 +1662129930635890944 +1662129930677891840 +1662129930719892736 +1662129930767893760 +1662129930818894848 +1662129930869895936 +1662129930914896896 +1662129930965897984 +1662129931010898944 +1662129931052899840 +1662129931100900864 +1662129931142901760 +1662129931184902656 +1662129931223903488 +1662129931265904384 +1662129931307905280 +1662129931346906112 +1662129931388907008 +1662129931433907968 +1662129931478908928 +1662129931526909952 +1662129931571910912 +1662129931619911936 +1662129931670913024 +1662129931721914112 +1662129931766915072 +1662129931820916224 +1662129931862917120 +1662129931910918144 +1662129931952919040 +1662129931997920000 +1662129932042920960 +1662129932084921856 +1662129932132922880 +1662129932177923840 +1662129932225924864 +1662129932267925760 +1662129932315926784 +1662129932363927808 +1662129932405928704 +1662129932447929600 +1662129932489930496 +1662129932537931520 +1662129932579932416 +1662129932621933312 +1662129932666934272 +1662129932711935232 +1662129932756936192 +1662129932807937280 +1662129932846938112 +1662129932885938944 +1662129932933939968 +1662129932984941056 +1662129933029942016 +1662129933068942848 +1662129933113943808 +1662129933155944704 +1662129933203945728 +1662129933245946624 +1662129933284947456 +1662129933326948352 +1662129933371949312 +1662129933416950272 +1662129933464951296 +1662129933506952192 +1662129933551953152 +1662129933593954048 +1662129933635954944 +1662129933686956032 +1662129933731956992 +1662129933773957888 +1662129933821958912 +1662129933863959808 +1662129933908960768 +1662129933956961792 +1662129933998962688 +1662129934040963584 +1662129934085964544 +1662129934130965504 +1662129934181966592 +1662129934226967552 +1662129934268968448 +1662129934313969408 +1662129934364970496 +1662129934409971456 +1662129934451972352 +1662129934508973568 +1662129934556974592 +1662129934604975616 +1662129934646976512 +1662129934688977408 +1662129934736978432 +1662129934778979328 +1662129934820980224 +1662129934862981120 +1662129934904982016 +1662129934946982912 +1662129934988983808 +1662129935033984768 +1662129935078985728 +1662129935120986624 +1662129935162987520 +1662129935204988416 +1662129935246989312 +1662129935294990336 +1662129935348991488 +1662129935399992576 +1662129935441993472 +1662129935483994368 +1662129935528995328 +1662129935570996224 +1662129935615997184 +1662129935657998080 +1662129935696998912 +1662129935738999808 +1662129935781000704 +1662129935826001664 +1662129935868002560 +1662129935910003456 +1662129935955004416 +1662129936000005376 +1662129936048006400 +1662129936099007488 +1662129936141008384 +1662129936192009472 +1662129936240010496 +1662129936285011456 +1662129936327012352 +1662129936369013248 +1662129936414014208 +1662129936471015424 +1662129936513016320 +1662129936564017408 +1662129936609018368 +1662129936654019328 +1662129936696020224 +1662129936738021120 +1662129936783022080 +1662129936825022976 +1662129936867023872 +1662129936912024832 +1662129936951025664 +1662129936993026560 +1662129937035027456 +1662129937086028544 +1662129937131029504 +1662129937176030464 +1662129937218031360 +1662129937260032256 +1662129937305033216 +1662129937353034240 +1662129937395035136 +1662129937437036032 +1662129937479036928 +1662129937524037888 +1662129937569038848 +1662129937608039680 +1662129937653040640 +1662129937701041664 +1662129937752042752 +1662129937797043712 +1662129937839044608 +1662129937881045504 +1662129937923046400 +1662129937974047488 +1662129938019048448 +1662129938073049600 +1662129938118050560 +1662129938169051648 +1662129938211052544 +1662129938259053568 +1662129938304054528 +1662129938349055488 +1662129938391056384 +1662129938436057344 +1662129938484058368 +1662129938532059392 +1662129938574060288 +1662129938619061248 +1662129938661062144 +1662129938703063040 +1662129938745063936 +1662129938787064832 +1662129938832065792 +1662129938871066624 +1662129938913067520 +1662129938961068544 +1662129939006069504 +1662129939048070400 +1662129939096071424 +1662129939135072256 +1662129939186073344 +1662129939231074304 +1662129939273075200 +1662129939315076096 +1662129939360077056 +1662129939408078080 +1662129939450078976 +1662129939492079872 +1662129939534080768 +1662129939579081728 +1662129939621082624 +1662129939669083648 +1662129939714084608 +1662129939759085568 +1662129939804086528 +1662129939843087360 +1662129939888088320 +1662129939933089280 +1662129939975090176 +1662129940017091072 +1662129940062092032 +1662129940107092992 +1662129940149093888 +1662129940191094784 +1662129940236095744 +1662129940275096576 +1662129940317097472 +1662129940359098368 +1662129940404099328 +1662129940452100352 +1662129940500101376 +1662129940539102208 +1662129940581103104 +1662129940629104128 +1662129940671105024 +1662129940716105984 +1662129940764107008 +1662129940812108032 +1662129940854108928 +1662129940896109824 +1662129940938110720 +1662129940980111616 +1662129941019112448 +1662129941061113344 +1662129941103114240 +1662129941148115200 +1662129941187116032 +1662129941235117056 +1662129941277117952 +1662129941322118912 +1662129941364119808 +1662129941406120704 +1662129941448121600 +1662129941496122624 +1662129941541123584 +1662129941586124544 +1662129941628125440 +1662129941685126656 +1662129941733127680 +1662129941778128640 +1662129941823129600 +1662129941865130496 +1662129941910131456 +1662129941967132672 +1662129942012133632 +1662129942051134464 +1662129942093135360 +1662129942135136256 +1662129942174137088 +1662129942216137984 +1662129942258138880 +1662129942297139712 +1662129942339140608 +1662129942390141696 +1662129942429142528 +1662129942471143424 +1662129942513144320 +1662129942558145280 +1662129942600146176 +1662129942639147008 +1662129942681147904 +1662129942723148800 +1662129942771149824 +1662129942810150656 +1662129942864151808 +1662129942906152704 +1662129942957153792 +1662129943005154816 +1662129943047155712 +1662129943086156544 +1662129943128157440 +1662129943167158272 +1662129943215159296 +1662129943257160192 +1662129943299161088 +1662129943344162048 +1662129943395163136 +1662129943440164096 +1662129943482164992 +1662129943527165952 +1662129943578167040 +1662129943623168000 +1662129943671169024 +1662129943710169856 +1662129943752170752 +1662129943797171712 +1662129943845172736 +1662129943893173760 +1662129943935174656 +1662129943977175552 +1662129944022176512 +1662129944064177408 +1662129944109178368 +1662129944151179264 +1662129944199180288 +1662129944247181312 +1662129944295182336 +1662129944337183232 +1662129944379184128 +1662129944421185024 +1662129944466185984 +1662129944511186944 +1662129944553187840 +1662129944595188736 +1662129944643189760 +1662129944685190656 +1662129944730191616 +1662129944772192512 +1662129944814193408 +1662129944859194368 +1662129944904195328 +1662129944946196224 +1662129944997197312 +1662129945039198208 +1662129945087199232 +1662129945135200256 +1662129945177201152 +1662129945222202112 +1662129945273203200 +1662129945324204288 +1662129945375205376 +1662129945426206464 +1662129945468207360 +1662129945510208256 +1662129945558209280 +1662129945609210368 +1662129945654211328 +1662129945696212224 +1662129945738213120 +1662129945783214080 +1662129945825214976 +1662129945873216000 +1662129945927217152 +1662129945966217984 +1662129946014219008 +1662129946059219968 +1662129946107220992 +1662129946155222016 +1662129946197222912 +1662129946242223872 +1662129946290224896 +1662129946332225792 +1662129946377226752 +1662129946425227776 +1662129946479228928 +1662129946521229824 +1662129946563230720 +1662129946608231680 +1662129946650232576 +1662129946692233472 +1662129946737234432 +1662129946782235392 +1662129946824236288 +1662129946866237184 +1662129946911238144 +1662129946956239104 +1662129946998240000 +1662129947040240896 +1662129947082241792 +1662129947124242688 +1662129947169243648 +1662129947211244544 +1662129947250245376 +1662129947292246272 +1662129947346247424 +1662129947391248384 +1662129947433249280 +1662129947478250240 +1662129947526251264 +1662129947574252288 +1662129947619253248 +1662129947667254272 +1662129947709255168 +1662129947754256128 +1662129947796257024 +1662129947841257984 +1662129947895259136 +1662129947940260096 +1662129947982260992 +1662129948033262080 +1662129948084263168 +1662129948129264128 +1662129948174265088 +1662129948219266048 +1662129948261266944 +1662129948312268032 +1662129948360269056 +1662129948402269952 +1662129948441270784 +1662129948486271744 +1662129948528272640 +1662129948570273536 +1662129948618274560 +1662129948660275456 +1662129948702276352 +1662129948750277376 +1662129948798278400 +1662129948840279296 +1662129948885280256 +1662129948927281152 +1662129948969282048 +1662129949011282944 +1662129949056283904 +1662129949095284736 +1662129949137285632 +1662129949185286656 +1662129949230287616 +1662129949272288512 +1662129949314289408 +1662129949356290304 +1662129949401291264 +1662129949443292160 +1662129949488293120 +1662129949533294080 +1662129949575294976 +1662129949617295872 +1662129949668296960 +1662129949710297856 +1662129949758298880 +1662129949800299776 +1662129949842300672 +1662129949884301568 +1662129949929302528 +1662129949977303552 +1662129950022304512 +1662129950067305472 +1662129950106306304 +1662129950148307200 +1662129950193308160 +1662129950235309056 +1662129950283310080 +1662129950328311040 +1662129950370311936 +1662129950415312896 +1662129950463313920 +1662129950505314816 +1662129950559315968 +1662129950601316864 +1662129950661318144 +1662129950706319104 +1662129950763320320 +1662129950808321280 +1662129950850322176 +1662129950892323072 +1662129950931323904 +1662129950982324992 +1662129951027325952 +1662129951069326848 +1662129951111327744 +1662129951156328704 +1662129951198329600 +1662129951240330496 +1662129951291331584 +1662129951333332480 +1662129951384333568 +1662129951429334528 +1662129951471335424 +1662129951516336384 +1662129951561337344 +1662129951606338304 +1662129951648339200 +1662129951693340160 +1662129951735341056 +1662129951780342016 +1662129951825342976 +1662129951867343872 +1662129951909344768 +1662129951954345728 +1662129951996346624 +1662129952044347648 +1662129952086348544 +1662129952128349440 +1662129952179350528 +1662129952221351424 +1662129952263352320 +1662129952305353216 +1662129952350354176 +1662129952386354944 +1662129952434355968 +1662129952479356928 +1662129952524357888 +1662129952572358912 +1662129952617359872 +1662129952665360896 +1662129952707361792 +1662129952752362752 +1662129952797363712 +1662129952842364672 +1662129952887365632 +1662129952929366528 +1662129952971367424 +1662129953016368384 +1662129953058369280 +1662129953106370304 +1662129953154371328 +1662129953199372288 +1662129953247373312 +1662129953298374400 +1662129953340375296 +1662129953394376448 +1662129953436377344 +1662129953475378176 +1662129953514379008 +1662129953568380160 +1662129953613381120 +1662129953655382016 +1662129953700382976 +1662129953739383808 +1662129953781384704 +1662129953826385664 +1662129953865386496 +1662129953907387392 +1662129953955388416 +1662129954000389376 +1662129954051390464 +1662129954093391360 +1662129954138392320 +1662129954183393280 +1662129954225394176 +1662129954267395072 +1662129954306395904 +1662129954354396928 +1662129954399397888 +1662129954441398784 +1662129954489399808 +1662129954531400704 +1662129954579401728 +1662129954630402816 +1662129954672403712 +1662129954714404608 +1662129954756405504 +1662129954798406400 +1662129954840407296 +1662129954888408320 +1662129954930409216 +1662129954975410176 +1662129955023411200 +1662129955071412224 +1662129955116413184 +1662129955158414080 +1662129955206415104 +1662129955254416128 +1662129955299417088 +1662129955344418048 +1662129955386418944 +1662129955428419840 +1662129955473420800 +1662129955518421760 +1662129955560422656 +1662129955608423680 +1662129955659424768 +1662129955701425664 +1662129955746426624 +1662129955800427776 +1662129955845428736 +1662129955887429632 +1662129955929430528 +1662129955968431360 +1662129956010432256 +1662129956052433152 +1662129956094434048 +1662129956139435008 +1662129956184435968 +1662129956226436864 +1662129956268437760 +1662129956313438720 +1662129956358439680 +1662129956406440704 +1662129956445441536 +1662129956490442496 +1662129956535443456 +1662129956583444480 +1662129956634445568 +1662129956676446464 +1662129956718447360 +1662129956760448256 +1662129956802449152 +1662129956850450176 +1662129956889451008 +1662129956931451904 +1662129956973452800 +1662129957015453696 +1662129957057454592 +1662129957102455552 +1662129957150456576 +1662129957198457600 +1662129957240458496 +1662129957288459520 +1662129957330460416 +1662129957378461440 +1662129957420462336 +1662129957462463232 +1662129957510464256 +1662129957555465216 +1662129957597466112 +1662129957642467072 +1662129957687468032 +1662129957729468928 +1662129957777469952 +1662129957825470976 +1662129957867471872 +1662129957912472832 +1662129957954473728 +1662129957999474688 +1662129958044475648 +1662129958089476608 +1662129958131477504 +1662129958191478784 +1662129958233479680 +1662129958278480640 +1662129958320481536 +1662129958362482432 +1662129958407483392 +1662129958452484352 +1662129958500485376 +1662129958545486336 +1662129958581487104 +1662129958626488064 +1662129958668488960 +1662129958710489856 +1662129958752490752 +1662129958797491712 +1662129958842492672 +1662129958884493568 +1662129958929494528 +1662129958971495424 +1662129959013496320 +1662129959055497216 +1662129959100498176 +1662129959142499072 +1662129959187500032 +1662129959229500928 +1662129959271501824 +1662129959313502720 +1662129959355503616 +1662129959397504512 +1662129959448505600 +1662129959499506688 +1662129959544507648 +1662129959589508608 +1662129959634509568 +1662129959679510528 +1662129959721511424 +1662129959766512384 +1662129959817513472 +1662129959859514368 +1662129959910515456 +1662129959955516416 +1662129959997517312 +1662129960039518208 +1662129960081519104 +1662129960123520000 +1662129960174521088 +1662129960219522048 +1662129960267523072 +1662129960309523968 +1662129960363525120 +1662129960405526016 +1662129960447526912 +1662129960489527808 +1662129960531528704 +1662129960576529664 +1662129960624530688 +1662129960666531584 +1662129960708532480 +1662129960750533376 +1662129960792534272 +1662129960831535104 +1662129960876536064 +1662129960921537024 +1662129960966537984 +1662129961005538816 +1662129961047539712 +1662129961092540672 +1662129961134541568 +1662129961179542528 +1662129961221543424 +1662129961263544320 +1662129961305545216 +1662129961350546176 +1662129961401547264 +1662129961443548160 +1662129961482548992 +1662129961524549888 +1662129961572550912 +1662129961614551808 +1662129961656552704 +1662129961698553600 +1662129961740554496 +1662129961779555328 +1662129961818556160 +1662129961860557056 +1662129961908558080 +1662129961953559040 +1662129961995559936 +1662129962037560832 +1662129962082561792 +1662129962124562688 +1662129962163563520 +1662129962205564416 +1662129962247565312 +1662129962289566208 +1662129962334567168 +1662129962385568256 +1662129962445569536 +1662129962496570624 +1662129962538571520 +1662129962583572480 +1662129962628573440 +1662129962676574464 +1662129962715575296 +1662129962757576192 +1662129962802577152 +1662129962847578112 +1662129962892579072 +1662129962943580160 +1662129962988581120 +1662129963039582208 +1662129963081583104 +1662129963126584064 +1662129963174585088 +1662129963216585984 +1662129963264587008 +1662129963306587904 +1662129963348588800 +1662129963390589696 +1662129963435590656 +1662129963477591552 +1662129963519592448 +1662129963561593344 +1662129963603594240 +1662129963648595200 +1662129963687596032 +1662129963729596928 +1662129963771597824 +1662129963822598912 +1662129963867599872 +1662129963909600768 +1662129963954601728 +1662129964005602816 +1662129964047603712 +1662129964101604864 +1662129964143605760 +1662129964188606720 +1662129964230607616 +1662129964275608576 +1662129964317609472 +1662129964359610368 +1662129964401611264 +1662129964446612224 +1662129964497613312 +1662129964539614208 +1662129964581615104 +1662129964626616064 +1662129964671617024 +1662129964713617920 +1662129964755618816 +1662129964800619776 +1662129964842620672 +1662129964887621632 +1662129964929622528 +1662129964977623552 +1662129965019624448 +1662129965067625472 +1662129965112626432 +1662129965157627392 +1662129965199628288 +1662129965253629440 +1662129965295630336 +1662129965334631168 +1662129965382632192 +1662129965427633152 +1662129965472634112 +1662129965514635008 +1662129965559635968 +1662129965604636928 +1662129965649637888 +1662129965694638848 +1662129965736639744 +1662129965784640768 +1662129965829641728 +1662129965880642816 +1662129965922643712 +1662129965964644608 +1662129966012645632 +1662129966054646528 +1662129966093647360 +1662129966138648320 +1662129966183649280 +1662129966228650240 +1662129966273651200 +1662129966324652288 +1662129966375653376 +1662129966420654336 +1662129966471655424 +1662129966516656384 +1662129966561657344 +1662129966606658304 +1662129966651659264 +1662129966696660224 +1662129966738661120 +1662129966780662016 +1662129966828663040 +1662129966870663936 +1662129966912664832 +1662129966954665728 +1662129966996666624 +1662129967041667584 +1662129967086668544 +1662129967128669440 +1662129967170670336 +1662129967209671168 +1662129967257672192 +1662129967296673024 +1662129967338673920 +1662129967386674944 +1662129967425675776 +1662129967467676672 +1662129967518677760 +1662129967560678656 +1662129967602679552 +1662129967647680512 +1662129967689681408 +1662129967731682304 +1662129967773683200 +1662129967818684160 +1662129967860685056 +1662129967905686016 +1662129967947686912 +1662129967992687872 +1662129968037688832 +1662129968088689920 +1662129968127690752 +1662129968172691712 +1662129968220692736 +1662129968271693824 +1662129968313694720 +1662129968355695616 +1662129968394696448 +1662129968433697280 +1662129968475698176 +1662129968517699072 +1662129968571700224 +1662129968622701312 +1662129968673702400 +1662129968715703296 +1662129968757704192 +1662129968805705216 +1662129968850706176 +1662129968895707136 +1662129968937708032 +1662129968979708928 +1662129969021709824 +1662129969063710720 +1662129969105711616 +1662129969162712832 +1662129969201713664 +1662129969252714752 +1662129969297715712 +1662129969339716608 +1662129969381717504 +1662129969423718400 +1662129969465719296 +1662129969513720320 +1662129969555721216 +1662129969600722176 +1662129969648723200 +1662129969690724096 +1662129969738725120 +1662129969783726080 +1662129969825726976 +1662129969870727936 +1662129969918728960 +1662129969966729984 +1662129970008730880 +1662129970059731968 +1662129970104732928 +1662129970149733888 +1662129970194734848 +1662129970242735872 +1662129970284736768 +1662129970335737856 +1662129970377738752 +1662129970419739648 +1662129970461740544 +1662129970503741440 +1662129970545742336 +1662129970590743296 +1662129970635744256 +1662129970677745152 +1662129970719746048 +1662129970764747008 +1662129970806747904 +1662129970851748864 +1662129970896749824 +1662129970941750784 +1662129970995751936 +1662129971043752960 +1662129971088753920 +1662129971136754944 +1662129971178755840 +1662129971220756736 +1662129971265757696 +1662129971313758720 +1662129971355759616 +1662129971403760640 +1662129971445761536 +1662129971496762624 +1662129971538763520 +1662129971583764480 +1662129971643765760 +1662129971682766592 +1662129971724767488 +1662129971769768448 +1662129971811769344 +1662129971859770368 +1662129971901771264 +1662129971943772160 +1662129971982772992 +1662129972024773888 +1662129972066774784 +1662129972108775680 +1662129972153776640 +1662129972195777536 +1662129972240778496 +1662129972285779456 +1662129972327780352 +1662129972369781248 +1662129972414782208 +1662129972456783104 +1662129972501784064 +1662129972540784896 +1662129972582785792 +1662129972627786752 +1662129972669787648 +1662129972717788672 +1662129972762789632 +1662129972804790528 +1662129972852791552 +1662129972894792448 +1662129972939793408 +1662129972981794304 +1662129973020795136 +1662129973062796032 +1662129973113797120 +1662129973155798016 +1662129973197798912 +1662129973239799808 +1662129973281800704 +1662129973323801600 +1662129973368802560 +1662129973416803584 +1662129973461804544 +1662129973506805504 +1662129973548806400 +1662129973590807296 +1662129973632808192 +1662129973674809088 +1662129973722810112 +1662129973773811200 +1662129973818812160 +1662129973866813184 +1662129973911814144 +1662129973953815040 +1662129973998816000 +1662129974040816896 +1662129974082817792 +1662129974124818688 +1662129974169819648 +1662129974211820544 +1662129974253821440 +1662129974295822336 +1662129974349823488 +1662129974391824384 +1662129974436825344 +1662129974481826304 +1662129974523827200 +1662129974580828416 +1662129974622829312 +1662129974667830272 +1662129974709831168 +1662129974754832128 +1662129974799833088 +1662129974844834048 +1662129974886834944 +1662129974940836096 +1662129974985837056 +1662129975027837952 +1662129975072838912 +1662129975114839808 +1662129975156840704 +1662129975201841664 +1662129975249842688 +1662129975291843584 +1662129975336844544 +1662129975384845568 +1662129975426846464 +1662129975471847424 +1662129975510848256 +1662129975561849344 +1662129975606850304 +1662129975657851392 +1662129975702852352 +1662129975747853312 +1662129975789854208 +1662129975834855168 +1662129975873856000 +1662129975918856960 +1662129975972858112 +1662129976017859072 +1662129976065860096 +1662129976110861056 +1662129976152861952 +1662129976197862912 +1662129976245863936 +1662129976287864832 +1662129976329865728 +1662129976377866752 +1662129976422867712 +1662129976473868800 +1662129976512869632 +1662129976557870592 +1662129976602871552 +1662129976644872448 +1662129976689873408 +1662129976731874304 +1662129976770875136 +1662129976812876032 +1662129976857876992 +1662129976896877824 +1662129976938878720 +1662129976983879680 +1662129977025880576 +1662129977070881536 +1662129977115882496 +1662129977154883328 +1662129977199884288 +1662129977250885376 +1662129977295886336 +1662129977334887168 +1662129977373888000 +1662129977415888896 +1662129977457889792 +1662129977499890688 +1662129977541891584 +1662129977583892480 +1662129977625893376 +1662129977670894336 +1662129977715895296 +1662129977757896192 +1662129977799897088 +1662129977844898048 +1662129977886898944 +1662129977937900032 +1662129977982900992 +1662129978030902016 +1662129978072902912 +1662129978111903744 +1662129978153904640 +1662129978201905664 +1662129978249906688 +1662129978297907712 +1662129978339908608 +1662129978381909504 +1662129978426910464 +1662129978477911552 +1662129978525912576 +1662129978567913472 +1662129978606914304 +1662129978648915200 +1662129978690916096 +1662129978732916992 +1662129978777917952 +1662129978822918912 +1662129978870919936 +1662129978921921024 +1662129978966921984 +1662129979014923008 +1662129979062924032 +1662129979104924928 +1662129979146925824 +1662129979188926720 +1662129979230927616 +1662129979272928512 +1662129979314929408 +1662129979353930240 +1662129979395931136 +1662129979437932032 +1662129979476932864 +1662129979521933824 +1662129979566934784 +1662129979611935744 +1662129979656936704 +1662129979704937728 +1662129979746938624 +1662129979788939520 +1662129979836940544 +1662129979875941376 +1662129979917942272 +1662129979956943104 +1662129980007944192 +1662129980052945152 +1662129980094946048 +1662129980139947008 +1662129980190948096 +1662129980232948992 +1662129980274949888 +1662129980316950784 +1662129980358951680 +1662129980400952576 +1662129980442953472 +1662129980490954496 +1662129980535955456 +1662129980577956352 +1662129980616957184 +1662129980661958144 +1662129980703959040 +1662129980745959936 +1662129980793960960 +1662129980841961984 +1662129980883962880 +1662129980928963840 +1662129980976964864 +1662129981027965952 +1662129981072966912 +1662129981117967872 +1662129981159968768 +1662129981201969664 +1662129981246970624 +1662129981285971456 +1662129981327972352 +1662129981378973440 +1662129981423974400 +1662129981462975232 +1662129981501976064 +1662129981543976960 +1662129981582977792 +1662129981624978688 +1662129981669979648 +1662129981711980544 +1662129981750981376 +1662129981792982272 +1662129981834983168 +1662129981876984064 +1662129981933985280 +1662129981975986176 +1662129982017987072 +1662129982059987968 +1662129982104988928 +1662129982146989824 +1662129982185990656 +1662129982230991616 +1662129982272992512 +1662129982314993408 +1662129982356994304 +1662129982401995264 +1662129982452996352 +1662129982494997248 +1662129982533998080 +1662129982575998976 +1662129982620999936 +1662129982669000960 +1662129982720002048 +1662129982774003200 +1662129982816004096 +1662129982858004992 +1662129982900005888 +1662129982942006784 +1662129982987007744 +1662129983029008640 +1662129983071009536 +1662129983131010816 +1662129983173011712 +1662129983221012736 +1662129983269013760 +1662129983311014656 +1662129983353015552 +1662129983398016512 +1662129983443017472 +1662129983488018432 +1662129983533019392 +1662129983575020288 +1662129983620021248 +1662129983668022272 +1662129983710023168 +1662129983752024064 +1662129983791024896 +1662129983833025792 +1662129983872026624 +1662129983917027584 +1662129983959028480 +1662129984013029632 +1662129984058030592 +1662129984100031488 +1662129984142032384 +1662129984181033216 +1662129984226034176 +1662129984274035200 +1662129984319036160 +1662129984367037184 +1662129984409038080 +1662129984457039104 +1662129984496039936 +1662129984541040896 +1662129984583041792 +1662129984628042752 +1662129984670043648 +1662129984724044800 +1662129984766045696 +1662129984811046656 +1662129984850047488 +1662129984892048384 +1662129984937049344 +1662129984979050240 +1662129985024051200 +1662129985069052160 +1662129985108052992 +1662129985150053888 +1662129985195054848 +1662129985243055872 +1662129985297057024 +1662129985342057984 +1662129985387058944 +1662129985432059904 +1662129985480060928 +1662129985525061888 +1662129985567062784 +1662129985615063808 +1662129985660064768 +1662129985711065856 +1662129985753066752 +1662129985792067584 +1662129985837068544 +1662129985879069440 +1662129985927070464 +1662129985975071488 +1662129986017072384 +1662129986065073408 +1662129986104074240 +1662129986149075200 +1662129986194076160 +1662129986233076992 +1662129986275077888 +1662129986320078848 +1662129986362079744 +1662129986404080640 +1662129986446081536 +1662129986488082432 +1662129986527083264 +1662129986569084160 +1662129986614085120 +1662129986665086208 +1662129986707087104 +1662129986755088128 +1662129986800089088 +1662129986842089984 +1662129986881090816 +1662129986923091712 +1662129986968092672 +1662129987013093632 +1662129987055094528 +1662129987097095424 +1662129987139096320 +1662129987178097152 +1662129987220098048 +1662129987268099072 +1662129987310099968 +1662129987352100864 +1662129987394101760 +1662129987439102720 +1662129987481103616 +1662129987529104640 +1662129987574105600 +1662129987622106624 +1662129987664107520 +1662129987706108416 +1662129987745109248 +1662129987790110208 +1662129987835111168 +1662129987880112128 +1662129987922113024 +1662129987961113856 +1662129988006114816 +1662129988048115712 +1662129988090116608 +1662129988132117504 +1662129988180118528 +1662129988225119488 +1662129988267120384 +1662129988309121280 +1662129988348122112 +1662129988390123008 +1662129988432123904 +1662129988474124800 +1662129988513125632 +1662129988561126656 +1662129988600127488 +1662129988648128512 +1662129988696129536 +1662129988738130432 +1662129988780131328 +1662129988831132416 +1662129988873133312 +1662129988921134336 +1662129988966135296 +1662129989011136256 +1662129989053137152 +1662129989092137984 +1662129989134138880 +1662129989179139840 +1662129989227140864 +1662129989269141760 +1662129989311142656 +1662129989356143616 +1662129989401144576 +1662129989443145472 +1662129989491146496 +1662129989533147392 +1662129989587148544 +1662129989629149440 +1662129989683150592 +1662129989725151488 +1662129989770152448 +1662129989812153344 +1662129989857154304 +1662129989899155200 +1662129989944156160 +1662129989986157056 +1662129990037158144 +1662129990079159040 +1662129990118159872 +1662129990160160768 +1662129990208161792 +1662129990253162752 +1662129990298163712 +1662129990334164480 +1662129990379165440 +1662129990421166336 +1662129990466167296 +1662129990508168192 +1662129990550169088 +1662129990601170176 +1662129990646171136 +1662129990691172096 +1662129990736173056 +1662129990781174016 +1662129990823174912 +1662129990865175808 +1662129990907176704 +1662129990949177600 +1662129990988178432 +1662129991027179264 +1662129991072180224 +1662129991111181056 +1662129991150181888 +1662129991192182784 +1662129991234183680 +1662129991276184576 +1662129991321185536 +1662129991366186496 +1662129991420187648 +1662129991462188544 +1662129991501189376 +1662129991540190208 +1662129991579191040 +1662129991621191936 +1662129991663192832 +1662129991708193792 +1662129991750194688 +1662129991792195584 +1662129991834196480 +1662129991882197504 +1662129991924198400 +1662129991966199296 +1662129992008200192 +1662129992047201024 +1662129992089201920 +1662129992131202816 +1662129992170203648 +1662129992209204480 +1662129992251205376 +1662129992290206208 +1662129992335207168 +1662129992380208128 +1662129992422209024 +1662129992464209920 +1662129992506210816 +1662129992551211776 +1662129992599212800 +1662129992641213696 +1662129992686214656 +1662129992731215616 +1662129992773216512 +1662129992821217536 +1662129992860218368 +1662129992905219328 +1662129992947220224 +1662129992989221120 +1662129993031222016 +1662129993073222912 +1662129993115223808 +1662129993163224832 +1662129993208225792 +1662129993250226688 +1662129993298227712 +1662129993355228928 +1662129993397229824 +1662129993439230720 +1662129993481231616 +1662129993523232512 +1662129993562233344 +1662129993607234304 +1662129993649235200 +1662129993691236096 +1662129993733236992 +1662129993775237888 +1662129993826238976 +1662129993877240064 +1662129993922241024 +1662129993976242176 +1662129994027243264 +1662129994072244224 +1662129994114245120 +1662129994156246016 +1662129994198246912 +1662129994243247872 +1662129994285248768 +1662129994327249664 +1662129994372250624 +1662129994414251520 +1662129994456252416 +1662129994498253312 +1662129994537254144 +1662129994579255040 +1662129994627256064 +1662129994672257024 +1662129994717257984 +1662129994759258880 +1662129994798259712 +1662129994843260672 +1662129994882261504 +1662129994924262400 +1662129994966263296 +1662129995008264192 +1662129995056265216 +1662129995104266240 +1662129995155267328 +1662129995197268224 +1662129995242269184 +1662129995287270144 +1662129995329271040 +1662129995371271936 +1662129995419272960 +1662129995458273792 +1662129995500274688 +1662129995545275648 +1662129995593276672 +1662129995635277568 +1662129995677278464 +1662129995719279360 +1662129995761280256 +1662129995803281152 +1662129995845282048 +1662129995887282944 +1662129995932283904 +1662129995983284992 +1662129996025285888 +1662129996067286784 +1662129996115287808 +1662129996157288704 +1662129996202289664 +1662129996244290560 +1662129996295291648 +1662129996340292608 +1662129996397293824 +1662129996442294784 +1662129996493295872 +1662129996538296832 +1662129996580297728 +1662129996622298624 +1662129996667299584 +1662129996712300544 +1662129996754301440 +1662129996796302336 +1662129996838303232 +1662129996880304128 +1662129996928305152 +1662129996970306048 +1662129997009306880 +1662129997054307840 +1662129997102308864 +1662129997147309824 +1662129997192310784 +1662129997234311680 +1662129997279312640 +1662129997321313536 +1662129997363314432 +1662129997405315328 +1662129997447316224 +1662129997489317120 +1662129997531318016 +1662129997573318912 +1662129997615319808 +1662129997657320704 +1662129997702321664 +1662129997741322496 +1662129997783323392 +1662129997828324352 +1662129997870325248 +1662129997912326144 +1662129997954327040 +1662129997999328000 +1662129998050329088 +1662129998098330112 +1662129998140331008 +1662129998188332032 +1662129998230332928 +1662129998275333888 +1662129998320334848 +1662129998365335808 +1662129998407336704 +1662129998446337536 +1662129998491338496 +1662129998542339584 +1662129998584340480 +1662129998626341376 +1662129998668342272 +1662129998713343232 +1662129998764344320 +1662129998806345216 +1662129998845346048 +1662129998887346944 +1662129998926347776 +1662129998968348672 +1662129999010349568 +1662129999052350464 +1662129999094351360 +1662129999139352320 +1662129999181353216 +1662129999226354176 +1662129999274355200 +1662129999316356096 +1662129999358356992 +1662129999406358016 +1662129999448358912 +1662129999496359936 +1662129999538360832 +1662129999577361664 +1662129999616362496 +1662129999658363392 +1662129999697364224 +1662129999739365120 +1662129999778365952 +1662129999817366784 +1662129999874368000 +1662129999916368896 +1662129999958369792 +1662130000012370944 +1662130000057371904 +1662130000099372800 +1662130000147373824 +1662130000189374720 +1662130000240375808 +1662130000282376704 +1662130000327377664 +1662130000375378688 +1662130000420379648 +1662130000462380544 +1662130000504381440 +1662130000546382336 +1662130000588383232 +1662130000630384128 +1662130000672385024 +1662130000714385920 +1662130000762386944 +1662130000807387904 +1662130000855388928 +1662130000903389952 +1662130000948390912 +1662130000987391744 +1662130001029392640 +1662130001071393536 +1662130001113394432 +1662130001161395456 +1662130001203396352 +1662130001245397248 +1662130001299398400 +1662130001341399296 +1662130001389400320 +1662130001428401152 +1662130001479402240 +1662130001524403200 +1662130001572404224 +1662130001620405248 +1662130001662406144 +1662130001704407040 +1662130001746407936 +1662130001788408832 +1662130001830409728 +1662130001872410624 +1662130001911411456 +1662130001953412352 +1662130001995413248 +1662130002037414144 +1662130002079415040 +1662130002124416000 +1662130002169416960 +1662130002214417920 +1662130002256418816 +1662130002301419776 +1662130002349420800 +1662130002394421760 +1662130002436422656 +1662130002481423616 +1662130002523424512 +1662130002568425472 +1662130002610426368 +1662130002652427264 +1662130002697428224 +1662130002739429120 +1662130002781430016 +1662130002826430976 +1662130002874432000 +1662130002916432896 +1662130002955433728 +1662130003000434688 +1662130003039435520 +1662130003081436416 +1662130003126437376 +1662130003171438336 +1662130003213439232 +1662130003255440128 +1662130003297441024 +1662130003339441920 +1662130003381442816 +1662130003423443712 +1662130003465444608 +1662130003507445504 +1662130003549446400 +1662130003591447296 +1662130003639448320 +1662130003681449216 +1662130003723450112 +1662130003768451072 +1662130003813452032 +1662130003855452928 +1662130003900453888 +1662130003948454912 +1662130003993455872 +1662130004035456768 +1662130004077457664 +1662130004122458624 +1662130004164459520 +1662130004209460480 +1662130004257461504 +1662130004302462464 +1662130004344463360 +1662130004398464512 +1662130004437465344 +1662130004485466368 +1662130004530467328 +1662130004578468352 +1662130004626469376 +1662130004665470208 +1662130004710471168 +1662130004749472000 +1662130004791472896 +1662130004833473792 +1662130004875474688 +1662130004917475584 +1662130004959476480 +1662130005013477632 +1662130005058478592 +1662130005103479552 +1662130005145480448 +1662130005184481280 +1662130005223482112 +1662130005265483008 +1662130005319484160 +1662130005361485056 +1662130005406486016 +1662130005448486912 +1662130005496487936 +1662130005538488832 +1662130005580489728 +1662130005628490752 +1662130005679491840 +1662130005721492736 +1662130005763493632 +1662130005817494784 +1662130005859495680 +1662130005901496576 +1662130005952497664 +1662130005991498496 +1662130006030499328 +1662130006075500288 +1662130006126501376 +1662130006171502336 +1662130006213503232 +1662130006261504256 +1662130006303505152 +1662130006342505984 +1662130006390507008 +1662130006432507904 +1662130006480508928 +1662130006522509824 +1662130006573510912 +1662130006615511808 +1662130006660512768 +1662130006702513664 +1662130006744514560 +1662130006786515456 +1662130006828516352 +1662130006867517184 +1662130006912518144 +1662130006960519168 +1662130006999520000 +1662130007041520896 +1662130007083521792 +1662130007128522752 +1662130007179523840 +1662130007227524864 +1662130007272525824 +1662130007317526784 +1662130007356527616 +1662130007398528512 +1662130007440529408 +1662130007485530368 +1662130007527531264 +1662130007572532224 +1662130007614533120 +1662130007665534208 +1662130007707535104 +1662130007749536000 +1662130007800537088 +1662130007848538112 +1662130007893539072 +1662130007938540032 +1662130007977540864 +1662130008022541824 +1662130008064542720 +1662130008115543808 +1662130008160544768 +1662130008208545792 +1662130008253546752 +1662130008295547648 +1662130008340548608 +1662130008385549568 +1662130008424550400 +1662130008466551296 +1662130008508552192 +1662130008547553024 +1662130008589553920 +1662130008634554880 +1662130008676555776 +1662130008724556800 +1662130008763557632 +1662130008805558528 +1662130008847559424 +1662130008895560448 +1662130008937561344 +1662130008982562304 +1662130009024563200 +1662130009063564032 +1662130009111565056 +1662130009153565952 +1662130009198566912 +1662130009240567808 +1662130009282568704 +1662130009327569664 +1662130009375570688 +1662130009417571584 +1662130009468572672 +1662130009519573760 +1662130009561574656 +1662130009603575552 +1662130009645576448 +1662130009687577344 +1662130009732578304 +1662130009774579200 +1662130009816580096 +1662130009864581120 +1662130009912582144 +1662130009954583040 +1662130009996583936 +1662130010038584832 +1662130010080585728 +1662130010128586752 +1662130010170587648 +1662130010209588480 +1662130010248589312 +1662130010290590208 +1662130010332591104 +1662130010386592256 +1662130010434593280 +1662130010476594176 +1662130010521595136 +1662130010560595968 +1662130010602596864 +1662130010650597888 +1662130010695598848 +1662130010737599744 +1662130010788600832 +1662130010830601728 +1662130010875602688 +1662130010920603648 +1662130010968604672 +1662130011013605632 +1662130011058606592 +1662130011100607488 +1662130011142608384 +1662130011190609408 +1662130011229610240 +1662130011286611456 +1662130011331612416 +1662130011373613312 +1662130011415614208 +1662130011463615232 +1662130011508616192 +1662130011550617088 +1662130011592617984 +1662130011637618944 +1662130011679619840 +1662130011724620800 +1662130011766621696 +1662130011811622656 +1662130011856623616 +1662130011904624640 +1662130011946625536 +1662130011988626432 +1662130012030627328 +1662130012072628224 +1662130012114629120 +1662130012156630016 +1662130012198630912 +1662130012237631744 +1662130012279632640 +1662130012321633536 +1662130012369634560 +1662130012414635520 +1662130012456636416 +1662130012513637632 +1662130012555638528 +1662130012606639616 +1662130012648640512 +1662130012690641408 +1662130012732642304 +1662130012777643264 +1662130012819644160 +1662130012867645184 +1662130012912646144 +1662130012954647040 +1662130013002648064 +1662130013053649152 +1662130013095650048 +1662130013140651008 +1662130013185651968 +1662130013230652928 +1662130013275653888 +1662130013317654784 +1662130013365655808 +1662130013407656704 +1662130013455657728 +1662130013494658560 +1662130013542659584 +1662130013584660480 +1662130013626661376 +1662130013668662272 +1662130013713663232 +1662130013767664384 +1662130013812665344 +1662130013851666176 +1662130013902667264 +1662130013941668096 +1662130013983668992 +1662130014028669952 +1662130014070670848 +1662130014112671744 +1662130014154672640 +1662130014208673792 +1662130014259674880 +1662130014301675776 +1662130014352676864 +1662130014400677888 +1662130014442678784 +1662130014484679680 +1662130014523680512 +1662130014565681408 +1662130014610682368 +1662130014652683264 +1662130014700684288 +1662130014742685184 +1662130014787686144 +1662130014832687104 +1662130014874688000 +1662130014919688960 +1662130014976690176 +1662130015024691200 +1662130015072692224 +1662130015114693120 +1662130015156694016 +1662130015201694976 +1662130015240695808 +1662130015279696640 +1662130015321697536 +1662130015369698560 +1662130015420699648 +1662130015462700544 +1662130015504701440 +1662130015552702464 +1662130015594703360 +1662130015636704256 +1662130015678705152 +1662130015720706048 +1662130015768707072 +1662130015819708160 +1662130015861709056 +1662130015903709952 +1662130015945710848 +1662130015996711936 +1662130016038712832 +1662130016080713728 +1662130016128714752 +1662130016179715840 +1662130016221716736 +1662130016263717632 +1662130016308718592 +1662130016362719744 +1662130016401720576 +1662130016443721472 +1662130016482722304 +1662130016527723264 +1662130016569724160 +1662130016611725056 +1662130016668726272 +1662130016710727168 +1662130016761728256 +1662130016812729344 +1662130016854730240 +1662130016896731136 +1662130016938732032 +1662130016977732864 +1662130017022733824 +1662130017061734656 +1662130017103735552 +1662130017154736640 +1662130017202737664 +1662130017247738624 +1662130017289739520 +1662130017334740480 +1662130017379741440 +1662130017421742336 +1662130017469743360 +1662130017517744384 +1662130017559745280 +1662130017601746176 +1662130017649747200 +1662130017691748096 +1662130017733748992 +1662130017781750016 +1662130017826750976 +1662130017877752064 +1662130017922753024 +1662130017964753920 +1662130018006754816 +1662130018045755648 +1662130018093756672 +1662130018147757824 +1662130018189758720 +1662130018228759552 +1662130018273760512 +1662130018318761472 +1662130018357762304 +1662130018402763264 +1662130018447764224 +1662130018489765120 +1662130018528765952 +1662130018573766912 +1662130018618767872 +1662130018660768768 +1662130018702769664 +1662130018744770560 +1662130018795771648 +1662130018837772544 +1662130018888773632 +1662130018936774656 +1662130018978775552 +1662130019032776704 +1662130019077777664 +1662130019116778496 +1662130019161779456 +1662130019209780480 +1662130019248781312 +1662130019287782144 +1662130019335783168 +1662130019383784192 +1662130019425785088 +1662130019473786112 +1662130019515787008 +1662130019557787904 +1662130019596788736 +1662130019644789760 +1662130019683790592 +1662130019728791552 +1662130019776792576 +1662130019821793536 +1662130019863794432 +1662130019905795328 +1662130019950796288 +1662130019992797184 +1662130020055798528 +1662130020097799424 +1662130020145800448 +1662130020190801408 +1662130020232802304 +1662130020274803200 +1662130020316804096 +1662130020364805120 +1662130020412806144 +1662130020454807040 +1662130020505808128 +1662130020550809088 +1662130020592809984 +1662130020634810880 +1662130020682811904 +1662130020724812800 +1662130020769813760 +1662130020811814656 +1662130020859815680 +1662130020904816640 +1662130020946817536 +1662130021000818688 +1662130021045819648 +1662130021093820672 +1662130021138821632 +1662130021180822528 +1662130021222823424 +1662130021267824384 +1662130021315825408 +1662130021357826304 +1662130021399827200 +1662130021441828096 +1662130021483828992 +1662130021522829824 +1662130021570830848 +1662130021615831808 +1662130021666832896 +1662130021720834048 +1662130021768835072 +1662130021822836224 +1662130021873837312 +1662130021921838336 +1662130021969839360 +1662130022014840320 +1662130022059841280 +1662130022104842240 +1662130022143843072 +1662130022188844032 +1662130022230844928 +1662130022278845952 +1662130022323846912 +1662130022374848000 +1662130022416848896 +1662130022467849984 +1662130022512850944 +1662130022554851840 +1662130022599852800 +1662130022638853632 +1662130022680854528 +1662130022722855424 +1662130022764856320 +1662130022812857344 +1662130022854858240 +1662130022896859136 +1662130022947860224 +1662130022989861120 +1662130023034862080 +1662130023076862976 +1662130023112863744 +1662130023157864704 +1662130023199865600 +1662130023244866560 +1662130023292867584 +1662130023334868480 +1662130023376869376 +1662130023418870272 +1662130023463871232 +1662130023505872128 +1662130023556873216 +1662130023607874304 +1662130023655875328 +1662130023697876224 +1662130023739877120 +1662130023787878144 +1662130023829879040 +1662130023877880064 +1662130023925881088 +1662130023970882048 +1662130024012882944 +1662130024054883840 +1662130024096884736 +1662130024150885888 +1662130024195886848 +1662130024240887808 +1662130024279888640 +1662130024324889600 +1662130024369890560 +1662130024414891520 +1662130024456892416 +1662130024501893376 +1662130024546894336 +1662130024597895424 +1662130024645896448 +1662130024690897408 +1662130024732898304 +1662130024774899200 +1662130024816900096 +1662130024858900992 +1662130024903901952 +1662130024948902912 +1662130024999904000 +1662130025041904896 +1662130025080905728 +1662130025128906752 +1662130025170907648 +1662130025224908800 +1662130025263909632 +1662130025302910464 +1662130025353911552 +1662130025398912512 +1662130025443913472 +1662130025485914368 +1662130025527915264 +1662130025569916160 +1662130025611917056 +1662130025647917824 +1662130025689918720 +1662130025734919680 +1662130025776920576 +1662130025824921600 +1662130025866922496 +1662130025908923392 +1662130025947924224 +1662130025989925120 +1662130026031926016 +1662130026076926976 +1662130026118927872 +1662130026163928832 +1662130026202929664 +1662130026244930560 +1662130026289931520 +1662130026337932544 +1662130026382933504 +1662130026424934400 +1662130026466935296 +1662130026508936192 +1662130026553937152 +1662130026595938048 +1662130026640939008 +1662130026682939904 +1662130026721940736 +1662130026763941632 +1662130026811942656 +1662130026856943616 +1662130026904944640 +1662130026955945728 +1662130026994946560 +1662130027039947520 +1662130027081948416 +1662130027117949184 +1662130027165950208 +1662130027207951104 +1662130027249952000 +1662130027297953024 +1662130027351954176 +1662130027396955136 +1662130027444956160 +1662130027489957120 +1662130027537958144 +1662130027579959040 +1662130027621959936 +1662130027660960768 +1662130027711961856 +1662130027753962752 +1662130027795963648 +1662130027837964544 +1662130027885965568 +1662130027930966528 +1662130027975967488 +1662130028026968576 +1662130028068969472 +1662130028113970432 +1662130028161971456 +1662130028209972480 +1662130028257973504 +1662130028296974336 +1662130028341975296 +1662130028383976192 +1662130028428977152 +1662130028473978112 +1662130028521979136 +1662130028563980032 +1662130028605980928 +1662130028647981824 +1662130028689982720 +1662130028731983616 +1662130028779984640 +1662130028815985408 +1662130028863986432 +1662130028908987392 +1662130028956988416 +1662130028998989312 +1662130029043990272 +1662130029085991168 +1662130029136992256 +1662130029178993152 +1662130029226994176 +1662130029271995136 +1662130029307995904 +1662130029352996864 +1662130029388997632 +1662130029433998592 +1662130029475999488 +1662130029518000384 +1662130029560001280 +1662130029605002240 +1662130029650003200 +1662130029692004096 +1662130029740005120 +1662130029782006016 +1662130029827006976 +1662130029872007936 +1662130029914008832 +1662130029959009792 +1662130030004010752 +1662130030058011904 +1662130030100012800 +1662130030145013760 +1662130030193014784 +1662130030238015744 +1662130030277016576 +1662130030319017472 +1662130030364018432 +1662130030406019328 +1662130030448020224 +1662130030496021248 +1662130030538022144 +1662130030583023104 +1662130030628024064 +1662130030676025088 +1662130030721026048 +1662130030763026944 +1662130030811027968 +1662130030856028928 +1662130030904029952 +1662130030952030976 +1662130030997031936 +1662130031045032960 +1662130031087033856 +1662130031126034688 +1662130031171035648 +1662130031213036544 +1662130031261037568 +1662130031306038528 +1662130031354039552 +1662130031396040448 +1662130031441041408 +1662130031480042240 +1662130031522043136 +1662130031567044096 +1662130031615045120 +1662130031660046080 +1662130031702046976 +1662130031744047872 +1662130031786048768 +1662130031831049728 +1662130031879050752 +1662130031921051648 +1662130031972052736 +1662130032020053760 +1662130032059054592 +1662130032110055680 +1662130032152056576 +1662130032191057408 +1662130032233058304 +1662130032278059264 +1662130032326060288 +1662130032368061184 +1662130032410062080 +1662130032452062976 +1662130032491063808 +1662130032530064640 +1662130032575065600 +1662130032617066496 +1662130032659067392 +1662130032701068288 +1662130032743069184 +1662130032782070016 +1662130032827070976 +1662130032869071872 +1662130032917072896 +1662130032959073792 +1662130033004074752 +1662130033046075648 +1662130033088076544 +1662130033133077504 +1662130033181078528 +1662130033226079488 +1662130033271080448 +1662130033319081472 +1662130033364082432 +1662130033406083328 +1662130033445084160 +1662130033493085184 +1662130033535086080 +1662130033577086976 +1662130033619087872 +1662130033661088768 +1662130033709089792 +1662130033751090688 +1662130033796091648 +1662130033838092544 +1662130033889093632 +1662130033931094528 +1662130033976095488 +1662130034018096384 +1662130034066097408 +1662130034108098304 +1662130034150099200 +1662130034195100160 +1662130034240101120 +1662130034285102080 +1662130034324102912 +1662130034366103808 +1662130034411104768 +1662130034453105664 +1662130034501106688 +1662130034543107584 +1662130034579108352 +1662130034621109248 +1662130034663110144 +1662130034708111104 +1662130034756112128 +1662130034798113024 +1662130034846114048 +1662130034888114944 +1662130034930115840 +1662130034969116672 +1662130035017117696 +1662130035059118592 +1662130035104119552 +1662130035149120512 +1662130035194121472 +1662130035236122368 +1662130035278123264 +1662130035323124224 +1662130035362125056 +1662130035404125952 +1662130035452126976 +1662130035500128000 +1662130035551129088 +1662130035593129984 +1662130035638130944 +1662130035686131968 +1662130035734132992 +1662130035776133888 +1662130035821134848 +1662130035863135744 +1662130035911136768 +1662130035953137664 +1662130036004138752 +1662130036046139648 +1662130036094140672 +1662130036139141632 +1662130036190142720 +1662130036235143680 +1662130036277144576 +1662130036328145664 +1662130036370146560 +1662130036415147520 +1662130036463148544 +1662130036502149376 +1662130036547150336 +1662130036586151168 +1662130036628152064 +1662130036676153088 +1662130036718153984 +1662130036760154880 +1662130036802155776 +1662130036844156672 +1662130036889157632 +1662130036931158528 +1662130036982159616 +1662130037021160448 +1662130037063161344 +1662130037105162240 +1662130037141163008 +1662130037183163904 +1662130037228164864 +1662130037270165760 +1662130037312166656 +1662130037354167552 +1662130037405168640 +1662130037450169600 +1662130037495170560 +1662130037537171456 +1662130037576172288 +1662130037627173376 +1662130037672174336 +1662130037711175168 +1662130037753176064 +1662130037795176960 +1662130037837177856 +1662130037885178880 +1662130037930179840 +1662130037972180736 +1662130038020181760 +1662130038059182592 +1662130038110183680 +1662130038161184768 +1662130038203185664 +1662130038251186688 +1662130038296187648 +1662130038341188608 +1662130038392189696 +1662130038434190592 +1662130038476191488 +1662130038524192512 +1662130038566193408 +1662130038614194432 +1662130038665195520 +1662130038713196544 +1662130038758197504 +1662130038800198400 +1662130038839199232 +1662130038881200128 +1662130038935201280 +1662130038980202240 +1662130039022203136 +1662130039064204032 +1662130039109204992 +1662130039154205952 +1662130039196206848 +1662130039241207808 +1662130039286208768 +1662130039325209600 +1662130039364210432 +1662130039412211456 +1662130039457212416 +1662130039499213312 +1662130039544214272 +1662130039592215296 +1662130039637216256 +1662130039679217152 +1662130039724218112 +1662130039769219072 +1662130039811219968 +1662130039853220864 +1662130039901221888 +1662130039946222848 +1662130039988223744 +1662130040027224576 +1662130040078225664 +1662130040132226816 +1662130040174227712 +1662130040213228544 +1662130040255229440 +1662130040294230272 +1662130040336231168 +1662130040375232000 +1662130040420232960 +1662130040468233984 +1662130040516235008 +1662130040558235904 +1662130040603236864 +1662130040648237824 +1662130040693238784 +1662130040738239744 +1662130040789240832 +1662130040828241664 +1662130040870242560 +1662130040912243456 +1662130040954244352 +1662130040999245312 +1662130041044246272 +1662130041089247232 +1662130041128248064 +1662130041170248960 +1662130041212249856 +1662130041254250752 +1662130041299251712 +1662130041341252608 +1662130041383253504 +1662130041428254464 +1662130041467255296 +1662130041518256384 +1662130041563257344 +1662130041608258304 +1662130041653259264 +1662130041698260224 +1662130041749261312 +1662130041785262080 +1662130041830263040 +1662130041872263936 +1662130041914264832 +1662130041971266048 +1662130042013266944 +1662130042061267968 +1662130042103268864 +1662130042145269760 +1662130042187270656 +1662130042238271744 +1662130042283272704 +1662130042334273792 +1662130042376274688 +1662130042418275584 +1662130042460276480 +1662130042517277696 +1662130042559278592 +1662130042601279488 +1662130042643280384 +1662130042691281408 +1662130042733282304 +1662130042775283200 +1662130042817284096 +1662130042859284992 +1662130042907286016 +1662130042955287040 +1662130043000288000 +1662130043054289152 +1662130043096290048 +1662130043135290880 +1662130043177291776 +1662130043228292864 +1662130043270293760 +1662130043312294656 +1662130043363295744 +1662130043405296640 +1662130043447297536 +1662130043501298688 +1662130043549299712 +1662130043594300672 +1662130043633301504 +1662130043678302464 +1662130043720303360 +1662130043759304192 +1662130043813305344 +1662130043858306304 +1662130043900307200 +1662130043945308160 +1662130043984308992 +1662130044026309888 +1662130044065310720 +1662130044110311680 +1662130044152312576 +1662130044194313472 +1662130044257314816 +1662130044293315584 +1662130044341316608 +1662130044383317504 +1662130044428318464 +1662130044470319360 +1662130044512320256 +1662130044557321216 +1662130044599322112 +1662130044647323136 +1662130044689324032 +1662130044734324992 +1662130044785326080 +1662130044827326976 +1662130044869327872 +1662130044911328768 +1662130044950329600 +1662130045001330688 +1662130045043331584 +1662130045091332608 +1662130045133333504 +1662130045175334400 +1662130045226335488 +1662130045268336384 +1662130045313337344 +1662130045355338240 +1662130045400339200 +1662130045448340224 +1662130045493341184 +1662130045544342272 +1662130045586343168 +1662130045628344064 +1662130045673345024 +1662130045715345920 +1662130045757346816 +1662130045799347712 +1662130045844348672 +1662130045886349568 +1662130045931350528 +1662130045973351424 +1662130046012352256 +1662130046054353152 +1662130046099354112 +1662130046138354944 +1662130046177355776 +1662130046219356672 +1662130046258357504 +1662130046300358400 +1662130046351359488 +1662130046396360448 +1662130046438361344 +1662130046477362176 +1662130046522363136 +1662130046561363968 +1662130046600364800 +1662130046642365696 +1662130046684366592 +1662130046726367488 +1662130046765368320 +1662130046807369216 +1662130046852370176 +1662130046900371200 +1662130046948372224 +1662130046990373120 +1662130047041374208 +1662130047086375168 +1662130047128376064 +1662130047170376960 +1662130047227378176 +1662130047269379072 +1662130047311379968 +1662130047356380928 +1662130047398381824 +1662130047443382784 +1662130047485383680 +1662130047530384640 +1662130047578385664 +1662130047626386688 +1662130047674387712 +1662130047725388800 +1662130047776389888 +1662130047815390720 +1662130047854391552 +1662130047896392448 +1662130047947393536 +1662130047995394560 +1662130048040395520 +1662130048088396544 +1662130048133397504 +1662130048181398528 +1662130048226399488 +1662130048274400512 +1662130048316401408 +1662130048364402432 +1662130048412403456 +1662130048460404480 +1662130048502405376 +1662130048553406464 +1662130048595407360 +1662130048643408384 +1662130048685409280 +1662130048736410368 +1662130048778411264 +1662130048829412352 +1662130048871413248 +1662130048916414208 +1662130048955415040 +1662130049003416064 +1662130049045416960 +1662130049090417920 +1662130049132418816 +1662130049180419840 +1662130049225420800 +1662130049270421760 +1662130049312422656 +1662130049375424000 +1662130049417424896 +1662130049462425856 +1662130049507426816 +1662130049552427776 +1662130049594428672 +1662130049633429504 +1662130049675430400 +1662130049726431488 +1662130049768432384 +1662130049810433280 +1662130049852434176 +1662130049897435136 +1662130049936435968 +1662130049984436992 +1662130050026437888 +1662130050068438784 +1662130050110439680 +1662130050155440640 +1662130050200441600 +1662130050245442560 +1662130050287443456 +1662130050329444352 +1662130050368445184 +1662130050410446080 +1662130050452446976 +1662130050500448000 +1662130050545448960 +1662130050587449856 +1662130050629450752 +1662130050674451712 +1662130050716452608 +1662130050761453568 +1662130050800454400 +1662130050845455360 +1662130050896456448 +1662130050941457408 +1662130050986458368 +1662130051031459328 +1662130051076460288 +1662130051118461184 +1662130051163462144 +1662130051211463168 +1662130051253464064 +1662130051298465024 +1662130051340465920 +1662130051385466880 +1662130051430467840 +1662130051478468864 +1662130051526469888 +1662130051571470848 +1662130051619471872 +1662130051664472832 +1662130051709473792 +1662130051751474688 +1662130051796475648 +1662130051838476544 +1662130051883477504 +1662130051925478400 +1662130051967479296 +1662130052006480128 +1662130052048481024 +1662130052090481920 +1662130052132482816 +1662130052180483840 +1662130052231484928 +1662130052273485824 +1662130052321486848 +1662130052363487744 +1662130052408488704 +1662130052453489664 +1662130052498490624 +1662130052546491648 +1662130052588492544 +1662130052639493632 +1662130052687494656 +1662130052729495552 +1662130052771496448 +1662130052816497408 +1662130052867498496 +1662130052912499456 +1662130052957500416 +1662130053008501504 +1662130053062502656 +1662130053107503616 +1662130053155504640 +1662130053197505536 +1662130053239506432 +1662130053281507328 +1662130053320508160 +1662130053362509056 +1662130053404509952 +1662130053446510848 +1662130053488511744 +1662130053536512768 +1662130053575513600 +1662130053629514752 +1662130053668515584 +1662130053713516544 +1662130053755517440 +1662130053800518400 +1662130053851519488 +1662130053896520448 +1662130053941521408 +1662130053983522304 +1662130054028523264 +1662130054073524224 +1662130054118525184 +1662130054160526080 +1662130054208527104 +1662130054250528000 +1662130054298529024 +1662130054346530048 +1662130054385530880 +1662130054427531776 +1662130054472532736 +1662130054514533632 +1662130054556534528 +1662130054604535552 +1662130054646536448 +1662130054694537472 +1662130054748538624 +1662130054796539648 +1662130054838540544 +1662130054880541440 +1662130054928542464 +1662130054976543488 +1662130055018544384 +1662130055060545280 +1662130055105546240 +1662130055153547264 +1662130055201548288 +1662130055246549248 +1662130055294550272 +1662130055342551296 +1662130055387552256 +1662130055429553152 +1662130055471554048 +1662130055510554880 +1662130055552555776 +1662130055594556672 +1662130055636557568 +1662130055693558784 +1662130055735559680 +1662130055777560576 +1662130055819561472 +1662130055861562368 +1662130055906563328 +1662130055948564224 +1662130055987565056 +1662130056032566016 +1662130056077566976 +1662130056119567872 +1662130056161568768 +1662130056203569664 +1662130056251570688 +1662130056290571520 +1662130056338572544 +1662130056386573568 +1662130056431574528 +1662130056476575488 +1662130056518576384 +1662130056563577344 +1662130056611578368 +1662130056656579328 +1662130056701580288 +1662130056743581184 +1662130056785582080 +1662130056827582976 +1662130056869583872 +1662130056914584832 +1662130056965585920 +1662130057010586880 +1662130057058587904 +1662130057106588928 +1662130057151589888 +1662130057193590784 +1662130057244591872 +1662130057286592768 +1662130057328593664 +1662130057376594688 +1662130057421595648 +1662130057466596608 +1662130057514597632 +1662130057553598464 +1662130057598599424 +1662130057646600448 +1662130057688601344 +1662130057730602240 +1662130057775603200 +1662130057823604224 +1662130057868605184 +1662130057910606080 +1662130057955607040 +1662130057994607872 +1662130058039608832 +1662130058084609792 +1662130058132610816 +1662130058180611840 +1662130058228612864 +1662130058279613952 +1662130058321614848 +1662130058363615744 +1662130058405616640 +1662130058450617600 +1662130058492618496 +1662130058537619456 +1662130058579620352 +1662130058624621312 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_dark.txt b/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_dark.txt new file mode 100644 index 0000000000..656025a687 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_dark.txt @@ -0,0 +1,2741 @@ +1662063934494348032 +1662063934536348928 +1662063934587350016 +1662063934629350912 +1662063934671351808 +1662063934713352704 +1662063934758353664 +1662063934803354624 +1662063934848355584 +1662063934893356544 +1662063934938357504 +1662063934977358336 +1662063935022359296 +1662063935064360192 +1662063935103361024 +1662063935145361920 +1662063935187362816 +1662063935229363712 +1662063935268364544 +1662063935310365440 +1662063935352366336 +1662063935394367232 +1662063935436368128 +1662063935478369024 +1662063935535370240 +1662063935577371136 +1662063935619372032 +1662063935670373120 +1662063935712374016 +1662063935757374976 +1662063935799375872 +1662063935844376832 +1662063935886377728 +1662063935931378688 +1662063935973379584 +1662063936015380480 +1662063936057381376 +1662063936099382272 +1662063936141383168 +1662063936180384000 +1662063936222384896 +1662063936267385856 +1662063936312386816 +1662063936360387840 +1662063936405388800 +1662063936447389696 +1662063936489390592 +1662063936531391488 +1662063936573392384 +1662063936615393280 +1662063936657394176 +1662063936699395072 +1662063936744396032 +1662063936786396928 +1662063936828397824 +1662063936870398720 +1662063936909399552 +1662063936948400384 +1662063936990401280 +1662063937038402304 +1662063937089403392 +1662063937134404352 +1662063937182405376 +1662063937224406272 +1662063937269407232 +1662063937314408192 +1662063937356409088 +1662063937401410048 +1662063937449411072 +1662063937488411904 +1662063937539412992 +1662063937584413952 +1662063937638415104 +1662063937677415936 +1662063937719416832 +1662063937761417728 +1662063937803418624 +1662063937842419456 +1662063937887420416 +1662063937935421440 +1662063937977422336 +1662063938019423232 +1662063938061424128 +1662063938106425088 +1662063938148425984 +1662063938193426944 +1662063938238427904 +1662063938283428864 +1662063938325429760 +1662063938370430720 +1662063938412431616 +1662063938457432576 +1662063938499433472 +1662063938544434432 +1662063938586435328 +1662063938631436288 +1662063938676437248 +1662063938718438144 +1662063938760439040 +1662063938802439936 +1662063938850440960 +1662063938898441984 +1662063938943442944 +1662063938988443904 +1662063939036444928 +1662063939078445824 +1662063939126446848 +1662063939165447680 +1662063939210448640 +1662063939252449536 +1662063939300450560 +1662063939342451456 +1662063939387452416 +1662063939429453312 +1662063939471454208 +1662063939510455040 +1662063939552455936 +1662063939594456832 +1662063939639457792 +1662063939681458688 +1662063939723459584 +1662063939765460480 +1662063939807461376 +1662063939852462336 +1662063939894463232 +1662063939939464192 +1662063939981465088 +1662063940026466048 +1662063940068466944 +1662063940113467904 +1662063940158468864 +1662063940209469952 +1662063940257470976 +1662063940299471872 +1662063940341472768 +1662063940383473664 +1662063940422474496 +1662063940464475392 +1662063940506476288 +1662063940548477184 +1662063940590478080 +1662063940632478976 +1662063940674479872 +1662063940716480768 +1662063940767481856 +1662063940806482688 +1662063940851483648 +1662063940899484672 +1662063940941485568 +1662063940989486592 +1662063941034487552 +1662063941079488512 +1662063941124489472 +1662063941169490432 +1662063941214491392 +1662063941262492416 +1662063941304493312 +1662063941346494208 +1662063941391495168 +1662063941436496128 +1662063941475496960 +1662063941517497856 +1662063941562498816 +1662063941604499712 +1662063941646500608 +1662063941688501504 +1662063941736502528 +1662063941784503552 +1662063941832504576 +1662063941874505472 +1662063941922506496 +1662063941964507392 +1662063942009508352 +1662063942051509248 +1662063942093510144 +1662063942138511104 +1662063942180512000 +1662063942222512896 +1662063942267513856 +1662063942309514752 +1662063942351515648 +1662063942396516608 +1662063942447517696 +1662063942498518784 +1662063942543519744 +1662063942585520640 +1662063942630521600 +1662063942672522496 +1662063942714523392 +1662063942762524416 +1662063942807525376 +1662063942852526336 +1662063942897527296 +1662063942942528256 +1662063942984529152 +1662063943029530112 +1662063943074531072 +1662063943116531968 +1662063943167533056 +1662063943206533888 +1662063943248534784 +1662063943287535616 +1662063943329536512 +1662063943374537472 +1662063943416538368 +1662063943458539264 +1662063943503540224 +1662063943545541120 +1662063943584541952 +1662063943629542912 +1662063943671543808 +1662063943710544640 +1662063943752545536 +1662063943794546432 +1662063943836547328 +1662063943884548352 +1662063943935549440 +1662063943977550336 +1662063944019551232 +1662063944061552128 +1662063944103553024 +1662063944145553920 +1662063944184554752 +1662063944229555712 +1662063944277556736 +1662063944319557632 +1662063944361558528 +1662063944418559744 +1662063944463560704 +1662063944508561664 +1662063944553562624 +1662063944595563520 +1662063944640564480 +1662063944682565376 +1662063944733566464 +1662063944778567424 +1662063944823568384 +1662063944865569280 +1662063944910570240 +1662063944955571200 +1662063944997572096 +1662063945039572992 +1662063945081573888 +1662063945126574848 +1662063945171575808 +1662063945213576704 +1662063945255577600 +1662063945297578496 +1662063945339579392 +1662063945381580288 +1662063945420581120 +1662063945465582080 +1662063945507582976 +1662063945549583872 +1662063945588584704 +1662063945642585856 +1662063945690586880 +1662063945732587776 +1662063945780588800 +1662063945822589696 +1662063945867590656 +1662063945912591616 +1662063945954592512 +1662063945999593472 +1662063946041594368 +1662063946089595392 +1662063946131596288 +1662063946173597184 +1662063946215598080 +1662063946263599104 +1662063946302599936 +1662063946344600832 +1662063946392601856 +1662063946437602816 +1662063946479603712 +1662063946524604672 +1662063946566605568 +1662063946608606464 +1662063946650607360 +1662063946692608256 +1662063946731609088 +1662063946776610048 +1662063946818610944 +1662063946863611904 +1662063946908612864 +1662063946950613760 +1662063946992614656 +1662063947037615616 +1662063947076616448 +1662063947124617472 +1662063947163618304 +1662063947205619200 +1662063947247620096 +1662063947292621056 +1662063947337622016 +1662063947382622976 +1662063947430624000 +1662063947472624896 +1662063947517625856 +1662063947565626880 +1662063947604627712 +1662063947649628672 +1662063947694629632 +1662063947736630528 +1662063947787631616 +1662063947832632576 +1662063947871633408 +1662063947913634304 +1662063947955635200 +1662063947997636096 +1662063948045637120 +1662063948087638016 +1662063948129638912 +1662063948171639808 +1662063948213640704 +1662063948270641920 +1662063948309642752 +1662063948354643712 +1662063948402644736 +1662063948444645632 +1662063948486646528 +1662063948534647552 +1662063948576648448 +1662063948621649408 +1662063948663650304 +1662063948699651072 +1662063948741651968 +1662063948783652864 +1662063948831653888 +1662063948879654912 +1662063948924655872 +1662063948966656768 +1662063949008657664 +1662063949050658560 +1662063949092659456 +1662063949134660352 +1662063949176661248 +1662063949215662080 +1662063949263663104 +1662063949305664000 +1662063949347664896 +1662063949389665792 +1662063949431666688 +1662063949473667584 +1662063949518668544 +1662063949563669504 +1662063949602670336 +1662063949641671168 +1662063949686672128 +1662063949728673024 +1662063949770673920 +1662063949812674816 +1662063949854675712 +1662063949902676736 +1662063949941677568 +1662063949986678528 +1662063950031679488 +1662063950073680384 +1662063950112681216 +1662063950154682112 +1662063950199683072 +1662063950244684032 +1662063950289684992 +1662063950334685952 +1662063950382686976 +1662063950430688000 +1662063950472688896 +1662063950520689920 +1662063950562690816 +1662063950604691712 +1662063950646692608 +1662063950688693504 +1662063950733694464 +1662063950778695424 +1662063950823696384 +1662063950865697280 +1662063950907698176 +1662063950949699072 +1662063951003700224 +1662063951042701056 +1662063951084701952 +1662063951135703040 +1662063951177703936 +1662063951222704896 +1662063951267705856 +1662063951309706752 +1662063951357707776 +1662063951402708736 +1662063951447709696 +1662063951495710720 +1662063951537711616 +1662063951585712640 +1662063951627713536 +1662063951672714496 +1662063951717715456 +1662063951759716352 +1662063951807717376 +1662063951849718272 +1662063951891719168 +1662063951933720064 +1662063951975720960 +1662063952017721856 +1662063952062722816 +1662063952104723712 +1662063952149724672 +1662063952194725632 +1662063952242726656 +1662063952287727616 +1662063952335728640 +1662063952380729600 +1662063952425730560 +1662063952470731520 +1662063952512732416 +1662063952551733248 +1662063952590734080 +1662063952635735040 +1662063952680736000 +1662063952722736896 +1662063952767737856 +1662063952809738752 +1662063952851739648 +1662063952890740480 +1662063952932741376 +1662063952980742400 +1662063953022743296 +1662063953067744256 +1662063953112745216 +1662063953154746112 +1662063953199747072 +1662063953241747968 +1662063953280748800 +1662063953325749760 +1662063953370750720 +1662063953415751680 +1662063953457752576 +1662063953502753536 +1662063953544754432 +1662063953586755328 +1662063953628756224 +1662063953676757248 +1662063953718758144 +1662063953763759104 +1662063953808760064 +1662063953850760960 +1662063953892761856 +1662063953934762752 +1662063953979763712 +1662063954024764672 +1662063954066765568 +1662063954108766464 +1662063954150767360 +1662063954192768256 +1662063954240769280 +1662063954282770176 +1662063954330771200 +1662063954375772160 +1662063954414772992 +1662063954456773888 +1662063954501774848 +1662063954543775744 +1662063954588776704 +1662063954633777664 +1662063954678778624 +1662063954720779520 +1662063954765780480 +1662063954807781376 +1662063954849782272 +1662063954891783168 +1662063954933784064 +1662063954975784960 +1662063955017785856 +1662063955065786880 +1662063955113787904 +1662063955155788800 +1662063955197789696 +1662063955242790656 +1662063955284791552 +1662063955329792512 +1662063955374793472 +1662063955425794560 +1662063955464795392 +1662063955509796352 +1662063955548797184 +1662063955590798080 +1662063955629798912 +1662063955671799808 +1662063955713800704 +1662063955755801600 +1662063955800802560 +1662063955854803712 +1662063955896804608 +1662063955938805504 +1662063955986806528 +1662063956031807488 +1662063956079808512 +1662063956121809408 +1662063956163810304 +1662063956205811200 +1662063956247812096 +1662063956289812992 +1662063956331813888 +1662063956376814848 +1662063956415815680 +1662063956457816576 +1662063956502817536 +1662063956547818496 +1662063956589819392 +1662063956637820416 +1662063956679821312 +1662063956718822144 +1662063956766823168 +1662063956814824192 +1662063956865825280 +1662063956910826240 +1662063956952827136 +1662063956997828096 +1662063957039828992 +1662063957084829952 +1662063957126830848 +1662063957171831808 +1662063957216832768 +1662063957261833728 +1662063957303834624 +1662063957348835584 +1662063957387836416 +1662063957429837312 +1662063957474838272 +1662063957522839296 +1662063957564840192 +1662063957603841024 +1662063957645841920 +1662063957690842880 +1662063957732843776 +1662063957777844736 +1662063957819845632 +1662063957864846592 +1662063957912847616 +1662063957954848512 +1662063957996849408 +1662063958041850368 +1662063958083851264 +1662063958131852288 +1662063958176853248 +1662063958224854272 +1662063958269855232 +1662063958320856320 +1662063958365857280 +1662063958407858176 +1662063958452859136 +1662063958494860032 +1662063958536860928 +1662063958584861952 +1662063958626862848 +1662063958668863744 +1662063958713864704 +1662063958752865536 +1662063958803866624 +1662063958848867584 +1662063958893868544 +1662063958941869568 +1662063958992870656 +1662063959034871552 +1662063959079872512 +1662063959121873408 +1662063959166874368 +1662063959208875264 +1662063959253876224 +1662063959301877248 +1662063959355878400 +1662063959397879296 +1662063959436880128 +1662063959478881024 +1662063959529882112 +1662063959574883072 +1662063959616883968 +1662063959658884864 +1662063959700885760 +1662063959742886656 +1662063959784887552 +1662063959829888512 +1662063959871889408 +1662063959913890304 +1662063959955891200 +1662063959997892096 +1662063960039892992 +1662063960084893952 +1662063960129894912 +1662063960174895872 +1662063960216896768 +1662063960258897664 +1662063960300898560 +1662063960342899456 +1662063960387900416 +1662063960429901312 +1662063960474902272 +1662063960525903360 +1662063960567904256 +1662063960606905088 +1662063960648905984 +1662063960687906816 +1662063960732907776 +1662063960774908672 +1662063960816909568 +1662063960861910528 +1662063960906911488 +1662063960948912384 +1662063960990913280 +1662063961032914176 +1662063961074915072 +1662063961119916032 +1662063961164916992 +1662063961209917952 +1662063961254918912 +1662063961299919872 +1662063961344920832 +1662063961389921792 +1662063961428922624 +1662063961470923520 +1662063961515924480 +1662063961563925504 +1662063961608926464 +1662063961650927360 +1662063961689928192 +1662063961728929024 +1662063961776930048 +1662063961821931008 +1662063961863931904 +1662063961908932864 +1662063961956933888 +1662063961998934784 +1662063962040935680 +1662063962088936704 +1662063962136937728 +1662063962178938624 +1662063962223939584 +1662063962271940608 +1662063962316941568 +1662063962367942656 +1662063962409943552 +1662063962451944448 +1662063962496945408 +1662063962547946496 +1662063962592947456 +1662063962640948480 +1662063962682949376 +1662063962724950272 +1662063962769951232 +1662063962814952192 +1662063962871953408 +1662063962913954304 +1662063962958955264 +1662063963006956288 +1662063963045957120 +1662063963090958080 +1662063963132958976 +1662063963183960064 +1662063963225960960 +1662063963267961856 +1662063963309962752 +1662063963354963712 +1662063963396964608 +1662063963435965440 +1662063963483966464 +1662063963531967488 +1662063963579968512 +1662063963621969408 +1662063963663970304 +1662063963711971328 +1662063963759972352 +1662063963801973248 +1662063963840974080 +1662063963885975040 +1662063963927975936 +1662063963972976896 +1662063964017977856 +1662063964059978752 +1662063964101979648 +1662063964143980544 +1662063964185981440 +1662063964227982336 +1662063964275983360 +1662063964320984320 +1662063964359985152 +1662063964401986048 +1662063964440986880 +1662063964479987712 +1662063964524988672 +1662063964566989568 +1662063964608990464 +1662063964653991424 +1662063964701992448 +1662063964749993472 +1662063964794994432 +1662063964836995328 +1662063964878996224 +1662063964923997184 +1662063964968998144 +1662063965010999040 +1662063965052999936 +1662063965098000896 +1662063965155002112 +1662063965197003008 +1662063965245004032 +1662063965287004928 +1662063965332005888 +1662063965377006848 +1662063965422007808 +1662063965461008640 +1662063965506009600 +1662063965545010432 +1662063965593011456 +1662063965635012352 +1662063965677013248 +1662063965719014144 +1662063965761015040 +1662063965809016064 +1662063965851016960 +1662063965893017856 +1662063965935018752 +1662063965980019712 +1662063966028020736 +1662063966073021696 +1662063966115022592 +1662063966160023552 +1662063966205024512 +1662063966250025472 +1662063966295026432 +1662063966337027328 +1662063966382028288 +1662063966427029248 +1662063966472030208 +1662063966514031104 +1662063966559032064 +1662063966601032960 +1662063966646033920 +1662063966688034816 +1662063966736035840 +1662063966781036800 +1662063966823037696 +1662063966868038656 +1662063966919039744 +1662063966964040704 +1662063967009041664 +1662063967054042624 +1662063967096043520 +1662063967138044416 +1662063967183045376 +1662063967225046272 +1662063967267047168 +1662063967309048064 +1662063967351048960 +1662063967393049856 +1662063967435050752 +1662063967477051648 +1662063967525052672 +1662063967570053632 +1662063967612054528 +1662063967654055424 +1662063967702056448 +1662063967741057280 +1662063967786058240 +1662063967828059136 +1662063967867059968 +1662063967909060864 +1662063967954061824 +1662063968002062848 +1662063968047063808 +1662063968089064704 +1662063968137065728 +1662063968179066624 +1662063968230067712 +1662063968275068672 +1662063968320069632 +1662063968365070592 +1662063968410071552 +1662063968455072512 +1662063968497073408 +1662063968539074304 +1662063968584075264 +1662063968623076096 +1662063968665076992 +1662063968710077952 +1662063968761079040 +1662063968803079936 +1662063968848080896 +1662063968893081856 +1662063968938082816 +1662063968983083776 +1662063969025084672 +1662063969073085696 +1662063969115086592 +1662063969157087488 +1662063969205088512 +1662063969253089536 +1662063969295090432 +1662063969346091520 +1662063969391092480 +1662063969433093376 +1662063969478094336 +1662063969523095296 +1662063969565096192 +1662063969610097152 +1662063969655098112 +1662063969700099072 +1662063969739099904 +1662063969781100800 +1662063969826101760 +1662063969868102656 +1662063969913103616 +1662063969967104768 +1662063970009105664 +1662063970051106560 +1662063970093107456 +1662063970132108288 +1662063970180109312 +1662063970228110336 +1662063970267111168 +1662063970309112064 +1662063970360113152 +1662063970405114112 +1662063970447115008 +1662063970492115968 +1662063970531116800 +1662063970576117760 +1662063970615118592 +1662063970660119552 +1662063970711120640 +1662063970750121472 +1662063970792122368 +1662063970834123264 +1662063970876124160 +1662063970918125056 +1662063970960125952 +1662063971002126848 +1662063971044127744 +1662063971089128704 +1662063971131129600 +1662063971176130560 +1662063971218131456 +1662063971260132352 +1662063971299133184 +1662063971341134080 +1662063971389135104 +1662063971431136000 +1662063971473136896 +1662063971515137792 +1662063971557138688 +1662063971605139712 +1662063971650140672 +1662063971692141568 +1662063971740142592 +1662063971782143488 +1662063971827144448 +1662063971869145344 +1662063971914146304 +1662063971956147200 +1662063971998148096 +1662063972040148992 +1662063972088150016 +1662063972142151168 +1662063972187152128 +1662063972232153088 +1662063972271153920 +1662063972316154880 +1662063972358155776 +1662063972400156672 +1662063972448157696 +1662063972490158592 +1662063972535159552 +1662063972577160448 +1662063972622161408 +1662063972661162240 +1662063972703163136 +1662063972754164224 +1662063972802165248 +1662063972853166336 +1662063972895167232 +1662063972937168128 +1662063972982169088 +1662063973024169984 +1662063973072171008 +1662063973114171904 +1662063973156172800 +1662063973201173760 +1662063973252174848 +1662063973300175872 +1662063973348176896 +1662063973402178048 +1662063973444178944 +1662063973486179840 +1662063973525180672 +1662063973564181504 +1662063973618182656 +1662063973660183552 +1662063973699184384 +1662063973744185344 +1662063973789186304 +1662063973834187264 +1662063973876188160 +1662063973921189120 +1662063973963190016 +1662063974014191104 +1662063974056192000 +1662063974095192832 +1662063974137193728 +1662063974176194560 +1662063974218195456 +1662063974260196352 +1662063974302197248 +1662063974350198272 +1662063974389199104 +1662063974440200192 +1662063974482201088 +1662063974527202048 +1662063974572203008 +1662063974614203904 +1662063974659204864 +1662063974704205824 +1662063974749206784 +1662063974797207808 +1662063974839208704 +1662063974881209600 +1662063974929210624 +1662063974971211520 +1662063975016212480 +1662063975064213504 +1662063975106214400 +1662063975154215424 +1662063975196216320 +1662063975238217216 +1662063975280218112 +1662063975325219072 +1662063975370220032 +1662063975412220928 +1662063975454221824 +1662063975493222656 +1662063975532223488 +1662063975577224448 +1662063975619225344 +1662063975661226240 +1662063975703227136 +1662063975748228096 +1662063975790228992 +1662063975832229888 +1662063975874230784 +1662063975910231552 +1662063975955232512 +1662063975994233344 +1662063976036234240 +1662063976084235264 +1662063976126236160 +1662063976168237056 +1662063976219238144 +1662063976261239040 +1662063976303239936 +1662063976345240832 +1662063976387241728 +1662063976429242624 +1662063976471243520 +1662063976519244544 +1662063976561245440 +1662063976603246336 +1662063976648247296 +1662063976693248256 +1662063976735249152 +1662063976780250112 +1662063976822251008 +1662063976867251968 +1662063976909252864 +1662063976954253824 +1662063977002254848 +1662063977044255744 +1662063977089256704 +1662063977134257664 +1662063977176258560 +1662063977218259456 +1662063977263260416 +1662063977305261312 +1662063977347262208 +1662063977389263104 +1662063977434264064 +1662063977476264960 +1662063977521265920 +1662063977563266816 +1662063977617267968 +1662063977659268864 +1662063977704269824 +1662063977761271040 +1662063977806272000 +1662063977854273024 +1662063977896273920 +1662063977938274816 +1662063977977275648 +1662063978022276608 +1662063978067277568 +1662063978112278528 +1662063978151279360 +1662063978196280320 +1662063978238281216 +1662063978286282240 +1662063978340283392 +1662063978397284608 +1662063978445285632 +1662063978484286464 +1662063978529287424 +1662063978571288320 +1662063978616289280 +1662063978658290176 +1662063978703291136 +1662063978745292032 +1662063978784292864 +1662063978826293760 +1662063978868294656 +1662063978913295616 +1662063978961296640 +1662063979003297536 +1662063979051298560 +1662063979093299456 +1662063979138300416 +1662063979186301440 +1662063979228302336 +1662063979267303168 +1662063979318304256 +1662063979363305216 +1662063979408306176 +1662063979453307136 +1662063979495308032 +1662063979534308864 +1662063979585309952 +1662063979627310848 +1662063979669311744 +1662063979711312640 +1662063979756313600 +1662063979798314496 +1662063979843315456 +1662063979888316416 +1662063979930317312 +1662063979978318336 +1662063980020319232 +1662063980065320192 +1662063980110321152 +1662063980158322176 +1662063980200323072 +1662063980239323904 +1662063980284324864 +1662063980326325760 +1662063980368326656 +1662063980410327552 +1662063980455328512 +1662063980503329536 +1662063980545330432 +1662063980587331328 +1662063980635332352 +1662063980683333376 +1662063980722334208 +1662063980764335104 +1662063980806336000 +1662063980854337024 +1662063980896337920 +1662063980947339008 +1662063980992339968 +1662063981034340864 +1662063981073341696 +1662063981118342656 +1662063981157343488 +1662063981199344384 +1662063981250345472 +1662063981292346368 +1662063981337347328 +1662063981379348224 +1662063981421349120 +1662063981472350208 +1662063981517351168 +1662063981574352384 +1662063981616353280 +1662063981667354368 +1662063981712355328 +1662063981757356288 +1662063981796357120 +1662063981841358080 +1662063981889359104 +1662063981931360000 +1662063981982361088 +1662063982024361984 +1662063982066362880 +1662063982114363904 +1662063982159364864 +1662063982201365760 +1662063982240366592 +1662063982288367616 +1662063982333368576 +1662063982384369664 +1662063982426370560 +1662063982465371392 +1662063982519372544 +1662063982561373440 +1662063982606374400 +1662063982648375296 +1662063982693376256 +1662063982738377216 +1662063982780378112 +1662063982822379008 +1662063982867379968 +1662063982909380864 +1662063982954381824 +1662063982993382656 +1662063983035383552 +1662063983080384512 +1662063983122385408 +1662063983173386496 +1662063983212387328 +1662063983257388288 +1662063983296389120 +1662063983338390016 +1662063983386391040 +1662063983434392064 +1662063983479393024 +1662063983524393984 +1662063983566394880 +1662063983608395776 +1662063983656396800 +1662063983698397696 +1662063983737398528 +1662063983779399424 +1662063983824400384 +1662063983863401216 +1662063983905402112 +1662063983959403264 +1662063984001404160 +1662063984043405056 +1662063984085405952 +1662063984124406784 +1662063984166407680 +1662063984220408832 +1662063984262409728 +1662063984310410752 +1662063984355411712 +1662063984397412608 +1662063984436413440 +1662063984478414336 +1662063984520415232 +1662063984568416256 +1662063984613417216 +1662063984658418176 +1662063984703419136 +1662063984745420032 +1662063984790420992 +1662063984835421952 +1662063984880422912 +1662063984940424192 +1662063984979425024 +1662063985021425920 +1662063985063426816 +1662063985111427840 +1662063985153428736 +1662063985195429632 +1662063985249430784 +1662063985291431680 +1662063985330432512 +1662063985375433472 +1662063985420434432 +1662063985459435264 +1662063985504436224 +1662063985546437120 +1662063985591438080 +1662063985636439040 +1662063985678439936 +1662063985726440960 +1662063985765441792 +1662063985807442688 +1662063985855443712 +1662063985900444672 +1662063985939445504 +1662063985987446528 +1662063986029447424 +1662063986074448384 +1662063986116449280 +1662063986158450176 +1662063986200451072 +1662063986248452096 +1662063986290452992 +1662063986335453952 +1662063986377454848 +1662063986419455744 +1662063986461456640 +1662063986509457664 +1662063986551458560 +1662063986593459456 +1662063986647460608 +1662063986686461440 +1662063986728462336 +1662063986770463232 +1662063986809464064 +1662063986851464960 +1662063986896465920 +1662063986938466816 +1662063986980467712 +1662063987022468608 +1662063987070469632 +1662063987112470528 +1662063987157471488 +1662063987196472320 +1662063987238473216 +1662063987289474304 +1662063987334475264 +1662063987391476480 +1662063987430477312 +1662063987475478272 +1662063987517479168 +1662063987559480064 +1662063987601480960 +1662063987637481728 +1662063987679482624 +1662063987721483520 +1662063987763484416 +1662063987805485312 +1662063987847486208 +1662063987889487104 +1662063987937488128 +1662063987979489024 +1662063988021489920 +1662063988057490688 +1662063988102491648 +1662063988144492544 +1662063988186493440 +1662063988231494400 +1662063988273495296 +1662063988318496256 +1662063988360497152 +1662063988402498048 +1662063988441498880 +1662063988483499776 +1662063988525500672 +1662063988567501568 +1662063988609502464 +1662063988651503360 +1662063988696504320 +1662063988738505216 +1662063988783506176 +1662063988825507072 +1662063988879508224 +1662063988921509120 +1662063988963510016 +1662063989008510976 +1662063989050511872 +1662063989092512768 +1662063989140513792 +1662063989185514752 +1662063989227515648 +1662063989269516544 +1662063989317517568 +1662063989362518528 +1662063989404519424 +1662063989449520384 +1662063989491521280 +1662063989533522176 +1662063989578523136 +1662063989623524096 +1662063989665524992 +1662063989707525888 +1662063989755526912 +1662063989797527808 +1662063989839528704 +1662063989881529600 +1662063989926530560 +1662063989971531520 +1662063990016532480 +1662063990055533312 +1662063990097534208 +1662063990139535104 +1662063990181536000 +1662063990223536896 +1662063990265537792 +1662063990307538688 +1662063990349539584 +1662063990391540480 +1662063990439541504 +1662063990481542400 +1662063990526543360 +1662063990571544320 +1662063990610545152 +1662063990652546048 +1662063990694546944 +1662063990739547904 +1662063990784548864 +1662063990826549760 +1662063990874550784 +1662063990916551680 +1662063990958552576 +1662063991003553536 +1662063991045554432 +1662063991087555328 +1662063991135556352 +1662063991183557376 +1662063991231558400 +1662063991270559232 +1662063991318560256 +1662063991360561152 +1662063991405562112 +1662063991450563072 +1662063991492563968 +1662063991540564992 +1662063991579565824 +1662063991618566656 +1662063991666567680 +1662063991708568576 +1662063991753569536 +1662063991801570560 +1662063991843571456 +1662063991888572416 +1662063991930573312 +1662063991975574272 +1662063992020575232 +1662063992065576192 +1662063992113577216 +1662063992158578176 +1662063992197579008 +1662063992245580032 +1662063992284580864 +1662063992332581888 +1662063992374582784 +1662063992422583808 +1662063992470584832 +1662063992521585920 +1662063992563586816 +1662063992602587648 +1662063992647588608 +1662063992692589568 +1662063992740590592 +1662063992785591552 +1662063992836592640 +1662063992875593472 +1662063992917594368 +1662063992962595328 +1662063993004596224 +1662063993049597184 +1662063993094598144 +1662063993139599104 +1662063993178599936 +1662063993223600896 +1662063993262601728 +1662063993304602624 +1662063993349603584 +1662063993388604416 +1662063993430605312 +1662063993475606272 +1662063993517607168 +1662063993559608064 +1662063993601608960 +1662063993649609984 +1662063993691610880 +1662063993733611776 +1662063993775612672 +1662063993826613760 +1662063993865614592 +1662063993907615488 +1662063993949616384 +1662063994000617472 +1662063994045618432 +1662063994084619264 +1662063994126620160 +1662063994162620928 +1662063994207621888 +1662063994255622912 +1662063994303623936 +1662063994345624832 +1662063994399625984 +1662063994444626944 +1662063994486627840 +1662063994525628672 +1662063994573629696 +1662063994621630720 +1662063994669631744 +1662063994711632640 +1662063994756633600 +1662063994798634496 +1662063994846635520 +1662063994888636416 +1662063994939637504 +1662063994990638592 +1662063995032639488 +1662063995077640448 +1662063995119641344 +1662063995164642304 +1662063995209643264 +1662063995254644224 +1662063995299645184 +1662063995347646208 +1662063995389647104 +1662063995434648064 +1662063995479649024 +1662063995527650048 +1662063995569650944 +1662063995608651776 +1662063995650652672 +1662063995695653632 +1662063995737654528 +1662063995785655552 +1662063995830656512 +1662063995872657408 +1662063995914658304 +1662063995953659136 +1662063995998660096 +1662063996040660992 +1662063996085661952 +1662063996133662976 +1662063996181664000 +1662063996229665024 +1662063996283666176 +1662063996325667072 +1662063996373668096 +1662063996412668928 +1662063996463670016 +1662063996508670976 +1662063996550671872 +1662063996592672768 +1662063996637673728 +1662063996679674624 +1662063996730675712 +1662063996775676672 +1662063996817677568 +1662063996859678464 +1662063996904679424 +1662063996952680448 +1662063996997681408 +1662063997048682496 +1662063997087683328 +1662063997126684160 +1662063997177685248 +1662063997222686208 +1662063997264687104 +1662063997306688000 +1662063997345688832 +1662063997396689920 +1662063997444690944 +1662063997486691840 +1662063997531692800 +1662063997573693696 +1662063997621694720 +1662063997666695680 +1662063997708696576 +1662063997750697472 +1662063997795698432 +1662063997840699392 +1662063997888700416 +1662063997933701376 +1662063997975702272 +1662063998020703232 +1662063998062704128 +1662063998107705088 +1662063998149705984 +1662063998200707072 +1662063998242707968 +1662063998287708928 +1662063998335709952 +1662063998377710848 +1662063998428711936 +1662063998473712896 +1662063998527714048 +1662063998575715072 +1662063998626716160 +1662063998677717248 +1662063998725718272 +1662063998770719232 +1662063998812720128 +1662063998854721024 +1662063998896721920 +1662063998944722944 +1662063998986723840 +1662063999028724736 +1662063999079725824 +1662063999121726720 +1662063999163727616 +1662063999208728576 +1662063999250729472 +1662063999292730368 +1662063999334731264 +1662063999385732352 +1662063999433733376 +1662063999475734272 +1662063999517735168 +1662063999559736064 +1662063999604737024 +1662063999646737920 +1662063999688738816 +1662063999730739712 +1662063999769740544 +1662063999811741440 +1662063999856742400 +1662063999904743424 +1662063999946744320 +1662063999988745216 +1662064000027746048 +1662064000069746944 +1662064000114747904 +1662064000156748800 +1662064000201749760 +1662064000246750720 +1662064000291751680 +1662064000333752576 +1662064000378753536 +1662064000420754432 +1662064000465755392 +1662064000510756352 +1662064000555757312 +1662064000603758336 +1662064000648759296 +1662064000687760128 +1662064000729761024 +1662064000771761920 +1662064000816762880 +1662064000864763904 +1662064000906764800 +1662064000948765696 +1662064000993766656 +1662064001044767744 +1662064001086768640 +1662064001128769536 +1662064001173770496 +1662064001215771392 +1662064001260772352 +1662064001308773376 +1662064001350774272 +1662064001398775296 +1662064001440776192 +1662064001488777216 +1662064001533778176 +1662064001578779136 +1662064001629780224 +1662064001671781120 +1662064001713782016 +1662064001755782912 +1662064001797783808 +1662064001839784704 +1662064001881785600 +1662064001929786624 +1662064001971787520 +1662064002013788416 +1662064002055789312 +1662064002097790208 +1662064002142791168 +1662064002187792128 +1662064002229793024 +1662064002274793984 +1662064002319794944 +1662064002373796096 +1662064002415796992 +1662064002457797888 +1662064002499798784 +1662064002550799872 +1662064002592800768 +1662064002634801664 +1662064002673802496 +1662064002718803456 +1662064002760804352 +1662064002805805312 +1662064002847806208 +1662064002889807104 +1662064002931808000 +1662064002979809024 +1662064003030810112 +1662064003075811072 +1662064003120812032 +1662064003168813056 +1662064003207813888 +1662064003249814784 +1662064003294815744 +1662064003342816768 +1662064003390817792 +1662064003435818752 +1662064003477819648 +1662064003522820608 +1662064003564821504 +1662064003606822400 +1662064003654823424 +1662064003699824384 +1662064003747825408 +1662064003789826304 +1662064003828827136 +1662064003873828096 +1662064003915828992 +1662064003960829952 +1662064004008830976 +1662064004053831936 +1662064004092832768 +1662064004134833664 +1662064004176834560 +1662064004218835456 +1662064004266836480 +1662064004308837376 +1662064004350838272 +1662064004392839168 +1662064004434840064 +1662064004485841152 +1662064004527842048 +1662064004575843072 +1662064004617843968 +1662064004668845056 +1662064004713846016 +1662064004758846976 +1662064004800847872 +1662064004842848768 +1662064004887849728 +1662064004929850624 +1662064004971851520 +1662064005019852544 +1662064005064853504 +1662064005115854592 +1662064005160855552 +1662064005202856448 +1662064005247857408 +1662064005289858304 +1662064005331859200 +1662064005373860096 +1662064005424861184 +1662064005466862080 +1662064005511863040 +1662064005553863936 +1662064005598864896 +1662064005640865792 +1662064005682866688 +1662064005736867840 +1662064005781868800 +1662064005826869760 +1662064005871870720 +1662064005910871552 +1662064005955872512 +1662064006000873472 +1662064006045874432 +1662064006090875392 +1662064006132876288 +1662064006177877248 +1662064006222878208 +1662064006264879104 +1662064006309880064 +1662064006360881152 +1662064006402882048 +1662064006444882944 +1662064006489883904 +1662064006531884800 +1662064006576885760 +1662064006621886720 +1662064006669887744 +1662064006717888768 +1662064006762889728 +1662064006804890624 +1662064006855891712 +1662064006897892608 +1662064006942893568 +1662064006990894592 +1662064007032895488 +1662064007077896448 +1662064007119897344 +1662064007161898240 +1662064007206899200 +1662064007248900096 +1662064007290900992 +1662064007332901888 +1662064007374902784 +1662064007425903872 +1662064007464904704 +1662064007512905728 +1662064007557906688 +1662064007602907648 +1662064007647908608 +1662064007692909568 +1662064007746910720 +1662064007791911680 +1662064007833912576 +1662064007878913536 +1662064007920914432 +1662064007962915328 +1662064008004916224 +1662064008046917120 +1662064008091918080 +1662064008133918976 +1662064008175919872 +1662064008220920832 +1662064008262921728 +1662064008307922688 +1662064008352923648 +1662064008394924544 +1662064008436925440 +1662064008478926336 +1662064008520927232 +1662064008565928192 +1662064008610929152 +1662064008664930304 +1662064008709931264 +1662064008754932224 +1662064008796933120 +1662064008844934144 +1662064008889935104 +1662064008934936064 +1662064008985937152 +1662064009027938048 +1662064009075939072 +1662064009120940032 +1662064009162940928 +1662064009207941888 +1662064009249942784 +1662064009288943616 +1662064009339944704 +1662064009381945600 +1662064009423946496 +1662064009465947392 +1662064009510948352 +1662064009558949376 +1662064009597950208 +1662064009636951040 +1662064009678951936 +1662064009717952768 +1662064009762953728 +1662064009807954688 +1662064009849955584 +1662064009897956608 +1662064009948957696 +1662064009990958592 +1662064010035959552 +1662064010077960448 +1662064010122961408 +1662064010170962432 +1662064010215963392 +1662064010260964352 +1662064010317965568 +1662064010365966592 +1662064010410967552 +1662064010458968576 +1662064010500969472 +1662064010542970368 +1662064010587971328 +1662064010629972224 +1662064010674973184 +1662064010719974144 +1662064010767975168 +1662064010809976064 +1662064010857977088 +1662064010902978048 +1662064010947979008 +1662064010989979904 +1662064011031980800 +1662064011073981696 +1662064011121982720 +1662064011172983808 +1662064011214984704 +1662064011259985664 +1662064011307986688 +1662064011346987520 +1662064011391988480 +1662064011436989440 +1662064011478990336 +1662064011523991296 +1662064011568992256 +1662064011610993152 +1662064011655994112 +1662064011700995072 +1662064011748996096 +1662064011790996992 +1662064011835997952 +1662064011877998848 +1662064011919999744 +1662064011965000704 +1662064012010001664 +1662064012049002496 +1662064012091003392 +1662064012133004288 +1662064012175005184 +1662064012217006080 +1662064012262007040 +1662064012301007872 +1662064012346008832 +1662064012391009792 +1662064012433010688 +1662064012481011712 +1662064012526012672 +1662064012568013568 +1662064012610014464 +1662064012652015360 +1662064012694016256 +1662064012748017408 +1662064012790018304 +1662064012832019200 +1662064012874020096 +1662064012916020992 +1662064012961021952 +1662064013015023104 +1662064013060024064 +1662064013105025024 +1662064013150025984 +1662064013192026880 +1662064013237027840 +1662064013279028736 +1662064013321029632 +1662064013369030656 +1662064013411031552 +1662064013456032512 +1662064013501033472 +1662064013543034368 +1662064013585035264 +1662064013630036224 +1662064013678037248 +1662064013720038144 +1662064013768039168 +1662064013810040064 +1662064013855041024 +1662064013900041984 +1662064013948043008 +1662064013993043968 +1662064014038044928 +1662064014089046016 +1662064014134046976 +1662064014179047936 +1662064014224048896 +1662064014275049984 +1662064014314050816 +1662064014356051712 +1662064014401052672 +1662064014446053632 +1662064014488054528 +1662064014533055488 +1662064014578056448 +1662064014623057408 +1662064014662058240 +1662064014710059264 +1662064014758060288 +1662064014797061120 +1662064014839062016 +1662064014887063040 +1662064014935064064 +1662064014980065024 +1662064015031066112 +1662064015082067200 +1662064015124068096 +1662064015166068992 +1662064015211069952 +1662064015259070976 +1662064015304071936 +1662064015349072896 +1662064015391073792 +1662064015436074752 +1662064015478075648 +1662064015520076544 +1662064015574077696 +1662064015634078976 +1662064015685080064 +1662064015727080960 +1662064015769081856 +1662064015811082752 +1662064015850083584 +1662064015889084416 +1662064015931085312 +1662064015973086208 +1662064016018087168 +1662064016060088064 +1662064016111089152 +1662064016153090048 +1662064016198091008 +1662064016240091904 +1662064016294093056 +1662064016342094080 +1662064016387095040 +1662064016435096064 +1662064016477096960 +1662064016522097920 +1662064016564098816 +1662064016609099776 +1662064016660100864 +1662064016705101824 +1662064016750102784 +1662064016792103680 +1662064016837104640 +1662064016879105536 +1662064016924106496 +1662064016966107392 +1662064017011108352 +1662064017053109248 +1662064017095110144 +1662064017140111104 +1662064017182112000 +1662064017227112960 +1662064017269113856 +1662064017311114752 +1662064017353115648 +1662064017395116544 +1662064017437117440 +1662064017482118400 +1662064017524119296 +1662064017566120192 +1662064017608121088 +1662064017656122112 +1662064017704123136 +1662064017749124096 +1662064017791124992 +1662064017836125952 +1662064017878126848 +1662064017920127744 +1662064017965128704 +1662064018010129664 +1662064018055130624 +1662064018103131648 +1662064018145132544 +1662064018187133440 +1662064018232134400 +1662064018289135616 +1662064018334136576 +1662064018382137600 +1662064018421138432 +1662064018463139328 +1662064018505140224 +1662064018550141184 +1662064018595142144 +1662064018640143104 +1662064018682144000 +1662064018721144832 +1662064018766145792 +1662064018808146688 +1662064018850147584 +1662064018892148480 +1662064018934149376 +1662064018976150272 +1662064019024151296 +1662064019066152192 +1662064019111153152 +1662064019153154048 +1662064019198155008 +1662064019243155968 +1662064019288156928 +1662064019327157760 +1662064019378158848 +1662064019417159680 +1662064019462160640 +1662064019507161600 +1662064019552162560 +1662064019594163456 +1662064019636164352 +1662064019672165120 +1662064019717166080 +1662064019756166912 +1662064019798167808 +1662064019843168768 +1662064019888169728 +1662064019936170752 +1662064019978171648 +1662064020020172544 +1662064020065173504 +1662064020107174400 +1662064020152175360 +1662064020194176256 +1662064020239177216 +1662064020284178176 +1662064020329179136 +1662064020377180160 +1662064020428181248 +1662064020479182336 +1662064020521183232 +1662064020572184320 +1662064020614185216 +1662064020662186240 +1662064020707187200 +1662064020752188160 +1662064020794189056 +1662064020836189952 +1662064020878190848 +1662064020923191808 +1662064020968192768 +1662064021013193728 +1662064021058194688 +1662064021100195584 +1662064021154196736 +1662064021205197824 +1662064021247198720 +1662064021289199616 +1662064021331200512 +1662064021373201408 +1662064021421202432 +1662064021463203328 +1662064021508204288 +1662064021553205248 +1662064021595206144 +1662064021637207040 +1662064021682208000 +1662064021724208896 +1662064021766209792 +1662064021811210752 +1662064021853211648 +1662064021901212672 +1662064021949213696 +1662064021994214656 +1662064022036215552 +1662064022081216512 +1662064022120217344 +1662064022162218240 +1662064022210219264 +1662064022255220224 +1662064022297221120 +1662064022342222080 +1662064022384222976 +1662064022432224000 +1662064022474224896 +1662064022525225984 +1662064022567226880 +1662064022612227840 +1662064022660228864 +1662064022702229760 +1662064022747230720 +1662064022789231616 +1662064022831232512 +1662064022888233728 +1662064022930234624 +1662064022978235648 +1662064023017236480 +1662064023065237504 +1662064023116238592 +1662064023155239424 +1662064023197240320 +1662064023239241216 +1662064023281242112 +1662064023323243008 +1662064023365243904 +1662064023407244800 +1662064023449245696 +1662064023500246784 +1662064023542247680 +1662064023584248576 +1662064023632249600 +1662064023677250560 +1662064023725251584 +1662064023767252480 +1662064023809253376 +1662064023857254400 +1662064023902255360 +1662064023944256256 +1662064023989257216 +1662064024031258112 +1662064024076259072 +1662064024127260160 +1662064024175261184 +1662064024217262080 +1662064024262263040 +1662064024304263936 +1662064024352264960 +1662064024397265920 +1662064024448267008 +1662064024496268032 +1662064024538268928 +1662064024583269888 +1662064024634270976 +1662064024679271936 +1662064024727272960 +1662064024778274048 +1662064024820274944 +1662064024871276032 +1662064024913276928 +1662064024955277824 +1662064024997278720 +1662064025039279616 +1662064025090280704 +1662064025129281536 +1662064025177282560 +1662064025228283648 +1662064025270284544 +1662064025312285440 +1662064025354286336 +1662064025396287232 +1662064025456288512 +1662064025507289600 +1662064025549290496 +1662064025594291456 +1662064025636292352 +1662064025678293248 +1662064025720294144 +1662064025768295168 +1662064025807296000 +1662064025852296960 +1662064025891297792 +1662064025933298688 +1662064025972299520 +1662064026020300544 +1662064026059301376 +1662064026101302272 +1662064026152303360 +1662064026197304320 +1662064026242305280 +1662064026284306176 +1662064026326307072 +1662064026368307968 +1662064026413308928 +1662064026455309824 +1662064026500310784 +1662064026539311616 +1662064026578312448 +1662064026620313344 +1662064026659314176 +1662064026701315072 +1662064026740315904 +1662064026785316864 +1662064026833317888 +1662064026878318848 +1662064026917319680 +1662064026962320640 +1662064027007321600 +1662064027061322752 +1662064027103323648 +1662064027142324480 +1662064027184325376 +1662064027226326272 +1662064027271327232 +1662064027313328128 +1662064027355329024 +1662064027397329920 +1662064027442330880 +1662064027484331776 +1662064027532332800 +1662064027571333632 +1662064027613334528 +1662064027655335424 +1662064027700336384 +1662064027745337344 +1662064027787338240 +1662064027832339200 +1662064027877340160 +1662064027922341120 +1662064027964342016 +1662064028006342912 +1662064028051343872 +1662064028093344768 +1662064028144345856 +1662064028192346880 +1662064028234347776 +1662064028288348928 +1662064028333349888 +1662064028378350848 +1662064028423351808 +1662064028462352640 +1662064028510353664 +1662064028549354496 +1662064028591355392 +1662064028636356352 +1662064028678357248 +1662064028723358208 +1662064028768359168 +1662064028810360064 +1662064028849360896 +1662064028891361792 +1662064028933362688 +1662064028975363584 +1662064029029364736 +1662064029071365632 +1662064029113366528 +1662064029158367488 +1662064029203368448 +1662064029245369344 +1662064029284370176 +1662064029329371136 +1662064029374372096 +1662064029416372992 +1662064029458373888 +1662064029503374848 +1662064029545375744 +1662064029593376768 +1662064029635377664 +1662064029683378688 +1662064029725379584 +1662064029767380480 +1662064029818381568 +1662064029866382592 +1662064029908383488 +1662064029950384384 +1662064029998385408 +1662064030052386560 +1662064030097387520 +1662064030145388544 +1662064030196389632 +1662064030238390528 +1662064030286391552 +1662064030331392512 +1662064030385393664 +1662064030430394624 +1662064030469395456 +1662064030514396416 +1662064030574397696 +1662064030616398592 +1662064030658399488 +1662064030700400384 +1662064030748401408 +1662064030793402368 +1662064030841403392 +1662064030886404352 +1662064030928405248 +1662064030979406336 +1662064031024407296 +1662064031066408192 +1662064031114409216 +1662064031156410112 +1662064031204411136 +1662064031246412032 +1662064031291412992 +1662064031333413888 +1662064031378414848 +1662064031417415680 +1662064031459416576 +1662064031519417856 +1662064031564418816 +1662064031612419840 +1662064031654420736 +1662064031699421696 +1662064031747422720 +1662064031798423808 +1662064031846424832 +1662064031888425728 +1662064031930426624 +1662064031972427520 +1662064032014428416 +1662064032056429312 +1662064032098430208 +1662064032143431168 +1662064032188432128 +1662064032230433024 +1662064032272433920 +1662064032314434816 +1662064032356435712 +1662064032401436672 +1662064032443437568 +1662064032488438528 +1662064032530439424 +1662064032584440576 +1662064032623441408 +1662064032665442304 +1662064032716443392 +1662064032758444288 +1662064032800445184 +1662064032845446144 +1662064032899447296 +1662064032947448320 +1662064032989449216 +1662064033031450112 +1662064033070450944 +1662064033112451840 +1662064033154452736 +1662064033205453824 +1662064033247454720 +1662064033295455744 +1662064033337456640 +1662064033385457664 +1662064033427458560 +1662064033472459520 +1662064033514460416 +1662064033559461376 +1662064033607462400 +1662064033652463360 +1662064033694464256 +1662064033736465152 +1662064033781466112 +1662064033826467072 +1662064033868467968 +1662064033910468864 +1662064033955469824 +1662064033997470720 +1662064034042471680 +1662064034084472576 +1662064034129473536 +1662064034168474368 +1662064034210475264 +1662064034252476160 +1662064034294477056 +1662064034336477952 +1662064034378478848 +1662064034417479680 +1662064034459480576 +1662064034504481536 +1662064034549482496 +1662064034597483520 +1662064034636484352 +1662064034681485312 +1662064034723486208 +1662064034765487104 +1662064034810488064 +1662064034855489024 +1662064034897489920 +1662064034936490752 +1662064034984491776 +1662064035032492800 +1662064035074493696 +1662064035122494720 +1662064035164495616 +1662064035206496512 +1662064035248497408 +1662064035290498304 +1662064035332499200 +1662064035374500096 +1662064035419501056 +1662064035458501888 +1662064035500502784 +1662064035542503680 +1662064035584504576 +1662064035626505472 +1662064035671506432 +1662064035713507328 +1662064035758508288 +1662064035806509312 +1662064035854510336 +1662064035896511232 +1662064035947512320 +1662064035995513344 +1662064036037514240 +1662064036085515264 +1662064036130516224 +1662064036172517120 +1662064036214518016 +1662064036256518912 +1662064036310520064 +1662064036352520960 +1662064036400521984 +1662064036445522944 +1662064036487523840 +1662064036529524736 +1662064036571525632 +1662064036613526528 +1662064036658527488 +1662064036697528320 +1662064036739529216 +1662064036787530240 +1662064036835531264 +1662064036877532160 +1662064036922533120 +1662064036967534080 +1662064037015535104 +1662064037057536000 +1662064037099536896 +1662064037147537920 +1662064037189538816 +1662064037234539776 +1662064037282540800 +1662064037324541696 +1662064037369542656 +1662064037408543488 +1662064037450544384 +1662064037492545280 +1662064037534546176 +1662064037576547072 +1662064037621548032 +1662064037663548928 +1662064037705549824 +1662064037750550784 +1662064037795551744 +1662064037843552768 +1662064037885553664 +1662064037930554624 +1662064037972555520 +1662064038014556416 +1662064038056557312 +1662064038104558336 +1662064038149559296 +1662064038191560192 +1662064038239561216 +1662064038281562112 +1662064038323563008 +1662064038365563904 +1662064038413564928 +1662064038455565824 +1662064038497566720 +1662064038542567680 +1662064038590568704 +1662064038638569728 +1662064038680570624 +1662064038719571456 +1662064038761572352 +1662064038806573312 +1662064038851574272 +1662064038896575232 +1662064038938576128 +1662064038983577088 +1662064039028578048 +1662064039076579072 +1662064039118579968 +1662064039160580864 +1662064039205581824 +1662064039253582848 +1662064039295583744 +1662064039340584704 +1662064039382585600 +1662064039424586496 +1662064039469587456 +1662064039508588288 +1662064039550589184 +1662064039595590144 +1662064039637591040 +1662064039685592064 +1662064039727592960 +1662064039766593792 +1662064039811594752 +1662064039853595648 +1662064039898596608 +1662064039940597504 +1662064039982598400 +1662064040024599296 +1662064040072600320 +1662064040114601216 +1662064040162602240 +1662064040207603200 +1662064040252604160 +1662064040303605248 +1662064040348606208 +1662064040390607104 +1662064040435608064 +1662064040477608960 +1662064040519609856 +1662064040561610752 +1662064040603611648 +1662064040642612480 +1662064040699613696 +1662064040738614528 +1662064040777615360 +1662064040819616256 +1662064040864617216 +1662064040906618112 +1662064040945618944 +1662064040990619904 +1662064041032620800 +1662064041074621696 +1662064041122622720 +1662064041164623616 +1662064041209624576 +1662064041254625536 +1662064041296626432 +1662064041347627520 +1662064041395628544 +1662064041443629568 +1662064041488630528 +1662064041533631488 +1662064041584632576 +1662064041629633536 +1662064041671634432 +1662064041713635328 +1662064041755636224 +1662064041806637312 +1662064041845638144 +1662064041887639040 +1662064041932640000 +1662064041977640960 +1662064042025641984 +1662064042076643072 +1662064042121644032 +1662064042163644928 +1662064042205645824 +1662064042247646720 +1662064042292647680 +1662064042334648576 +1662064042379649536 +1662064042424650496 +1662064042466651392 +1662064042508652288 +1662064042553653248 +1662064042598654208 +1662064042646655232 +1662064042691656192 +1662064042733657088 +1662064042778658048 +1662064042829659136 +1662064042871660032 +1662064042916660992 +1662064042964662016 +1662064043015663104 +1662064043057664000 +1662064043108665088 +1662064043153666048 +1662064043198667008 +1662064043240667904 +1662064043288668928 +1662064043330669824 +1662064043378670848 +1662064043423671808 +1662064043471672832 +1662064043513673728 +1662064043558674688 +1662064043603675648 +1662064043657676800 +1662064043705677824 +1662064043750678784 +1662064043792679680 +1662064043843680768 +1662064043882681600 +1662064043927682560 +1662064043966683392 +1662064044011684352 +1662064044062685440 +1662064044107686400 +1662064044146687232 +1662064044197688320 +1662064044239689216 +1662064044290690304 +1662064044332691200 +1662064044383692288 +1662064044431693312 +1662064044473694208 +1662064044515695104 +1662064044563696128 +1662064044602696960 +1662064044647697920 +1662064044698699008 +1662064044743699968 +1662064044788700928 +1662064044830701824 +1662064044872702720 +1662064044923703808 +1662064044965704704 +1662064045016705792 +1662064045058706688 +1662064045100707584 +1662064045145708544 +1662064045187709440 +1662064045238710528 +1662064045280711424 +1662064045328712448 +1662064045370713344 +1662064045415714304 +1662064045454715136 +1662064045496716032 +1662064045544717056 +1662064045589718016 +1662064045634718976 +1662064045679719936 +1662064045721720832 +1662064045763721728 +1662064045805722624 +1662064045850723584 +1662064045895724544 +1662064045940725504 +1662064045982726400 +1662064046027727360 +1662064046075728384 +1662064046123729408 +1662064046165730304 +1662064046207731200 +1662064046258732288 +1662064046303733248 +1662064046351734272 +1662064046396735232 +1662064046441736192 +1662064046492737280 +1662064046534738176 +1662064046576739072 +1662064046621740032 +1662064046666740992 +1662064046711741952 +1662064046756742912 +1662064046804743936 +1662064046846744832 +1662064046885745664 +1662064046927746560 +1662064046969747456 +1662064047014748416 +1662064047056749312 +1662064047101750272 +1662064047149751296 +1662064047194752256 +1662064047239753216 +1662064047284754176 +1662064047326755072 +1662064047371756032 +1662064047419757056 +1662064047464758016 +1662064047509758976 +1662064047554759936 +1662064047605761024 +1662064047653762048 +1662064047707763200 +1662064047752764160 +1662064047794765056 +1662064047836765952 +1662064047878766848 +1662064047923767808 +1662064047965768704 +1662064048010769664 +1662064048052770560 +1662064048094771456 +1662064048142772480 +1662064048184773376 +1662064048226774272 +1662064048277775360 +1662064048319776256 +1662064048361777152 +1662064048406778112 +1662064048448779008 +1662064048493779968 +1662064048535780864 +1662064048577781760 +1662064048619782656 +1662064048664783616 +1662064048706784512 +1662064048754785536 +1662064048793786368 +1662064048832787200 +1662064048877788160 +1662064048922789120 +1662064048967790080 +1662064049009790976 +1662064049048791808 +1662064049096792832 +1662064049141793792 +1662064049186794752 +1662064049234795776 +1662064049276796672 +1662064049318797568 +1662064049366798592 +1662064049408799488 +1662064049450800384 +1662064049495801344 +1662064049537802240 +1662064049576803072 +1662064049618803968 +1662064049660804864 +1662064049702805760 +1662064049744806656 +1662064049789807616 +1662064049834808576 +1662064049876809472 +1662064049918810368 +1662064049960811264 +1662064050002812160 +1662064050053813248 +1662064050095814144 +1662064050137815040 +1662064050179815936 +1662064050221816832 +1662064050263817728 +1662064050305818624 +1662064050347819520 +1662064050389820416 +1662064050434821376 +1662064050482822400 +1662064050524823296 +1662064050584824576 +1662064050626825472 +1662064050668826368 +1662064050713827328 +1662064050755828224 +1662064050797829120 +1662064050845830144 +1662064050887831040 +1662064050932832000 +1662064050977832960 +1662064051016833792 +1662064051070834944 +1662064051115835904 +1662064051157836800 +1662064051199837696 +1662064051241838592 +1662064051283839488 +1662064051325840384 +1662064051367841280 +1662064051409842176 +1662064051454843136 +1662064051499844096 +1662064051544845056 +1662064051592846080 +1662064051631846912 +1662064051673847808 +1662064051715848704 +1662064051763849728 +1662064051808850688 +1662064051853851648 +1662064051901852672 +1662064051943853568 +1662064051985854464 +1662064052036855552 +1662064052081856512 +1662064052129857536 +1662064052171858432 +1662064052213859328 +1662064052261860352 +1662064052303861248 +1662064052345862144 +1662064052387863040 +1662064052438864128 +1662064052483865088 +1662064052525865984 +1662064052573867008 +1662064052624868096 +1662064052669869056 +1662064052714870016 +1662064052759870976 +1662064052795871744 +1662064052840872704 +1662064052885873664 +1662064052924874496 +1662064052969875456 +1662064053011876352 +1662064053056877312 +1662064053098878208 +1662064053143879168 +1662064053188880128 +1662064053233881088 +1662064053278882048 +1662064053323883008 +1662064053365883904 +1662064053407884800 +1662064053452885760 +1662064053491886592 +1662064053533887488 +1662064053575888384 +1662064053614889216 +1662064053659890176 +1662064053698891008 +1662064053746892032 +1662064053791892992 +1662064053842894080 +1662064053884894976 +1662064053929895936 +1662064053974896896 +1662064054019897856 +1662064054061898752 +1662064054103899648 +1662064054142900480 +1662064054184901376 +1662064054223902208 +1662064054265903104 +1662064054307904000 +1662064054355905024 +1662064054409906176 +1662064054457907200 +1662064054502908160 +1662064054541908992 +1662064054589910016 +1662064054631910912 +1662064054676911872 +1662064054727912960 +1662064054772913920 +1662064054814914816 +1662064054865915904 +1662064054910916864 +1662064054946917632 +1662064054997918720 +1662064055042919680 +1662064055090920704 +1662064055138921728 +1662064055180922624 +1662064055225923584 +1662064055270924544 +1662064055315925504 +1662064055360926464 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_light.txt b/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_light.txt new file mode 100644 index 0000000000..b9447370b4 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_light.txt @@ -0,0 +1,2605 @@ +1662121584099220736 +1662121584144221696 +1662121584186222592 +1662121584234223616 +1662121584279224576 +1662121584321225472 +1662121584369226496 +1662121584417227520 +1662121584459228416 +1662121584498229248 +1662121584540230144 +1662121584582231040 +1662121584624231936 +1662121584669232896 +1662121584717233920 +1662121584762234880 +1662121584807235840 +1662121584855236864 +1662121584900237824 +1662121584942238720 +1662121584987239680 +1662121585032240640 +1662121585074241536 +1662121585119242496 +1662121585161243392 +1662121585203244288 +1662121585251245312 +1662121585296246272 +1662121585338247168 +1662121585389248256 +1662121585434249216 +1662121585476250112 +1662121585524251136 +1662121585575252224 +1662121585617253120 +1662121585671254272 +1662121585716255232 +1662121585758256128 +1662121585803257088 +1662121585845257984 +1662121585887258880 +1662121585932259840 +1662121585977260800 +1662121586019261696 +1662121586061262592 +1662121586106263552 +1662121586151264512 +1662121586193265408 +1662121586235266304 +1662121586277267200 +1662121586319268096 +1662121586364269056 +1662121586409270016 +1662121586460271104 +1662121586502272000 +1662121586553273088 +1662121586595273984 +1662121586634274816 +1662121586679275776 +1662121586724276736 +1662121586766277632 +1662121586823278848 +1662121586868279808 +1662121586916280832 +1662121586961281792 +1662121587003282688 +1662121587048283648 +1662121587093284608 +1662121587135285504 +1662121587177286400 +1662121587216287232 +1662121587258288128 +1662121587303289088 +1662121587345289984 +1662121587387290880 +1662121587429291776 +1662121587474292736 +1662121587522293760 +1662121587567294720 +1662121587615295744 +1662121587657296640 +1662121587702297600 +1662121587747298560 +1662121587789299456 +1662121587834300416 +1662121587876301312 +1662121587921302272 +1662121587966303232 +1662121588008304128 +1662121588053305088 +1662121588101306112 +1662121588143307008 +1662121588197308160 +1662121588245309184 +1662121588290310144 +1662121588332311040 +1662121588383312128 +1662121588428313088 +1662121588470313984 +1662121588512314880 +1662121588557315840 +1662121588602316800 +1662121588644317696 +1662121588686318592 +1662121588737319680 +1662121588779320576 +1662121588821321472 +1662121588872322560 +1662121588914323456 +1662121588962324480 +1662121589004325376 +1662121589043326208 +1662121589088327168 +1662121589130328064 +1662121589172328960 +1662121589214329856 +1662121589265330944 +1662121589307331840 +1662121589349332736 +1662121589397333760 +1662121589439334656 +1662121589478335488 +1662121589520336384 +1662121589565337344 +1662121589604338176 +1662121589646339072 +1662121589691340032 +1662121589739341056 +1662121589784342016 +1662121589826342912 +1662121589871343872 +1662121589919344896 +1662121589961345792 +1662121590003346688 +1662121590051347712 +1662121590093348608 +1662121590135349504 +1662121590183350528 +1662121590228351488 +1662121590279352576 +1662121590321353472 +1662121590360354304 +1662121590405355264 +1662121590447356160 +1662121590492357120 +1662121590540358144 +1662121590579358976 +1662121590621359872 +1662121590663360768 +1662121590705361664 +1662121590747362560 +1662121590792363520 +1662121590837364480 +1662121590885365504 +1662121590927366400 +1662121590969367296 +1662121591014368256 +1662121591062369280 +1662121591107370240 +1662121591155371264 +1662121591194372096 +1662121591236372992 +1662121591284374016 +1662121591329374976 +1662121591374375936 +1662121591428377088 +1662121591473378048 +1662121591518379008 +1662121591560379904 +1662121591611380992 +1662121591650381824 +1662121591701382912 +1662121591743383808 +1662121591785384704 +1662121591830385664 +1662121591875386624 +1662121591917387520 +1662121591962388480 +1662121592007389440 +1662121592049390336 +1662121592091391232 +1662121592133392128 +1662121592175393024 +1662121592226394112 +1662121592268395008 +1662121592313395968 +1662121592352396800 +1662121592391397632 +1662121592439398656 +1662121592496399872 +1662121592538400768 +1662121592583401728 +1662121592625402624 +1662121592670403584 +1662121592712404480 +1662121592751405312 +1662121592799406336 +1662121592844407296 +1662121592883408128 +1662121592925409024 +1662121592970409984 +1662121593024411136 +1662121593069412096 +1662121593114413056 +1662121593156413952 +1662121593201414912 +1662121593246415872 +1662121593294416896 +1662121593342417920 +1662121593390418944 +1662121593444420096 +1662121593486420992 +1662121593531421952 +1662121593576422912 +1662121593627424000 +1662121593672424960 +1662121593726426112 +1662121593777427200 +1662121593816428032 +1662121593855428864 +1662121593900429824 +1662121593948430848 +1662121594005432064 +1662121594050433024 +1662121594092433920 +1662121594143435008 +1662121594185435904 +1662121594230436864 +1662121594278437888 +1662121594323438848 +1662121594371439872 +1662121594416440832 +1662121594461441792 +1662121594503442688 +1662121594551443712 +1662121594599444736 +1662121594641445632 +1662121594683446528 +1662121594725447424 +1662121594770448384 +1662121594812449280 +1662121594857450240 +1662121594899451136 +1662121594941452032 +1662121594983452928 +1662121595034454016 +1662121595076454912 +1662121595124455936 +1662121595184457216 +1662121595226458112 +1662121595274459136 +1662121595316460032 +1662121595361460992 +1662121595406461952 +1662121595454462976 +1662121595496463872 +1662121595541464832 +1662121595583465728 +1662121595631466752 +1662121595676467712 +1662121595724468736 +1662121595772469760 +1662121595826470912 +1662121595868471808 +1662121595919472896 +1662121595964473856 +1662121596006474752 +1662121596051475712 +1662121596099476736 +1662121596144477696 +1662121596186478592 +1662121596234479616 +1662121596276480512 +1662121596318481408 +1662121596357482240 +1662121596399483136 +1662121596447484160 +1662121596489485056 +1662121596534486016 +1662121596576486912 +1662121596630488064 +1662121596675489024 +1662121596720489984 +1662121596768491008 +1662121596819492096 +1662121596861492992 +1662121596912494080 +1662121596951494912 +1662121596993495808 +1662121597038496768 +1662121597083497728 +1662121597125498624 +1662121597173499648 +1662121597215500544 +1662121597260501504 +1662121597305502464 +1662121597344503296 +1662121597389504256 +1662121597443505408 +1662121597485506304 +1662121597524507136 +1662121597572508160 +1662121597617509120 +1662121597662510080 +1662121597710511104 +1662121597761512192 +1662121597812513280 +1662121597863514368 +1662121597908515328 +1662121597950516224 +1662121598001517312 +1662121598043518208 +1662121598097519360 +1662121598148520448 +1662121598190521344 +1662121598238522368 +1662121598283523328 +1662121598334524416 +1662121598379525376 +1662121598427526400 +1662121598472527360 +1662121598520528384 +1662121598565529344 +1662121598607530240 +1662121598652531200 +1662121598694532096 +1662121598742533120 +1662121598781533952 +1662121598823534848 +1662121598868535808 +1662121598913536768 +1662121598955537664 +1662121598997538560 +1662121599042539520 +1662121599090540544 +1662121599135541504 +1662121599183542528 +1662121599231543552 +1662121599279544576 +1662121599324545536 +1662121599369546496 +1662121599411547392 +1662121599456548352 +1662121599498549248 +1662121599543550208 +1662121599585551104 +1662121599633552128 +1662121599678553088 +1662121599717553920 +1662121599762554880 +1662121599807555840 +1662121599852556800 +1662121599894557696 +1662121599936558592 +1662121599984559616 +1662121600026560512 +1662121600071561472 +1662121600122562560 +1662121600179563776 +1662121600221564672 +1662121600263565568 +1662121600302566400 +1662121600350567424 +1662121600395568384 +1662121600437569280 +1662121600482570240 +1662121600536571392 +1662121600581572352 +1662121600623573248 +1662121600665574144 +1662121600710575104 +1662121600752576000 +1662121600806577152 +1662121600848578048 +1662121600890578944 +1662121600932579840 +1662121600974580736 +1662121601025581824 +1662121601070582784 +1662121601115583744 +1662121601157584640 +1662121601205585664 +1662121601247586560 +1662121601289587456 +1662121601337588480 +1662121601382589440 +1662121601433590528 +1662121601475591424 +1662121601517592320 +1662121601559593216 +1662121601604594176 +1662121601652595200 +1662121601697596160 +1662121601742597120 +1662121601784598016 +1662121601835599104 +1662121601880600064 +1662121601928601088 +1662121601970601984 +1662121602027603200 +1662121602075604224 +1662121602117605120 +1662121602162606080 +1662121602204606976 +1662121602255608064 +1662121602297608960 +1662121602336609792 +1662121602378610688 +1662121602426611712 +1662121602468612608 +1662121602519613696 +1662121602555614464 +1662121602600615424 +1662121602645616384 +1662121602699617536 +1662121602741618432 +1662121602783619328 +1662121602825620224 +1662121602867621120 +1662121602909622016 +1662121602951622912 +1662121602999623936 +1662121603047624960 +1662121603089625856 +1662121603140626944 +1662121603185627904 +1662121603227628800 +1662121603281629952 +1662121603326630912 +1662121603368631808 +1662121603422632960 +1662121603467633920 +1662121603509634816 +1662121603563635968 +1662121603608636928 +1662121603650637824 +1662121603692638720 +1662121603734639616 +1662121603776640512 +1662121603818641408 +1662121603860642304 +1662121603905643264 +1662121603953644288 +1662121604001645312 +1662121604043646208 +1662121604088647168 +1662121604133648128 +1662121604175649024 +1662121604217649920 +1662121604262650880 +1662121604307651840 +1662121604355652864 +1662121604394653696 +1662121604442654720 +1662121604484655616 +1662121604523656448 +1662121604574657536 +1662121604619658496 +1662121604664659456 +1662121604709660416 +1662121604754661376 +1662121604805662464 +1662121604850663424 +1662121604895664384 +1662121604940665344 +1662121604988666368 +1662121605042667520 +1662121605084668416 +1662121605129669376 +1662121605174670336 +1662121605216671232 +1662121605255672064 +1662121605300673024 +1662121605342673920 +1662121605396675072 +1662121605438675968 +1662121605480676864 +1662121605528677888 +1662121605573678848 +1662121605618679808 +1662121605663680768 +1662121605705681664 +1662121605747682560 +1662121605798683648 +1662121605840684544 +1662121605882685440 +1662121605930686464 +1662121605975687424 +1662121606017688320 +1662121606059689216 +1662121606104690176 +1662121606146691072 +1662121606188691968 +1662121606230692864 +1662121606275693824 +1662121606323694848 +1662121606368695808 +1662121606413696768 +1662121606455697664 +1662121606497698560 +1662121606542699520 +1662121606587700480 +1662121606626701312 +1662121606665702144 +1662121606710703104 +1662121606758704128 +1662121606803705088 +1662121606857706240 +1662121606902707200 +1662121606944708096 +1662121606986708992 +1662121607031709952 +1662121607076710912 +1662121607124711936 +1662121607169712896 +1662121607217713920 +1662121607262714880 +1662121607304715776 +1662121607346716672 +1662121607391717632 +1662121607436718592 +1662121607487719680 +1662121607532720640 +1662121607577721600 +1662121607628722688 +1662121607670723584 +1662121607715724544 +1662121607763725568 +1662121607805726464 +1662121607847727360 +1662121607889728256 +1662121607928729088 +1662121607970729984 +1662121608018731008 +1662121608060731904 +1662121608102732800 +1662121608147733760 +1662121608198734848 +1662121608246735872 +1662121608288736768 +1662121608333737728 +1662121608375738624 +1662121608426739712 +1662121608468740608 +1662121608510741504 +1662121608552742400 +1662121608597743360 +1662121608639744256 +1662121608681745152 +1662121608729746176 +1662121608777747200 +1662121608822748160 +1662121608867749120 +1662121608909750016 +1662121608951750912 +1662121609002752000 +1662121609044752896 +1662121609086753792 +1662121609134754816 +1662121609182755840 +1662121609230756864 +1662121609272757760 +1662121609317758720 +1662121609359759616 +1662121609398760448 +1662121609443761408 +1662121609491762432 +1662121609533763328 +1662121609575764224 +1662121609617765120 +1662121609662766080 +1662121609710767104 +1662121609755768064 +1662121609797768960 +1662121609839769856 +1662121609884770816 +1662121609935771904 +1662121609977772800 +1662121610022773760 +1662121610064774656 +1662121610106775552 +1662121610151776512 +1662121610196777472 +1662121610238778368 +1662121610292779520 +1662121610331780352 +1662121610382781440 +1662121610427782400 +1662121610469783296 +1662121610511784192 +1662121610559785216 +1662121610604786176 +1662121610646787072 +1662121610691788032 +1662121610733788928 +1662121610787790080 +1662121610832791040 +1662121610874791936 +1662121610922792960 +1662121610964793856 +1662121611006794752 +1662121611048795648 +1662121611096796672 +1662121611147797760 +1662121611198798848 +1662121611252800000 +1662121611294800896 +1662121611336801792 +1662121611381802752 +1662121611432803840 +1662121611474804736 +1662121611519805696 +1662121611561806592 +1662121611603807488 +1662121611651808512 +1662121611702809600 +1662121611747810560 +1662121611789811456 +1662121611834812416 +1662121611879813376 +1662121611927814400 +1662121611972815360 +1662121612017816320 +1662121612062817280 +1662121612107818240 +1662121612152819200 +1662121612194820096 +1662121612236820992 +1662121612278821888 +1662121612323822848 +1662121612368823808 +1662121612410824704 +1662121612449825536 +1662121612491826432 +1662121612548827648 +1662121612593828608 +1662121612635829504 +1662121612683830528 +1662121612731831552 +1662121612770832384 +1662121612818833408 +1662121612860834304 +1662121612902835200 +1662121612947836160 +1662121612989837056 +1662121613037838080 +1662121613082839040 +1662121613124839936 +1662121613166840832 +1662121613211841792 +1662121613259842816 +1662121613307843840 +1662121613349844736 +1662121613397845760 +1662121613442846720 +1662121613484847616 +1662121613526848512 +1662121613577849600 +1662121613625850624 +1662121613670851584 +1662121613724852736 +1662121613769853696 +1662121613817854720 +1662121613859855616 +1662121613907856640 +1662121613958857728 +1662121614009858816 +1662121614054859776 +1662121614096860672 +1662121614138861568 +1662121614177862400 +1662121614219863296 +1662121614267864320 +1662121614318865408 +1662121614360866304 +1662121614405867264 +1662121614450868224 +1662121614492869120 +1662121614540870144 +1662121614582871040 +1662121614630872064 +1662121614672872960 +1662121614720873984 +1662121614768875008 +1662121614816876032 +1662121614855876864 +1662121614897877760 +1662121614939878656 +1662121614987879680 +1662121615032880640 +1662121615077881600 +1662121615119882496 +1662121615164883456 +1662121615209884416 +1662121615254885376 +1662121615302886400 +1662121615350887424 +1662121615395888384 +1662121615443889408 +1662121615488890368 +1662121615530891264 +1662121615584892416 +1662121615626893312 +1662121615668894208 +1662121615707895040 +1662121615752896000 +1662121615800897024 +1662121615845897984 +1662121615896899072 +1662121615947900160 +1662121615992901120 +1662121616034902016 +1662121616079902976 +1662121616127904000 +1662121616178905088 +1662121616223906048 +1662121616268907008 +1662121616316908032 +1662121616358908928 +1662121616412910080 +1662121616463911168 +1662121616505912064 +1662121616547912960 +1662121616589913856 +1662121616634914816 +1662121616679915776 +1662121616727916800 +1662121616769917696 +1662121616823918848 +1662121616865919744 +1662121616913920768 +1662121616955921664 +1662121616997922560 +1662121617045923584 +1662121617087924480 +1662121617132925440 +1662121617177926400 +1662121617222927360 +1662121617264928256 +1662121617312929280 +1662121617360930304 +1662121617402931200 +1662121617444932096 +1662121617501933312 +1662121617543934208 +1662121617591935232 +1662121617639936256 +1662121617690937344 +1662121617741938432 +1662121617789939456 +1662121617831940352 +1662121617873941248 +1662121617918942208 +1662121617966943232 +1662121618014944256 +1662121618062945280 +1662121618104946176 +1662121618149947136 +1662121618200948224 +1662121618245949184 +1662121618287950080 +1662121618326950912 +1662121618368951808 +1662121618410952704 +1662121618452953600 +1662121618500954624 +1662121618545955584 +1662121618599956736 +1662121618641957632 +1662121618686958592 +1662121618728959488 +1662121618770960384 +1662121618815961344 +1662121618863962368 +1662121618905963264 +1662121618947964160 +1662121618992965120 +1662121619034966016 +1662121619079966976 +1662121619124967936 +1662121619166968832 +1662121619211969792 +1662121619253970688 +1662121619304971776 +1662121619346972672 +1662121619400973824 +1662121619442974720 +1662121619490975744 +1662121619535976704 +1662121619577977600 +1662121619619978496 +1662121619667979520 +1662121619706980352 +1662121619751981312 +1662121619802982400 +1662121619847983360 +1662121619892984320 +1662121619937985280 +1662121619979986176 +1662121620027987200 +1662121620075988224 +1662121620117989120 +1662121620162990080 +1662121620207991040 +1662121620252992000 +1662121620306993152 +1662121620351994112 +1662121620396995072 +1662121620438995968 +1662121620480996864 +1662121620525997824 +1662121620570998784 +1662121620615999744 +1662121620658000640 +1662121620703001600 +1662121620757002752 +1662121620799003648 +1662121620847004672 +1662121620892005632 +1662121620934006528 +1662121620976007424 +1662121621018008320 +1662121621060009216 +1662121621111010304 +1662121621159011328 +1662121621204012288 +1662121621246013184 +1662121621291014144 +1662121621330014976 +1662121621372015872 +1662121621414016768 +1662121621462017792 +1662121621507018752 +1662121621555019776 +1662121621594020608 +1662121621645021696 +1662121621687022592 +1662121621729023488 +1662121621774024448 +1662121621816025344 +1662121621861026304 +1662121621912027392 +1662121621957028352 +1662121622005029376 +1662121622050030336 +1662121622095031296 +1662121622137032192 +1662121622182033152 +1662121622227034112 +1662121622272035072 +1662121622323036160 +1662121622374037248 +1662121622413038080 +1662121622458039040 +1662121622503040000 +1662121622548040960 +1662121622593041920 +1662121622638042880 +1662121622686043904 +1662121622731044864 +1662121622773045760 +1662121622818046720 +1662121622863047680 +1662121622908048640 +1662121622953049600 +1662121623001050624 +1662121623049051648 +1662121623097052672 +1662121623148053760 +1662121623193054720 +1662121623238055680 +1662121623295056896 +1662121623340057856 +1662121623385058816 +1662121623427059712 +1662121623472060672 +1662121623514061568 +1662121623559062528 +1662121623604063488 +1662121623658064640 +1662121623700065536 +1662121623742066432 +1662121623784067328 +1662121623829068288 +1662121623877069312 +1662121623919070208 +1662121623961071104 +1662121624006072064 +1662121624051073024 +1662121624093073920 +1662121624135074816 +1662121624180075776 +1662121624225076736 +1662121624279077888 +1662121624324078848 +1662121624369079808 +1662121624411080704 +1662121624456081664 +1662121624498082560 +1662121624543083520 +1662121624594084608 +1662121624642085632 +1662121624687086592 +1662121624735087616 +1662121624780088576 +1662121624828089600 +1662121624879090688 +1662121624924091648 +1662121624966092544 +1662121625020093696 +1662121625065094656 +1662121625107095552 +1662121625152096512 +1662121625197097472 +1662121625239098368 +1662121625284099328 +1662121625335100416 +1662121625380101376 +1662121625425102336 +1662121625467103232 +1662121625512104192 +1662121625560105216 +1662121625608106240 +1662121625653107200 +1662121625698108160 +1662121625752109312 +1662121625797110272 +1662121625839111168 +1662121625887112192 +1662121625929113088 +1662121625977114112 +1662121626016114944 +1662121626058115840 +1662121626100116736 +1662121626148117760 +1662121626193118720 +1662121626241119744 +1662121626283120640 +1662121626325121536 +1662121626370122496 +1662121626412123392 +1662121626457124352 +1662121626502125312 +1662121626544126208 +1662121626589127168 +1662121626631128064 +1662121626673128960 +1662121626715129856 +1662121626760130816 +1662121626808131840 +1662121626859132928 +1662121626904133888 +1662121626952134912 +1662121626997135872 +1662121627042136832 +1662121627090137856 +1662121627135138816 +1662121627177139712 +1662121627228140800 +1662121627276141824 +1662121627318142720 +1662121627360143616 +1662121627405144576 +1662121627447145472 +1662121627498146560 +1662121627549147648 +1662121627597148672 +1662121627639149568 +1662121627690150656 +1662121627732151552 +1662121627774152448 +1662121627816153344 +1662121627858154240 +1662121627900155136 +1662121627942156032 +1662121627984156928 +1662121628029157888 +1662121628071158784 +1662121628119159808 +1662121628173160960 +1662121628212161792 +1662121628254162688 +1662121628299163648 +1662121628350164736 +1662121628398165760 +1662121628440166656 +1662121628488167680 +1662121628533168640 +1662121628581169664 +1662121628623170560 +1662121628671171584 +1662121628722172672 +1662121628770173696 +1662121628818174720 +1662121628860175616 +1662121628908176640 +1662121628953177600 +1662121629001178624 +1662121629049179648 +1662121629094180608 +1662121629145181696 +1662121629196182784 +1662121629244183808 +1662121629289184768 +1662121629331185664 +1662121629376186624 +1662121629424187648 +1662121629472188672 +1662121629517189632 +1662121629571190784 +1662121629616191744 +1662121629661192704 +1662121629703193600 +1662121629739194368 +1662121629787195392 +1662121629838196480 +1662121629883197440 +1662121629931198464 +1662121629973199360 +1662121630015200256 +1662121630057201152 +1662121630102202112 +1662121630153203200 +1662121630195204096 +1662121630237204992 +1662121630282205952 +1662121630324206848 +1662121630369207808 +1662121630423208960 +1662121630474210048 +1662121630525211136 +1662121630582212352 +1662121630621213184 +1662121630660214016 +1662121630702214912 +1662121630750215936 +1662121630792216832 +1662121630843217920 +1662121630885218816 +1662121630933219840 +1662121630975220736 +1662121631026221824 +1662121631068222720 +1662121631119223808 +1662121631167224832 +1662121631212225792 +1662121631254226688 +1662121631305227776 +1662121631347228672 +1662121631389229568 +1662121631431230464 +1662121631482231552 +1662121631530232576 +1662121631575233536 +1662121631620234496 +1662121631662235392 +1662121631707236352 +1662121631752237312 +1662121631800238336 +1662121631854239488 +1662121631896240384 +1662121631938241280 +1662121631983242240 +1662121632022243072 +1662121632064243968 +1662121632109244928 +1662121632154245888 +1662121632196246784 +1662121632244247808 +1662121632289248768 +1662121632334249728 +1662121632382250752 +1662121632424251648 +1662121632466252544 +1662121632508253440 +1662121632553254400 +1662121632598255360 +1662121632649256448 +1662121632697257472 +1662121632751258624 +1662121632793259520 +1662121632838260480 +1662121632883261440 +1662121632925262336 +1662121632976263424 +1662121633018264320 +1662121633066265344 +1662121633111266304 +1662121633159267328 +1662121633204268288 +1662121633246269184 +1662121633291270144 +1662121633339271168 +1662121633390272256 +1662121633435273216 +1662121633477274112 +1662121633519275008 +1662121633564275968 +1662121633609276928 +1662121633651277824 +1662121633696278784 +1662121633738279680 +1662121633786280704 +1662121633828281600 +1662121633876282624 +1662121633921283584 +1662121633963284480 +1662121634008285440 +1662121634050286336 +1662121634098287360 +1662121634143288320 +1662121634185289216 +1662121634233290240 +1662121634281291264 +1662121634320292096 +1662121634368293120 +1662121634422294272 +1662121634467295232 +1662121634515296256 +1662121634554297088 +1662121634602298112 +1662121634644299008 +1662121634692300032 +1662121634746301184 +1662121634797302272 +1662121634842303232 +1662121634884304128 +1662121634929305088 +1662121634980306176 +1662121635022307072 +1662121635073308160 +1662121635124309248 +1662121635169310208 +1662121635211311104 +1662121635262312192 +1662121635307313152 +1662121635349314048 +1662121635391314944 +1662121635436315904 +1662121635484316928 +1662121635526317824 +1662121635574318848 +1662121635622319872 +1662121635670320896 +1662121635724322048 +1662121635769323008 +1662121635811323904 +1662121635853324800 +1662121635901325824 +1662121635946326784 +1662121635991327744 +1662121636033328640 +1662121636078329600 +1662121636123330560 +1662121636174331648 +1662121636219332608 +1662121636267333632 +1662121636309334528 +1662121636351335424 +1662121636396336384 +1662121636438337280 +1662121636480338176 +1662121636525339136 +1662121636567340032 +1662121636609340928 +1662121636657341952 +1662121636702342912 +1662121636744343808 +1662121636789344768 +1662121636840345856 +1662121636894347008 +1662121636942348032 +1662121636987348992 +1662121637029349888 +1662121637074350848 +1662121637125351936 +1662121637170352896 +1662121637212353792 +1662121637254354688 +1662121637302355712 +1662121637350356736 +1662121637398357760 +1662121637443358720 +1662121637485359616 +1662121637533360640 +1662121637587361792 +1662121637632362752 +1662121637677363712 +1662121637719364608 +1662121637761365504 +1662121637803366400 +1662121637848367360 +1662121637887368192 +1662121637929369088 +1662121637974370048 +1662121638019371008 +1662121638061371904 +1662121638103372800 +1662121638145373696 +1662121638190374656 +1662121638232375552 +1662121638277376512 +1662121638319377408 +1662121638361378304 +1662121638406379264 +1662121638448380160 +1662121638490381056 +1662121638532381952 +1662121638574382848 +1662121638616383744 +1662121638655384576 +1662121638703385600 +1662121638748386560 +1662121638799387648 +1662121638841388544 +1662121638895389696 +1662121638937390592 +1662121638979391488 +1662121639024392448 +1662121639063393280 +1662121639105394176 +1662121639159395328 +1662121639204396288 +1662121639249397248 +1662121639300398336 +1662121639342399232 +1662121639387400192 +1662121639432401152 +1662121639477402112 +1662121639519403008 +1662121639564403968 +1662121639609404928 +1662121639651405824 +1662121639699406848 +1662121639750407936 +1662121639792408832 +1662121639834409728 +1662121639876410624 +1662121639924411648 +1662121639969412608 +1662121640011413504 +1662121640062414592 +1662121640113415680 +1662121640155416576 +1662121640197417472 +1662121640239418368 +1662121640284419328 +1662121640326420224 +1662121640371421184 +1662121640419422208 +1662121640464423168 +1662121640506424064 +1662121640554425088 +1662121640590425856 +1662121640644427008 +1662121640692428032 +1662121640737428992 +1662121640785430016 +1662121640824430848 +1662121640866431744 +1662121640911432704 +1662121640959433728 +1662121641004434688 +1662121641049435648 +1662121641091436544 +1662121641142437632 +1662121641193438720 +1662121641238439680 +1662121641283440640 +1662121641337441792 +1662121641379442688 +1662121641421443584 +1662121641463444480 +1662121641505445376 +1662121641550446336 +1662121641601447424 +1662121641643448320 +1662121641694449408 +1662121641739450368 +1662121641778451200 +1662121641823452160 +1662121641868453120 +1662121641907453952 +1662121641952454912 +1662121641997455872 +1662121642042456832 +1662121642090457856 +1662121642132458752 +1662121642174459648 +1662121642219460608 +1662121642264461568 +1662121642312462592 +1662121642354463488 +1662121642399464448 +1662121642441465344 +1662121642483466240 +1662121642528467200 +1662121642570468096 +1662121642612468992 +1662121642660470016 +1662121642705470976 +1662121642747471872 +1662121642801473024 +1662121642843473920 +1662121642891474944 +1662121642939475968 +1662121642981476864 +1662121643023477760 +1662121643065478656 +1662121643107479552 +1662121643149480448 +1662121643191481344 +1662121643233482240 +1662121643275483136 +1662121643317484032 +1662121643362484992 +1662121643410486016 +1662121643455486976 +1662121643503488000 +1662121643542488832 +1662121643587489792 +1662121643629490688 +1662121643674491648 +1662121643719492608 +1662121643764493568 +1662121643806494464 +1662121643845495296 +1662121643887496192 +1662121643932497152 +1662121643983498240 +1662121644034499328 +1662121644079500288 +1662121644121501184 +1662121644160502016 +1662121644208503040 +1662121644250503936 +1662121644295504896 +1662121644337505792 +1662121644385506816 +1662121644433507840 +1662121644478508800 +1662121644526509824 +1662121644568510720 +1662121644613511680 +1662121644658512640 +1662121644706513664 +1662121644748514560 +1662121644799515648 +1662121644853516800 +1662121644898517760 +1662121644940518656 +1662121644988519680 +1662121645033520640 +1662121645078521600 +1662121645120522496 +1662121645162523392 +1662121645210524416 +1662121645252525312 +1662121645300526336 +1662121645342527232 +1662121645384528128 +1662121645426529024 +1662121645468529920 +1662121645510530816 +1662121645561531904 +1662121645603532800 +1662121645645533696 +1662121645690534656 +1662121645735535616 +1662121645780536576 +1662121645825537536 +1662121645870538496 +1662121645912539392 +1662121645957540352 +1662121646005541376 +1662121646053542400 +1662121646107543552 +1662121646149544448 +1662121646197545472 +1662121646239546368 +1662121646281547264 +1662121646329548288 +1662121646371549184 +1662121646419550208 +1662121646470551296 +1662121646521552384 +1662121646566553344 +1662121646611554304 +1662121646653555200 +1662121646698556160 +1662121646737556992 +1662121646779557888 +1662121646824558848 +1662121646869559808 +1662121646911560704 +1662121646956561664 +1662121646998562560 +1662121647040563456 +1662121647085564416 +1662121647127565312 +1662121647172566272 +1662121647214567168 +1662121647262568192 +1662121647304569088 +1662121647352570112 +1662121647400571136 +1662121647451572224 +1662121647496573184 +1662121647547574272 +1662121647589575168 +1662121647634576128 +1662121647676577024 +1662121647727578112 +1662121647784579328 +1662121647832580352 +1662121647874581248 +1662121647931582464 +1662121647973583360 +1662121648015584256 +1662121648069585408 +1662121648114586368 +1662121648156587264 +1662121648198588160 +1662121648240589056 +1662121648288590080 +1662121648336591104 +1662121648393592320 +1662121648435593216 +1662121648477594112 +1662121648519595008 +1662121648573596160 +1662121648627597312 +1662121648678598400 +1662121648723599360 +1662121648768600320 +1662121648813601280 +1662121648852602112 +1662121648894603008 +1662121648939603968 +1662121648981604864 +1662121649023605760 +1662121649080606976 +1662121649125607936 +1662121649167608832 +1662121649209609728 +1662121649251610624 +1662121649302611712 +1662121649341612544 +1662121649392613632 +1662121649437614592 +1662121649479615488 +1662121649521616384 +1662121649569617408 +1662121649614618368 +1662121649653619200 +1662121649692620032 +1662121649740621056 +1662121649785622016 +1662121649830622976 +1662121649875623936 +1662121649920624896 +1662121649971625984 +1662121650013626880 +1662121650058627840 +1662121650106628864 +1662121650148629760 +1662121650193630720 +1662121650241631744 +1662121650286632704 +1662121650331633664 +1662121650376634624 +1662121650424635648 +1662121650466636544 +1662121650517637632 +1662121650559638528 +1662121650601639424 +1662121650646640384 +1662121650688641280 +1662121650730642176 +1662121650772643072 +1662121650823644160 +1662121650868645120 +1662121650910646016 +1662121650952646912 +1662121651000647936 +1662121651042648832 +1662121651087649792 +1662121651129650688 +1662121651171651584 +1662121651213652480 +1662121651255653376 +1662121651300654336 +1662121651345655296 +1662121651384656128 +1662121651429657088 +1662121651477658112 +1662121651525659136 +1662121651573660160 +1662121651618661120 +1662121651669662208 +1662121651714663168 +1662121651765664256 +1662121651816665344 +1662121651864666368 +1662121651909667328 +1662121651951668224 +1662121652002669312 +1662121652050670336 +1662121652101671424 +1662121652143672320 +1662121652188673280 +1662121652236674304 +1662121652284675328 +1662121652335676416 +1662121652377677312 +1662121652425678336 +1662121652479679488 +1662121652521680384 +1662121652560681216 +1662121652608682240 +1662121652665683456 +1662121652707684352 +1662121652749685248 +1662121652791686144 +1662121652839687168 +1662121652881688064 +1662121652923688960 +1662121652971689984 +1662121653013690880 +1662121653055691776 +1662121653100692736 +1662121653142693632 +1662121653184694528 +1662121653229695488 +1662121653271696384 +1662121653319697408 +1662121653358698240 +1662121653403699200 +1662121653445700096 +1662121653487700992 +1662121653532701952 +1662121653577702912 +1662121653625703936 +1662121653670704896 +1662121653712705792 +1662121653754706688 +1662121653799707648 +1662121653841708544 +1662121653883709440 +1662121653934710528 +1662121653979711488 +1662121654024712448 +1662121654066713344 +1662121654108714240 +1662121654162715392 +1662121654210716416 +1662121654252717312 +1662121654300718336 +1662121654342719232 +1662121654387720192 +1662121654432721152 +1662121654471721984 +1662121654519723008 +1662121654564723968 +1662121654606724864 +1662121654657725952 +1662121654696726784 +1662121654738727680 +1662121654789728768 +1662121654831729664 +1662121654876730624 +1662121654918731520 +1662121654963732480 +1662121655002733312 +1662121655044734208 +1662121655086735104 +1662121655131736064 +1662121655176737024 +1662121655221737984 +1662121655278739200 +1662121655323740160 +1662121655365741056 +1662121655410742016 +1662121655455742976 +1662121655500743936 +1662121655539744768 +1662121655596745984 +1662121655638746880 +1662121655680747776 +1662121655722748672 +1662121655764749568 +1662121655806750464 +1662121655848751360 +1662121655893752320 +1662121655935753216 +1662121655977754112 +1662121656028755200 +1662121656073756160 +1662121656124757248 +1662121656172758272 +1662121656214759168 +1662121656262760192 +1662121656307761152 +1662121656355762176 +1662121656403763200 +1662121656445764096 +1662121656493765120 +1662121656544766208 +1662121656589767168 +1662121656631768064 +1662121656670768896 +1662121656715769856 +1662121656757770752 +1662121656805771776 +1662121656859772928 +1662121656901773824 +1662121656949774848 +1662121656991775744 +1662121657033776640 +1662121657075777536 +1662121657123778560 +1662121657168779520 +1662121657210780416 +1662121657258781440 +1662121657312782592 +1662121657360783616 +1662121657405784576 +1662121657453785600 +1662121657501786624 +1662121657546787584 +1662121657591788544 +1662121657636789504 +1662121657681790464 +1662121657723791360 +1662121657768792320 +1662121657813793280 +1662121657852794112 +1662121657897795072 +1662121657939795968 +1662121657984796928 +1662121658026797824 +1662121658068798720 +1662121658113799680 +1662121658158800640 +1662121658200801536 +1662121658254802688 +1662121658302803712 +1662121658350804736 +1662121658404805888 +1662121658446806784 +1662121658491807744 +1662121658536808704 +1662121658575809536 +1662121658626810624 +1662121658668811520 +1662121658716812544 +1662121658758813440 +1662121658809814528 +1662121658851815424 +1662121658905816576 +1662121658947817472 +1662121658989818368 +1662121659031819264 +1662121659076820224 +1662121659121821184 +1662121659166822144 +1662121659208823040 +1662121659253824000 +1662121659307825152 +1662121659361826304 +1662121659406827264 +1662121659454828288 +1662121659502829312 +1662121659547830272 +1662121659589831168 +1662121659640832256 +1662121659685833216 +1662121659739834368 +1662121659787835392 +1662121659835836416 +1662121659880837376 +1662121659925838336 +1662121659970839296 +1662121660012840192 +1662121660063841280 +1662121660108842240 +1662121660150843136 +1662121660195844096 +1662121660240845056 +1662121660288846080 +1662121660339847168 +1662121660387848192 +1662121660429849088 +1662121660474850048 +1662121660528851200 +1662121660570852096 +1662121660615853056 +1662121660657853952 +1662121660702854912 +1662121660747855872 +1662121660798856960 +1662121660840857856 +1662121660882858752 +1662121660924859648 +1662121660972860672 +1662121661020861696 +1662121661062862592 +1662121661104863488 +1662121661152864512 +1662121661197865472 +1662121661239866368 +1662121661284867328 +1662121661329868288 +1662121661374869248 +1662121661422870272 +1662121661470871296 +1662121661512872192 +1662121661557873152 +1662121661605874176 +1662121661650875136 +1662121661698876160 +1662121661740877056 +1662121661782877952 +1662121661833879040 +1662121661887880192 +1662121661929881088 +1662121661974882048 +1662121662013882880 +1662121662055883776 +1662121662103884800 +1662121662148885760 +1662121662190886656 +1662121662232887552 +1662121662283888640 +1662121662328889600 +1662121662370890496 +1662121662418891520 +1662121662463892480 +1662121662511893504 +1662121662556894464 +1662121662604895488 +1662121662649896448 +1662121662688897280 +1662121662736898304 +1662121662778899200 +1662121662823900160 +1662121662868901120 +1662121662913902080 +1662121662958903040 +1662121663006904064 +1662121663051905024 +1662121663102906112 +1662121663147907072 +1662121663195908096 +1662121663243909120 +1662121663282909952 +1662121663324910848 +1662121663366911744 +1662121663414912768 +1662121663459913728 +1662121663504914688 +1662121663549915648 +1662121663597916672 +1662121663639917568 +1662121663681918464 +1662121663723919360 +1662121663765920256 +1662121663810921216 +1662121663855922176 +1662121663903923200 +1662121663948924160 +1662121663993925120 +1662121664035926016 +1662121664089927168 +1662121664134928128 +1662121664182929152 +1662121664224930048 +1662121664272931072 +1662121664320932096 +1662121664365933056 +1662121664413934080 +1662121664461935104 +1662121664512936192 +1662121664554937088 +1662121664596937984 +1662121664647939072 +1662121664701940224 +1662121664752941312 +1662121664809942528 +1662121664854943488 +1662121664899944448 +1662121664941945344 +1662121664983946240 +1662121665037947392 +1662121665079948288 +1662121665121949184 +1662121665163950080 +1662121665214951168 +1662121665262952192 +1662121665307953152 +1662121665355954176 +1662121665400955136 +1662121665445956096 +1662121665502957312 +1662121665547958272 +1662121665592959232 +1662121665640960256 +1662121665685961216 +1662121665730962176 +1662121665772963072 +1662121665817964032 +1662121665856964864 +1662121665904965888 +1662121665946966784 +1662121665988967680 +1662121666030968576 +1662121666078969600 +1662121666120970496 +1662121666162971392 +1662121666210972416 +1662121666255973376 +1662121666297974272 +1662121666345975296 +1662121666390976256 +1662121666432977152 +1662121666474978048 +1662121666519979008 +1662121666567980032 +1662121666612980992 +1662121666666982144 +1662121666705982976 +1662121666756984064 +1662121666801985024 +1662121666858986240 +1662121666900987136 +1662121666942988032 +1662121666987988992 +1662121667041990144 +1662121667089991168 +1662121667137992192 +1662121667185993216 +1662121667230994176 +1662121667275995136 +1662121667320996096 +1662121667362996992 +1662121667410998016 +1662121667455998976 +1662121667500999936 +1662121667546000896 +1662121667594001920 +1662121667642002944 +1662121667687003904 +1662121667729004800 +1662121667771005696 +1662121667816006656 +1662121667861007616 +1662121667903008512 +1662121667957009664 +1662121667999010560 +1662121668041011456 +1662121668089012480 +1662121668134013440 +1662121668179014400 +1662121668224015360 +1662121668278016512 +1662121668323017472 +1662121668374018560 +1662121668413019392 +1662121668458020352 +1662121668500021248 +1662121668539022080 +1662121668581022976 +1662121668626023936 +1662121668668024832 +1662121668710025728 +1662121668752026624 +1662121668797027584 +1662121668842028544 +1662121668884029440 +1662121668926030336 +1662121668974031360 +1662121669019032320 +1662121669061033216 +1662121669103034112 +1662121669154035200 +1662121669199036160 +1662121669241037056 +1662121669283037952 +1662121669325038848 +1662121669367039744 +1662121669409040640 +1662121669454041600 +1662121669511042816 +1662121669556043776 +1662121669595044608 +1662121669634045440 +1662121669673046272 +1662121669715047168 +1662121669760048128 +1662121669802049024 +1662121669856050176 +1662121669901051136 +1662121669943052032 +1662121669988052992 +1662121670036054016 +1662121670081054976 +1662121670123055872 +1662121670165056768 +1662121670219057920 +1662121670267058944 +1662121670315059968 +1662121670360060928 +1662121670411062016 +1662121670456062976 +1662121670507064064 +1662121670561065216 +1662121670606066176 +1662121670654067200 +1662121670699068160 +1662121670753069312 +1662121670789070080 +1662121670831070976 +1662121670873071872 +1662121670921072896 +1662121670963073792 +1662121671005074688 +1662121671047075584 +1662121671089076480 +1662121671137077504 +1662121671179078400 +1662121671221079296 +1662121671263080192 +1662121671317081344 +1662121671359082240 +1662121671401083136 +1662121671443084032 +1662121671485084928 +1662121671536086016 +1662121671578086912 +1662121671620087808 +1662121671671088896 +1662121671713089792 +1662121671758090752 +1662121671800091648 +1662121671842092544 +1662121671893093632 +1662121671935094528 +1662121671977095424 +1662121672025096448 +1662121672073097472 +1662121672115098368 +1662121672157099264 +1662121672208100352 +1662121672259101440 +1662121672304102400 +1662121672349103360 +1662121672394104320 +1662121672436105216 +1662121672484106240 +1662121672526107136 +1662121672574108160 +1662121672616109056 +1662121672664110080 +1662121672709111040 +1662121672754112000 +1662121672799112960 +1662121672841113856 +1662121672886114816 +1662121672934115840 +1662121672985116928 +1662121673027117824 +1662121673066118656 +1662121673111119616 +1662121673159120640 +1662121673204121600 +1662121673243122432 +1662121673288123392 +1662121673339124480 +1662121673387125504 +1662121673435126528 +1662121673489127680 +1662121673537128704 +1662121673582129664 +1662121673639130880 +1662121673681131776 +1662121673726132736 +1662121673768133632 +1662121673819134720 +1662121673861135616 +1662121673906136576 +1662121673963137792 +1662121674002138624 +1662121674050139648 +1662121674092140544 +1662121674137141504 +1662121674182142464 +1662121674230143488 +1662121674275144448 +1662121674323145472 +1662121674365146368 +1662121674413147392 +1662121674458148352 +1662121674500149248 +1662121674542150144 +1662121674587151104 +1662121674629152000 +1662121674674152960 +1662121674719153920 +1662121674767154944 +1662121674818156032 +1662121674863156992 +1662121674917158144 +1662121674959159040 +1662121675007160064 +1662121675046160896 +1662121675094161920 +1662121675136162816 +1662121675178163712 +1662121675226164736 +1662121675268165632 +1662121675313166592 +1662121675355167488 +1662121675400168448 +1662121675445169408 +1662121675493170432 +1662121675535171328 +1662121675580172288 +1662121675625173248 +1662121675667174144 +1662121675709175040 +1662121675751175936 +1662121675799176960 +1662121675847177984 +1662121675892178944 +1662121675937179904 +1662121675979180800 +1662121676021181696 +1662121676066182656 +1662121676108183552 +1662121676153184512 +1662121676207185664 +1662121676249186560 +1662121676294187520 +1662121676339188480 +1662121676387189504 +1662121676432190464 +1662121676474191360 +1662121676519192320 +1662121676567193344 +1662121676621194496 +1662121676666195456 +1662121676708196352 +1662121676756197376 +1662121676798198272 +1662121676852199424 +1662121676903200512 +1662121676948201472 +1662121676993202432 +1662121677035203328 +1662121677083204352 +1662121677134205440 +1662121677188206592 +1662121677236207616 +1662121677278208512 +1662121677317209344 +1662121677365210368 +1662121677407211264 +1662121677449212160 +1662121677491213056 +1662121677533213952 +1662121677575214848 +1662121677617215744 +1662121677659216640 +1662121677701217536 +1662121677743218432 +1662121677785219328 +1662121677827220224 +1662121677869221120 +1662121677914222080 +1662121677956222976 +1662121678004224000 +1662121678055225088 +1662121678094225920 +1662121678136226816 +1662121678187227904 +1662121678229228800 +1662121678274229760 +1662121678319230720 +1662121678367231744 +1662121678412232704 +1662121678469233920 +1662121678520235008 +1662121678565235968 +1662121678607236864 +1662121678649237760 +1662121678691238656 +1662121678733239552 +1662121678775240448 +1662121678817241344 +1662121678862242304 +1662121678907243264 +1662121678952244224 +1662121679009245440 +1662121679051246336 +1662121679093247232 +1662121679138248192 +1662121679186249216 +1662121679228250112 +1662121679273251072 +1662121679321252096 +1662121679372253184 +1662121679420254208 +1662121679462255104 +1662121679504256000 +1662121679549256960 +1662121679594257920 +1662121679639258880 +1662121679684259840 +1662121679729260800 +1662121679768261632 +1662121679810262528 +1662121679861263616 +1662121679903264512 +1662121679948265472 +1662121679996266496 +1662121680035267328 +1662121680080268288 +1662121680125269248 +1662121680167270144 +1662121680218271232 +1662121680263272192 +1662121680305273088 +1662121680347273984 +1662121680392274944 +1662121680437275904 +1662121680479276800 +1662121680530277888 +1662121680578278912 +1662121680629280000 +1662121680671280896 +1662121680713281792 +1662121680761282816 +1662121680803283712 +1662121680851284736 +1662121680896285696 +1662121680935286528 +1662121680974287360 +1662121681016288256 +1662121681064289280 +1662121681109290240 +1662121681157291264 +1662121681208292352 +1662121681250293248 +1662121681295294208 +1662121681340295168 +1662121681391296256 +1662121681436297216 +1662121681484298240 +1662121681535299328 +1662121681577300224 +1662121681622301184 +1662121681673302272 +1662121681724303360 +1662121681772304384 +1662121681817305344 +1662121681862306304 +1662121681910307328 +1662121681958308352 +1662121682000309248 +1662121682048310272 +1662121682090311168 +1662121682132312064 +1662121682180313088 +1662121682225314048 +1662121682270315008 +1662121682321316096 +1662121682369317120 +1662121682417318144 +1662121682459319040 +1662121682504320000 +1662121682546320896 +1662121682597321984 +1662121682639322880 +1662121682684323840 +1662121682735324928 +1662121682789326080 +1662121682831326976 +1662121682873327872 +1662121682921328896 +1662121682966329856 +1662121683014330880 +1662121683062331904 +1662121683107332864 +1662121683161334016 +1662121683203334912 +1662121683248335872 +1662121683296336896 +1662121683341337856 +1662121683386338816 +1662121683434339840 +1662121683482340864 +1662121683527341824 +1662121683575342848 +1662121683623343872 +1662121683668344832 +1662121683713345792 +1662121683761346816 +1662121683806347776 +1662121683848348672 +1662121683899349760 +1662121683941350656 +1662121683983351552 +1662121684025352448 +1662121684067353344 +1662121684109354240 +1662121684157355264 +1662121684202356224 +1662121684250357248 +1662121684298358272 +1662121684346359296 +1662121684391360256 +1662121684433361152 +1662121684475362048 +1662121684517362944 +1662121684562363904 +1662121684616365056 +1662121684661366016 +1662121684703366912 +1662121684754368000 +1662121684799368960 +1662121684850370048 +1662121684898371072 +1662121684940371968 +1662121684997373184 +1662121685036374016 +1662121685081374976 +1662121685123375872 +1662121685171376896 +1662121685228378112 +1662121685282379264 +1662121685330380288 +1662121685375381248 +1662121685420382208 +1662121685468383232 +1662121685510384128 +1662121685561385216 +1662121685609386240 +1662121685651387136 +1662121685693388032 +1662121685738388992 +1662121685783389952 +1662121685834391040 +1662121685897392384 +1662121685948393472 +1662121685993394432 +1662121686044395520 +1662121686086396416 +1662121686131397376 +1662121686176398336 +1662121686215399168 +1662121686260400128 +1662121686305401088 +1662121686353402112 +1662121686404403200 +1662121686449404160 +1662121686491405056 +1662121686533405952 +1662121686575406848 +1662121686626407936 +1662121686668408832 +1662121686716409856 +1662121686767410944 +1662121686812411904 +1662121686854412800 +1662121686899413760 +1662121686941414656 +1662121686992415744 +1662121687040416768 +1662121687085417728 +1662121687133418752 +1662121687175419648 +1662121687217420544 +1662121687265421568 +1662121687307422464 +1662121687352423424 +1662121687397424384 +1662121687445425408 +1662121687490426368 +1662121687532427264 +1662121687574428160 +1662121687619429120 +1662121687664430080 +1662121687709431040 +1662121687751431936 +1662121687793432832 +1662121687832433664 +1662121687880434688 +1662121687928435712 +1662121687970436608 +1662121688018437632 +1662121688069438720 +1662121688126439936 +1662121688171440896 +1662121688216441856 +1662121688258442752 +1662121688303443712 +1662121688345444608 +1662121688387445504 +1662121688429446400 +1662121688474447360 +1662121688522448384 +1662121688570449408 +1662121688609450240 +1662121688651451136 +1662121688705452288 +1662121688747453184 +1662121688795454208 +1662121688840455168 +1662121688885456128 +1662121688924456960 +1662121688975458048 +1662121689017458944 +1662121689059459840 +1662121689101460736 +1662121689149461760 +1662121689194462720 +1662121689239463680 +1662121689287464704 +1662121689329465600 +1662121689380466688 +1662121689422467584 +1662121689467468544 +1662121689509469440 +1662121689554470400 +1662121689602471424 +1662121689644472320 +1662121689686473216 +1662121689734474240 +1662121689773475072 +1662121689812475904 +1662121689857476864 +1662121689908477952 +1662121689950478848 +1662121689995479808 +1662121690046480896 +1662121690094481920 +1662121690139482880 +1662121690178483712 +1662121690220484608 +1662121690268485632 +1662121690313486592 +1662121690361487616 +1662121690403488512 +1662121690454489600 +1662121690496490496 +1662121690538491392 +1662121690583492352 +1662121690625493248 +1662121690673494272 +1662121690721495296 +1662121690766496256 +1662121690805497088 +1662121690850498048 +1662121690892498944 +1662121690934499840 +1662121690976500736 +1662121691027501824 +1662121691072502784 +1662121691114503680 +1662121691156504576 +1662121691201505536 +1662121691246506496 +1662121691297507584 +1662121691342508544 +1662121691384509440 +1662121691429510400 +1662121691471511296 +1662121691522512384 +1662121691564513280 +1662121691612514304 +1662121691660515328 +1662121691705516288 +1662121691747517184 +1662121691792518144 +1662121691834519040 +1662121691885520128 +1662121691927521024 +1662121691969521920 +1662121692023523072 +1662121692068524032 +1662121692125525248 +1662121692182526464 +1662121692224527360 +1662121692266528256 +1662121692311529216 +1662121692359530240 +1662121692407531264 +1662121692449532160 +1662121692491533056 +1662121692545534208 +1662121692593535232 +1662121692644536320 +1662121692686537216 +1662121692731538176 +1662121692779539200 +1662121692818540032 +1662121692866541056 +1662121692911542016 +1662121692956542976 +1662121692998543872 +1662121693046544896 +1662121693097545984 +1662121693139546880 +1662121693184547840 +1662121693229548800 +1662121693277549824 +1662121693322550784 +1662121693364551680 +1662121693409552640 +1662121693457553664 +1662121693502554624 +1662121693547555584 +1662121693589556480 +1662121693634557440 +1662121693673558272 +1662121693718559232 +1662121693763560192 +1662121693805561088 +1662121693847561984 +1662121693895563008 +1662121693937563904 +1662121693982564864 +1662121694033565952 +1662121694081566976 +1662121694132568064 +1662121694177569024 +1662121694219569920 +1662121694267570944 +1662121694312571904 +1662121694360572928 +1662121694408573952 +1662121694462575104 +1662121694507576064 +1662121694549576960 +1662121694594577920 +1662121694636578816 +1662121694678579712 +1662121694729580800 +1662121694771581696 +1662121694822582784 +1662121694864583680 +1662121694909584640 +1662121694951585536 +1662121695002586624 +1662121695047587584 +1662121695089588480 +1662121695137589504 +1662121695185590528 +1662121695227591424 +1662121695269592320 +1662121695311593216 +1662121695353594112 +1662121695398595072 +1662121695449596160 +1662121695491597056 +1662121695548598272 +1662121695593599232 +1662121695638600192 +1662121695683601152 +1662121695725602048 +1662121695767602944 +1662121695809603840 +1662121695854604800 +1662121695896605696 +1662121695947606784 +1662121695998607872 +1662121696046608896 +1662121696091609856 +1662121696151611136 +1662121696202612224 +1662121696250613248 +1662121696298614272 +1662121696340615168 +1662121696385616128 +1662121696433617152 +1662121696478618112 +1662121696526619136 +1662121696571620096 +1662121696616621056 +1662121696661622016 +1662121696709623040 +1662121696757624064 +1662121696802625024 +1662121696847625984 +1662121696889626880 +1662121696943628032 +1662121696985628928 +1662121697036630016 +1662121697084631040 +1662121697123631872 +1662121697171632896 +1662121697219633920 +1662121697267634944 +1662121697312635904 +1662121697354636800 +1662121697399637760 +1662121697441638656 +1662121697489639680 +1662121697534640640 +1662121697582641664 +1662121697633642752 +1662121697678643712 +1662121697732644864 +1662121697780645888 +1662121697831646976 +1662121697873647872 +1662121697915648768 +1662121697960649728 +1662121698005650688 +1662121698047651584 +1662121698098652672 +1662121698143653632 +1662121698191654656 +1662121698242655744 +1662121698287656704 +1662121698329657600 +1662121698371658496 +1662121698413659392 +1662121698458660352 +1662121698506661376 +1662121698554662400 +1662121698602663424 +1662121698647664384 +1662121698689665280 +1662121698737666304 +1662121698782667264 +1662121698827668224 +1662121698866669056 +1662121698914670080 +1662121698959671040 +1662121699004672000 +1662121699049672960 +1662121699094673920 +1662121699136674816 +1662121699181675776 +1662121699226676736 +1662121699268677632 +1662121699310678528 +1662121699358679552 +1662121699400680448 +1662121699445681408 +1662121699487682304 +1662121699532683264 +1662121699577684224 +1662121699622685184 +1662121699667686144 +1662121699709687040 +1662121699763688192 +1662121699814689280 +1662121699856690176 +1662121699898691072 +1662121699946692096 +1662121700003693312 +1662121700048694272 +1662121700096695296 +1662121700138696192 +1662121700177697024 +1662121700219697920 +1662121700267698944 +1662121700312699904 +1662121700357700864 +1662121700408701952 +1662121700453702912 +1662121700495703808 +1662121700546704896 +1662121700597705984 +1662121700642706944 +1662121700684707840 +1662121700729708800 +1662121700774709760 +1662121700816710656 +1662121700864711680 +1662121700906712576 +1662121700960713728 +1662121701011714816 +1662121701053715712 +1662121701095716608 +1662121701140717568 +1662121701191718656 +1662121701233719552 +1662121701278720512 +1662121701326721536 +1662121701371722496 +1662121701413723392 +1662121701461724416 +1662121701503725312 +1662121701545726208 +1662121701584727040 +1662121701629728000 +1662121701677729024 +1662121701722729984 +1662121701770731008 +1662121701812731904 +1662121701857732864 +1662121701902733824 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt new file mode 100644 index 0000000000..23ef73aa69 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt @@ -0,0 +1,2934 @@ +1662064490014331136 +1662064490059332096 +1662064490101332992 +1662064490140333824 +1662064490188334848 +1662064490233335808 +1662064490275336704 +1662064490323337728 +1662064490371338752 +1662064490419339776 +1662064490461340672 +1662064490506341632 +1662064490548342528 +1662064490590343424 +1662064490632344320 +1662064490671345152 +1662064490710345984 +1662064490749346816 +1662064490794347776 +1662064490836348672 +1662064490878349568 +1662064490920350464 +1662064490962351360 +1662064491007352320 +1662064491049353216 +1662064491088354048 +1662064491130354944 +1662064491175355904 +1662064491223356928 +1662064491265357824 +1662064491307358720 +1662064491352359680 +1662064491397360640 +1662064491439361536 +1662064491481362432 +1662064491523363328 +1662064491562364160 +1662064491601364992 +1662064491643365888 +1662064491685366784 +1662064491727367680 +1662064491778368768 +1662064491820369664 +1662064491862370560 +1662064491904371456 +1662064491946372352 +1662064491985373184 +1662064492030374144 +1662064492072375040 +1662064492117376000 +1662064492159376896 +1662064492201377792 +1662064492246378752 +1662064492288379648 +1662064492330380544 +1662064492372381440 +1662064492411382272 +1662064492456383232 +1662064492501384192 +1662064492543385088 +1662064492588386048 +1662064492630386944 +1662064492669387776 +1662064492714388736 +1662064492756389632 +1662064492801390592 +1662064492846391552 +1662064492885392384 +1662064492927393280 +1662064492975394304 +1662064493017395200 +1662064493065396224 +1662064493107397120 +1662064493149398016 +1662064493188398848 +1662064493236399872 +1662064493284400896 +1662064493329401856 +1662064493374402816 +1662064493419403776 +1662064493464404736 +1662064493506405632 +1662064493554406656 +1662064493596407552 +1662064493638408448 +1662064493680409344 +1662064493722410240 +1662064493767411200 +1662064493815412224 +1662064493857413120 +1662064493899414016 +1662064493938414848 +1662064493983415808 +1662064494028416768 +1662064494073417728 +1662064494115418624 +1662064494160419584 +1662064494205420544 +1662064494244421376 +1662064494289422336 +1662064494331423232 +1662064494379424256 +1662064494418425088 +1662064494463426048 +1662064494505426944 +1662064494547427840 +1662064494589428736 +1662064494631429632 +1662064494670430464 +1662064494721431552 +1662064494766432512 +1662064494811433472 +1662064494853434368 +1662064494895435264 +1662064494937436160 +1662064494976436992 +1662064495018437888 +1662064495063438848 +1662064495108439808 +1662064495147440640 +1662064495189441536 +1662064495231442432 +1662064495273443328 +1662064495321444352 +1662064495366445312 +1662064495408446208 +1662064495450447104 +1662064495486447872 +1662064495528448768 +1662064495570449664 +1662064495615450624 +1662064495654451456 +1662064495699452416 +1662064495738453248 +1662064495783454208 +1662064495819454976 +1662064495861455872 +1662064495903456768 +1662064495945457664 +1662064495987458560 +1662064496026459392 +1662064496071460352 +1662064496116461312 +1662064496161462272 +1662064496200463104 +1662064496242464000 +1662064496284464896 +1662064496326465792 +1662064496365466624 +1662064496407467520 +1662064496452468480 +1662064496494469376 +1662064496536470272 +1662064496578471168 +1662064496623472128 +1662064496668473088 +1662064496707473920 +1662064496752474880 +1662064496794475776 +1662064496833476608 +1662064496875477504 +1662064496917478400 +1662064496959479296 +1662064497004480256 +1662064497046481152 +1662064497091482112 +1662064497133483008 +1662064497175483904 +1662064497217484800 +1662064497256485632 +1662064497295486464 +1662064497334487296 +1662064497379488256 +1662064497424489216 +1662064497463490048 +1662064497505490944 +1662064497550491904 +1662064497589492736 +1662064497631493632 +1662064497676494592 +1662064497727495680 +1662064497769496576 +1662064497811497472 +1662064497853498368 +1662064497892499200 +1662064497934500096 +1662064497973500928 +1662064498012501760 +1662064498057502720 +1662064498102503680 +1662064498147504640 +1662064498189505536 +1662064498234506496 +1662064498276507392 +1662064498318508288 +1662064498363509248 +1662064498408510208 +1662064498450511104 +1662064498492512000 +1662064498534512896 +1662064498579513856 +1662064498615514624 +1662064498654515456 +1662064498696516352 +1662064498741517312 +1662064498777518080 +1662064498813518848 +1662064498855519744 +1662064498903520768 +1662064498948521728 +1662064498993522688 +1662064499035523584 +1662064499080524544 +1662064499122525440 +1662064499161526272 +1662064499206527232 +1662064499242528000 +1662064499284528896 +1662064499323529728 +1662064499365530624 +1662064499404531456 +1662064499446532352 +1662064499494533376 +1662064499542534400 +1662064499590535424 +1662064499629536256 +1662064499671537152 +1662064499716538112 +1662064499761539072 +1662064499800539904 +1662064499839540736 +1662064499884541696 +1662064499923542528 +1662064499968543488 +1662064500016544512 +1662064500064545536 +1662064500109546496 +1662064500148547328 +1662064500190548224 +1662064500235549184 +1662064500277550080 +1662064500322551040 +1662064500367552000 +1662064500409552896 +1662064500451553792 +1662064500496554752 +1662064500541555712 +1662064500583556608 +1662064500625557504 +1662064500670558464 +1662064500712559360 +1662064500757560320 +1662064500799561216 +1662064500841562112 +1662064500883563008 +1662064500925563904 +1662064500970564864 +1662064501015565824 +1662064501060566784 +1662064501102567680 +1662064501144568576 +1662064501192569600 +1662064501234570496 +1662064501276571392 +1662064501315572224 +1662064501354573056 +1662064501405574144 +1662064501447575040 +1662064501489575936 +1662064501534576896 +1662064501579577856 +1662064501621578752 +1662064501666579712 +1662064501714580736 +1662064501756581632 +1662064501798582528 +1662064501843583488 +1662064501885584384 +1662064501924585216 +1662064501969586176 +1662064502011587072 +1662064502053587968 +1662064502098588928 +1662064502143589888 +1662064502191590912 +1662064502236591872 +1662064502281592832 +1662064502320593664 +1662064502362594560 +1662064502398595328 +1662064502440596224 +1662064502485597184 +1662064502524598016 +1662064502566598912 +1662064502608599808 +1662064502653600768 +1662064502695601664 +1662064502737602560 +1662064502782603520 +1662064502827604480 +1662064502872605440 +1662064502917606400 +1662064502962607360 +1662064503007608320 +1662064503052609280 +1662064503100610304 +1662064503139611136 +1662064503178611968 +1662064503223612928 +1662064503268613888 +1662064503313614848 +1662064503355615744 +1662064503397616640 +1662064503442617600 +1662064503484618496 +1662064503526619392 +1662064503568620288 +1662064503610621184 +1662064503658622208 +1662064503703623168 +1662064503745624064 +1662064503790625024 +1662064503832625920 +1662064503874626816 +1662064503916627712 +1662064503958628608 +1662064504000629504 +1662064504042630400 +1662064504084631296 +1662064504126632192 +1662064504162632960 +1662064504204633856 +1662064504249634816 +1662064504294635776 +1662064504339636736 +1662064504381637632 +1662064504429638656 +1662064504468639488 +1662064504510640384 +1662064504558641408 +1662064504597642240 +1662064504645643264 +1662064504687644160 +1662064504729645056 +1662064504771645952 +1662064504813646848 +1662064504852647680 +1662064504897648640 +1662064504936649472 +1662064504975650304 +1662064505017651200 +1662064505059652096 +1662064505101652992 +1662064505143653888 +1662064505191654912 +1662064505236655872 +1662064505278656768 +1662064505320657664 +1662064505362658560 +1662064505407659520 +1662064505449660416 +1662064505497661440 +1662064505539662336 +1662064505578663168 +1662064505623664128 +1662064505668665088 +1662064505716666112 +1662064505758667008 +1662064505809668096 +1662064505848668928 +1662064505890669824 +1662064505938670848 +1662064505980671744 +1662064506022672640 +1662064506064673536 +1662064506106674432 +1662064506151675392 +1662064506196676352 +1662064506244677376 +1662064506289678336 +1662064506334679296 +1662064506376680192 +1662064506418681088 +1662064506454681856 +1662064506499682816 +1662064506544683776 +1662064506586684672 +1662064506631685632 +1662064506673686528 +1662064506715687424 +1662064506757688320 +1662064506796689152 +1662064506838690048 +1662064506880690944 +1662064506922691840 +1662064506970692864 +1662064507012693760 +1662064507057694720 +1662064507099695616 +1662064507141696512 +1662064507180697344 +1662064507219698176 +1662064507270699264 +1662064507315700224 +1662064507357701120 +1662064507405702144 +1662064507447703040 +1662064507486703872 +1662064507528704768 +1662064507570705664 +1662064507612706560 +1662064507654707456 +1662064507702708480 +1662064507747709440 +1662064507789710336 +1662064507834711296 +1662064507879712256 +1662064507930713344 +1662064507975714304 +1662064508014715136 +1662064508062716160 +1662064508107717120 +1662064508152718080 +1662064508194718976 +1662064508236719872 +1662064508281720832 +1662064508329721856 +1662064508362722560 +1662064508407723520 +1662064508455724544 +1662064508497725440 +1662064508539726336 +1662064508584727296 +1662064508623728128 +1662064508665729024 +1662064508710729984 +1662064508761731072 +1662064508806732032 +1662064508854733056 +1662064508899734016 +1662064508941734912 +1662064508983735808 +1662064509025736704 +1662064509070737664 +1662064509115738624 +1662064509151739392 +1662064509193740288 +1662064509235741184 +1662064509280742144 +1662064509325743104 +1662064509364743936 +1662064509406744832 +1662064509448745728 +1662064509490746624 +1662064509532747520 +1662064509574748416 +1662064509616749312 +1662064509661750272 +1662064509706751232 +1662064509751752192 +1662064509793753088 +1662064509835753984 +1662064509877754880 +1662064509922755840 +1662064509967756800 +1662064510009757696 +1662064510051758592 +1662064510099759616 +1662064510141760512 +1662064510183761408 +1662064510228762368 +1662064510273763328 +1662064510321764352 +1662064510363765248 +1662064510405766144 +1662064510453767168 +1662064510495768064 +1662064510540769024 +1662064510582769920 +1662064510621770752 +1662064510660771584 +1662064510702772480 +1662064510747773440 +1662064510789774336 +1662064510831775232 +1662064510870776064 +1662064510915777024 +1662064510957777920 +1662064510999778816 +1662064511041779712 +1662064511083780608 +1662064511122781440 +1662064511164782336 +1662064511206783232 +1662064511254784256 +1662064511296785152 +1662064511338786048 +1662064511383787008 +1662064511425787904 +1662064511473788928 +1662064511515789824 +1662064511557790720 +1662064511602791680 +1662064511644792576 +1662064511686793472 +1662064511725794304 +1662064511770795264 +1662064511809796096 +1662064511851796992 +1662064511896797952 +1662064511938798848 +1662064511980799744 +1662064512028800768 +1662064512070801664 +1662064512109802496 +1662064512151803392 +1662064512193804288 +1662064512235805184 +1662064512271805952 +1662064512322807040 +1662064512364807936 +1662064512406808832 +1662064512445809664 +1662064512484810496 +1662064512523811328 +1662064512568812288 +1662064512607813120 +1662064512646813952 +1662064512691814912 +1662064512733815808 +1662064512778816768 +1662064512820817664 +1662064512859818496 +1662064512904819456 +1662064512952820480 +1662064512997821440 +1662064513039822336 +1662064513081823232 +1662064513123824128 +1662064513165825024 +1662064513207825920 +1662064513252826880 +1662064513294827776 +1662064513339828736 +1662064513381829632 +1662064513423830528 +1662064513465831424 +1662064513507832320 +1662064513546833152 +1662064513588834048 +1662064513627834880 +1662064513672835840 +1662064513714836736 +1662064513756837632 +1662064513795838464 +1662064513834839296 +1662064513873840128 +1662064513915841024 +1662064513960841984 +1662064514008843008 +1662064514050843904 +1662064514095844864 +1662064514137845760 +1662064514179846656 +1662064514221847552 +1662064514266848512 +1662064514311849472 +1662064514350850304 +1662064514383851008 +1662064514425851904 +1662064514467852800 +1662064514512853760 +1662064514554854656 +1662064514596855552 +1662064514641856512 +1662064514683857408 +1662064514725858304 +1662064514767859200 +1662064514812860160 +1662064514854861056 +1662064514899862016 +1662064514944862976 +1662064514986863872 +1662064515028864768 +1662064515070865664 +1662064515112866560 +1662064515154867456 +1662064515205868544 +1662064515250869504 +1662064515295870464 +1662064515343871488 +1662064515388872448 +1662064515427873280 +1662064515472874240 +1662064515517875200 +1662064515556876032 +1662064515598876928 +1662064515637877760 +1662064515685878784 +1662064515727879680 +1662064515769880576 +1662064515817881600 +1662064515859882496 +1662064515898883328 +1662064515937884160 +1662064515985885184 +1662064516024886016 +1662064516063886848 +1662064516105887744 +1662064516144888576 +1662064516189889536 +1662064516228890368 +1662064516270891264 +1662064516315892224 +1662064516360893184 +1662064516402894080 +1662064516441894912 +1662064516483895808 +1662064516522896640 +1662064516558897408 +1662064516600898304 +1662064516639899136 +1662064516687900160 +1662064516729901056 +1662064516774902016 +1662064516819902976 +1662064516858903808 +1662064516900904704 +1662064516942905600 +1662064516984906496 +1662064517029907456 +1662064517071908352 +1662064517116909312 +1662064517158910208 +1662064517200911104 +1662064517254912256 +1662064517296913152 +1662064517338914048 +1662064517380914944 +1662064517419915776 +1662064517467916800 +1662064517512917760 +1662064517554918656 +1662064517605919744 +1662064517650920704 +1662064517692921600 +1662064517737922560 +1662064517779923456 +1662064517824924416 +1662064517863925248 +1662064517902926080 +1662064517947927040 +1662064517989927936 +1662064518028928768 +1662064518073929728 +1662064518118930688 +1662064518160931584 +1662064518199932416 +1662064518241933312 +1662064518280934144 +1662064518322935040 +1662064518361935872 +1662064518406936832 +1662064518448937728 +1662064518490938624 +1662064518532939520 +1662064518577940480 +1662064518622941440 +1662064518667942400 +1662064518709943296 +1662064518751944192 +1662064518793945088 +1662064518832945920 +1662064518874946816 +1662064518916947712 +1662064518964948736 +1662064519009949696 +1662064519048950528 +1662064519084951296 +1662064519126952192 +1662064519168953088 +1662064519210953984 +1662064519252954880 +1662064519288955648 +1662064519333956608 +1662064519378957568 +1662064519420958464 +1662064519462959360 +1662064519507960320 +1662064519546961152 +1662064519591962112 +1662064519639963136 +1662064519678963968 +1662064519717964800 +1662064519759965696 +1662064519804966656 +1662064519849967616 +1662064519888968448 +1662064519930969344 +1662064519975970304 +1662064520017971200 +1662064520062972160 +1662064520104973056 +1662064520149974016 +1662064520194974976 +1662064520239975936 +1662064520281976832 +1662064520323977728 +1662064520368978688 +1662064520416979712 +1662064520464980736 +1662064520506981632 +1662064520548982528 +1662064520593983488 +1662064520641984512 +1662064520683985408 +1662064520725986304 +1662064520767987200 +1662064520812988160 +1662064520854989056 +1662064520896989952 +1662064520938990848 +1662064520977991680 +1662064521022992640 +1662064521064993536 +1662064521106994432 +1662064521148995328 +1662064521187996160 +1662064521226996992 +1662064521268997888 +1662064521316998912 +1662064521361999872 +1662064521407000832 +1662064521449001728 +1662064521491002624 +1662064521536003584 +1662064521578004480 +1662064521620005376 +1662064521662006272 +1662064521707007232 +1662064521746008064 +1662064521788008960 +1662064521827009792 +1662064521869010688 +1662064521911011584 +1662064521950012416 +1662064521992013312 +1662064522034014208 +1662064522076015104 +1662064522118016000 +1662064522163016960 +1662064522205017856 +1662064522247018752 +1662064522286019584 +1662064522328020480 +1662064522370021376 +1662064522412022272 +1662064522457023232 +1662064522499024128 +1662064522538024960 +1662064522580025856 +1662064522625026816 +1662064522667027712 +1662064522709028608 +1662064522754029568 +1662064522793030400 +1662064522835031296 +1662064522877032192 +1662064522919033088 +1662064522961033984 +1662064523003034880 +1662064523045035776 +1662064523093036800 +1662064523138037760 +1662064523180038656 +1662064523225039616 +1662064523267040512 +1662064523312041472 +1662064523354042368 +1662064523396043264 +1662064523438044160 +1662064523480045056 +1662064523522045952 +1662064523561046784 +1662064523600047616 +1662064523645048576 +1662064523687049472 +1662064523735050496 +1662064523777051392 +1662064523819052288 +1662064523861053184 +1662064523903054080 +1662064523954055168 +1662064523996056064 +1662064524035056896 +1662064524083057920 +1662064524128058880 +1662064524170059776 +1662064524212060672 +1662064524254061568 +1662064524302062592 +1662064524344063488 +1662064524389064448 +1662064524431065344 +1662064524470066176 +1662064524512067072 +1662064524557068032 +1662064524596068864 +1662064524638069760 +1662064524677070592 +1662064524722071552 +1662064524761072384 +1662064524806073344 +1662064524851074304 +1662064524896075264 +1662064524932076032 +1662064524971076864 +1662064525013077760 +1662064525058078720 +1662064525106079744 +1662064525151080704 +1662064525196081664 +1662064525238082560 +1662064525280083456 +1662064525328084480 +1662064525367085312 +1662064525412086272 +1662064525454087168 +1662064525499088128 +1662064525544089088 +1662064525586089984 +1662064525628090880 +1662064525664091648 +1662064525712092672 +1662064525754093568 +1662064525802094592 +1662064525847095552 +1662064525889096448 +1662064525931097344 +1662064525982098432 +1662064526024099328 +1662064526066100224 +1662064526105101056 +1662064526147101952 +1662064526189102848 +1662064526231103744 +1662064526276104704 +1662064526324105728 +1662064526366106624 +1662064526405107456 +1662064526450108416 +1662064526492109312 +1662064526534110208 +1662064526579111168 +1662064526624112128 +1662064526666113024 +1662064526708113920 +1662064526753114880 +1662064526798115840 +1662064526840116736 +1662064526885117696 +1662064526927118592 +1662064526969119488 +1662064527020120576 +1662064527062121472 +1662064527104122368 +1662064527149123328 +1662064527185124096 +1662064527227124992 +1662064527269125888 +1662064527311126784 +1662064527353127680 +1662064527389128448 +1662064527431129344 +1662064527470130176 +1662064527512131072 +1662064527557132032 +1662064527602132992 +1662064527644133888 +1662064527692134912 +1662064527731135744 +1662064527776136704 +1662064527815137536 +1662064527863138560 +1662064527905139456 +1662064527950140416 +1662064527992141312 +1662064528037142272 +1662064528079143168 +1662064528124144128 +1662064528172145152 +1662064528214146048 +1662064528262147072 +1662064528304147968 +1662064528349148928 +1662064528391149824 +1662064528430150656 +1662064528472151552 +1662064528514152448 +1662064528556153344 +1662064528592154112 +1662064528628154880 +1662064528667155712 +1662064528712156672 +1662064528754157568 +1662064528796158464 +1662064528838159360 +1662064528883160320 +1662064528922161152 +1662064528964162048 +1662064529009163008 +1662064529048163840 +1662064529093164800 +1662064529138165760 +1662064529183166720 +1662064529225167616 +1662064529267168512 +1662064529309169408 +1662064529354170368 +1662064529396171264 +1662064529438172160 +1662064529480173056 +1662064529525174016 +1662064529564174848 +1662064529609175808 +1662064529654176768 +1662064529693177600 +1662064529738178560 +1662064529780179456 +1662064529822180352 +1662064529867181312 +1662064529915182336 +1662064529957183232 +1662064530002184192 +1662064530047185152 +1662064530092186112 +1662064530134187008 +1662064530182188032 +1662064530227188992 +1662064530269189888 +1662064530308190720 +1662064530350191616 +1662064530395192576 +1662064530437193472 +1662064530482194432 +1662064530521195264 +1662064530566196224 +1662064530611197184 +1662064530653198080 +1662064530695198976 +1662064530740199936 +1662064530788200960 +1662064530833201920 +1662064530872202752 +1662064530920203776 +1662064530962204672 +1662064531007205632 +1662064531049206528 +1662064531097207552 +1662064531142208512 +1662064531184209408 +1662064531223210240 +1662064531265211136 +1662064531310212096 +1662064531352212992 +1662064531394213888 +1662064531436214784 +1662064531478215680 +1662064531517216512 +1662064531556217344 +1662064531601218304 +1662064531646219264 +1662064531685220096 +1662064531727220992 +1662064531769221888 +1662064531808222720 +1662064531847223552 +1662064531892224512 +1662064531934225408 +1662064531982226432 +1662064532027227392 +1662064532069228288 +1662064532111229184 +1662064532159230208 +1662064532201231104 +1662064532246232064 +1662064532291233024 +1662064532330233856 +1662064532372234752 +1662064532417235712 +1662064532462236672 +1662064532504237568 +1662064532543238400 +1662064532585239296 +1662064532627240192 +1662064532672241152 +1662064532714242048 +1662064532756242944 +1662064532795243776 +1662064532837244672 +1662064532882245632 +1662064532927246592 +1662064532966247424 +1662064533008248320 +1662064533047249152 +1662064533089250048 +1662064533131250944 +1662064533173251840 +1662064533215252736 +1662064533257253632 +1662064533302254592 +1662064533344255488 +1662064533386256384 +1662064533428257280 +1662064533470258176 +1662064533512259072 +1662064533551259904 +1662064533593260800 +1662064533638261760 +1662064533680262656 +1662064533722263552 +1662064533767264512 +1662064533809265408 +1662064533851266304 +1662064533893267200 +1662064533935268096 +1662064533977268992 +1662064534022269952 +1662064534067270912 +1662064534109271808 +1662064534154272768 +1662064534193273600 +1662064534238274560 +1662064534280275456 +1662064534322276352 +1662064534367277312 +1662064534409278208 +1662064534451279104 +1662064534499280128 +1662064534544281088 +1662064534589282048 +1662064534634283008 +1662064534673283840 +1662064534712284672 +1662064534754285568 +1662064534799286528 +1662064534844287488 +1662064534892288512 +1662064534937289472 +1662064534979290368 +1662064535021291264 +1662064535060292096 +1662064535105293056 +1662064535156294144 +1662064535201295104 +1662064535249296128 +1662064535291297024 +1662064535336297984 +1662064535375298816 +1662064535417299712 +1662064535459300608 +1662064535501301504 +1662064535543302400 +1662064535585303296 +1662064535627304192 +1662064535669305088 +1662064535714306048 +1662064535753306880 +1662064535795307776 +1662064535837308672 +1662064535879309568 +1662064535921310464 +1662064535969311488 +1662064536014312448 +1662064536056313344 +1662064536104314368 +1662064536143315200 +1662064536185316096 +1662064536230317056 +1662064536275318016 +1662064536323319040 +1662064536365319936 +1662064536410320896 +1662064536452321792 +1662064536497322752 +1662064536545323776 +1662064536593324800 +1662064536635325696 +1662064536677326592 +1662064536719327488 +1662064536761328384 +1662064536806329344 +1662064536854330368 +1662064536905331456 +1662064536950332416 +1662064536992333312 +1662064537034334208 +1662064537079335168 +1662064537124336128 +1662064537163336960 +1662064537202337792 +1662064537244338688 +1662064537289339648 +1662064537331340544 +1662064537376341504 +1662064537421342464 +1662064537463343360 +1662064537505344256 +1662064537553345280 +1662064537595346176 +1662064537640347136 +1662064537688348160 +1662064537733349120 +1662064537775350016 +1662064537817350912 +1662064537856351744 +1662064537898352640 +1662064537940353536 +1662064537988354560 +1662064538033355520 +1662064538078356480 +1662064538123357440 +1662064538171358464 +1662064538213359360 +1662064538258360320 +1662064538297361152 +1662064538339362048 +1662064538384363008 +1662064538429363968 +1662064538471364864 +1662064538513365760 +1662064538555366656 +1662064538597367552 +1662064538639368448 +1662064538684369408 +1662064538726370304 +1662064538771371264 +1662064538810372096 +1662064538852372992 +1662064538891373824 +1662064538939374848 +1662064538984375808 +1662064539026376704 +1662064539071377664 +1662064539113378560 +1662064539158379520 +1662064539200380416 +1662064539242381312 +1662064539281382144 +1662064539326383104 +1662064539368384000 +1662064539410384896 +1662064539455385856 +1662064539497386752 +1662064539539387648 +1662064539581388544 +1662064539629389568 +1662064539671390464 +1662064539719391488 +1662064539764392448 +1662064539803393280 +1662064539845394176 +1662064539896395264 +1662064539938396160 +1662064539977396992 +1662064540022397952 +1662064540061398784 +1662064540103399680 +1662064540151400704 +1662064540187401472 +1662064540226402304 +1662064540271403264 +1662064540319404288 +1662064540361405184 +1662064540403406080 +1662064540445406976 +1662064540481407744 +1662064540523408640 +1662064540562409472 +1662064540607410432 +1662064540649411328 +1662064540694412288 +1662064540736413184 +1662064540781414144 +1662064540826415104 +1662064540868416000 +1662064540910416896 +1662064540949417728 +1662064540994418688 +1662064541039419648 +1662064541078420480 +1662064541117421312 +1662064541159422208 +1662064541198423040 +1662064541240423936 +1662064541282424832 +1662064541324425728 +1662064541366426624 +1662064541405427456 +1662064541444428288 +1662064541489429248 +1662064541534430208 +1662064541576431104 +1662064541621432064 +1662064541666433024 +1662064541705433856 +1662064541744434688 +1662064541789435648 +1662064541828436480 +1662064541870437376 +1662064541915438336 +1662064541957439232 +1662064541999440128 +1662064542044441088 +1662064542086441984 +1662064542131442944 +1662064542173443840 +1662064542215444736 +1662064542263445760 +1662064542308446720 +1662064542350447616 +1662064542395448576 +1662064542440449536 +1662064542482450432 +1662064542524451328 +1662064542569452288 +1662064542614453248 +1662064542659454208 +1662064542701455104 +1662064542743456000 +1662064542782456832 +1662064542827457792 +1662064542875458816 +1662064542920459776 +1662064542959460608 +1662064543004461568 +1662064543049462528 +1662064543091463424 +1662064543139464448 +1662064543184465408 +1662064543235466496 +1662064543280467456 +1662064543325468416 +1662064543367469312 +1662064543412470272 +1662064543454471168 +1662064543496472064 +1662064543541473024 +1662064543580473856 +1662064543625474816 +1662064543667475712 +1662064543706476544 +1662064543742477312 +1662064543784478208 +1662064543823479040 +1662064543877480192 +1662064543928481280 +1662064543973482240 +1662064544018483200 +1662064544057484032 +1662064544099484928 +1662064544144485888 +1662064544186486784 +1662064544228487680 +1662064544267488512 +1662064544309489408 +1662064544354490368 +1662064544396491264 +1662064544438492160 +1662064544477492992 +1662064544519493888 +1662064544564494848 +1662064544609495808 +1662064544651496704 +1662064544693497600 +1662064544735498496 +1662064544777499392 +1662064544819500288 +1662064544864501248 +1662064544909502208 +1662064544954503168 +1662064544993504000 +1662064545035504896 +1662064545080505856 +1662064545122506752 +1662064545164507648 +1662064545209508608 +1662064545257509632 +1662064545299510528 +1662064545344511488 +1662064545389512448 +1662064545431513344 +1662064545476514304 +1662064545518515200 +1662064545563516160 +1662064545617517312 +1662064545659518208 +1662064545707519232 +1662064545749520128 +1662064545794521088 +1662064545836521984 +1662064545881522944 +1662064545926523904 +1662064545971524864 +1662064546016525824 +1662064546061526784 +1662064546106527744 +1662064546148528640 +1662064546193529600 +1662064546232530432 +1662064546274531328 +1662064546316532224 +1662064546361533184 +1662064546406534144 +1662064546445534976 +1662064546484535808 +1662064546529536768 +1662064546574537728 +1662064546619538688 +1662064546658539520 +1662064546700540416 +1662064546739541248 +1662064546784542208 +1662064546826543104 +1662064546871544064 +1662064546913544960 +1662064546955545856 +1662064546997546752 +1662064547042547712 +1662064547087548672 +1662064547132549632 +1662064547177550592 +1662064547219551488 +1662064547264552448 +1662064547306553344 +1662064547348554240 +1662064547390555136 +1662064547432556032 +1662064547474556928 +1662064547522557952 +1662064547564558848 +1662064547606559744 +1662064547651560704 +1662064547699561728 +1662064547738562560 +1662064547780563456 +1662064547816564224 +1662064547855565056 +1662064547900566016 +1662064547942566912 +1662064547987567872 +1662064548029568768 +1662064548074569728 +1662064548116570624 +1662064548158571520 +1662064548197572352 +1662064548242573312 +1662064548284574208 +1662064548329575168 +1662064548368576000 +1662064548407576832 +1662064548452577792 +1662064548500578816 +1662064548545579776 +1662064548590580736 +1662064548629581568 +1662064548671582464 +1662064548713583360 +1662064548758584320 +1662064548803585280 +1662064548845586176 +1662064548884587008 +1662064548929587968 +1662064548974588928 +1662064549016589824 +1662064549061590784 +1662064549100591616 +1662064549148592640 +1662064549199593728 +1662064549241594624 +1662064549286595584 +1662064549328596480 +1662064549373597440 +1662064549418598400 +1662064549463599360 +1662064549505600256 +1662064549550601216 +1662064549592602112 +1662064549634603008 +1662064549676603904 +1662064549724604928 +1662064549766605824 +1662064549805606656 +1662064549847607552 +1662064549886608384 +1662064549931609344 +1662064549976610304 +1662064550021611264 +1662064550063612160 +1662064550108613120 +1662064550147613952 +1662064550189614848 +1662064550231615744 +1662064550276616704 +1662064550318617600 +1662064550357618432 +1662064550399619328 +1662064550444620288 +1662064550486621184 +1662064550528622080 +1662064550567622912 +1662064550609623808 +1662064550657624832 +1662064550702625792 +1662064550744626688 +1662064550786627584 +1662064550822628352 +1662064550861629184 +1662064550906630144 +1662064550951631104 +1662064550987631872 +1662064551029632768 +1662064551071633664 +1662064551116634624 +1662064551158635520 +1662064551200636416 +1662064551239637248 +1662064551281638144 +1662064551323639040 +1662064551365639936 +1662064551404640768 +1662064551449641728 +1662064551494642688 +1662064551539643648 +1662064551581644544 +1662064551623645440 +1662064551662646272 +1662064551707647232 +1662064551749648128 +1662064551794649088 +1662064551839650048 +1662064551881650944 +1662064551926651904 +1662064551971652864 +1662064552010653696 +1662064552049654528 +1662064552088655360 +1662064552133656320 +1662064552178657280 +1662064552220658176 +1662064552262659072 +1662064552310660096 +1662064552352660992 +1662064552394661888 +1662064552436662784 +1662064552478663680 +1662064552532664832 +1662064552577665792 +1662064552619666688 +1662064552661667584 +1662064552709668608 +1662064552757669632 +1662064552802670592 +1662064552844671488 +1662064552886672384 +1662064552928673280 +1662064552970674176 +1662064553018675200 +1662064553060676096 +1662064553093676800 +1662064553141677824 +1662064553180678656 +1662064553228679680 +1662064553273680640 +1662064553315681536 +1662064553354682368 +1662064553396683264 +1662064553438684160 +1662064553480685056 +1662064553525686016 +1662064553567686912 +1662064553612687872 +1662064553654688768 +1662064553699689728 +1662064553741690624 +1662064553780691456 +1662064553822692352 +1662064553864693248 +1662064553906694144 +1662064553948695040 +1662064553990695936 +1662064554035696896 +1662064554074697728 +1662064554116698624 +1662064554155699456 +1662064554200700416 +1662064554245701376 +1662064554287702272 +1662064554332703232 +1662064554371704064 +1662064554413704960 +1662064554452705792 +1662064554494706688 +1662064554536707584 +1662064554578708480 +1662064554620709376 +1662064554665710336 +1662064554707711232 +1662064554752712192 +1662064554797713152 +1662064554836713984 +1662064554878714880 +1662064554920715776 +1662064554962716672 +1662064555007717632 +1662064555049718528 +1662064555088719360 +1662064555130720256 +1662064555172721152 +1662064555214722048 +1662064555256722944 +1662064555301723904 +1662064555346724864 +1662064555391725824 +1662064555433726720 +1662064555475727616 +1662064555514728448 +1662064555571729664 +1662064555613730560 +1662064555655731456 +1662064555703732480 +1662064555748733440 +1662064555790734336 +1662064555832735232 +1662064555874736128 +1662064555919737088 +1662064555961737984 +1662064556006738944 +1662064556048739840 +1662064556093740800 +1662064556132741632 +1662064556174742528 +1662064556219743488 +1662064556264744448 +1662064556309745408 +1662064556357746432 +1662064556405747456 +1662064556450748416 +1662064556489749248 +1662064556534750208 +1662064556582751232 +1662064556627752192 +1662064556669753088 +1662064556711753984 +1662064556756754944 +1662064556798755840 +1662064556843756800 +1662064556885757696 +1662064556933758720 +1662064556969759488 +1662064557008760320 +1662064557047761152 +1662064557089762048 +1662064557131762944 +1662064557173763840 +1662064557212764672 +1662064557260765696 +1662064557305766656 +1662064557347767552 +1662064557383768320 +1662064557422769152 +1662064557467770112 +1662064557515771136 +1662064557557772032 +1662064557599772928 +1662064557638773760 +1662064557683774720 +1662064557728775680 +1662064557773776640 +1662064557818777600 +1662064557860778496 +1662064557902779392 +1662064557941780224 +1662064557983781120 +1662064558028782080 +1662064558067782912 +1662064558109783808 +1662064558148784640 +1662064558190785536 +1662064558232786432 +1662064558277787392 +1662064558322788352 +1662064558364789248 +1662064558409790208 +1662064558457791232 +1662064558499792128 +1662064558538792960 +1662064558583793920 +1662064558631794944 +1662064558673795840 +1662064558715796736 +1662064558757797632 +1662064558799798528 +1662064558847799552 +1662064558886800384 +1662064558928801280 +1662064558973802240 +1662064559018803200 +1662064559063804160 +1662064559108805120 +1662064559147805952 +1662064559189806848 +1662064559234807808 +1662064559276808704 +1662064559312809472 +1662064559354810368 +1662064559399811328 +1662064559441812224 +1662064559489813248 +1662064559534814208 +1662064559576815104 +1662064559618816000 +1662064559663816960 +1662064559705817856 +1662064559744818688 +1662064559786819584 +1662064559828820480 +1662064559867821312 +1662064559915822336 +1662064559957823232 +1662064559999824128 +1662064560044825088 +1662064560089826048 +1662064560134827008 +1662064560176827904 +1662064560218828800 +1662064560260829696 +1662064560299830528 +1662064560338831360 +1662064560377832192 +1662064560416833024 +1662064560458833920 +1662064560503834880 +1662064560545835776 +1662064560587836672 +1662064560632837632 +1662064560671838464 +1662064560716839424 +1662064560761840384 +1662064560803841280 +1662064560848842240 +1662064560893843200 +1662064560932844032 +1662064560968844800 +1662064561010845696 +1662064561055846656 +1662064561094847488 +1662064561136848384 +1662064561184849408 +1662064561220850176 +1662064561265851136 +1662064561310852096 +1662064561352852992 +1662064561397853952 +1662064561436854784 +1662064561478855680 +1662064561523856640 +1662064561568857600 +1662064561607858432 +1662064561652859392 +1662064561691860224 +1662064561733861120 +1662064561775862016 +1662064561817862912 +1662064561859863808 +1662064561901864704 +1662064561943865600 +1662064561988866560 +1662064562033867520 +1662064562075868416 +1662064562120869376 +1662064562162870272 +1662064562201871104 +1662064562243872000 +1662064562285872896 +1662064562327873792 +1662064562372874752 +1662064562417875712 +1662064562462876672 +1662064562510877696 +1662064562552878592 +1662064562594879488 +1662064562636880384 +1662064562681881344 +1662064562726882304 +1662064562768883200 +1662064562816884224 +1662064562861885184 +1662064562903886080 +1662064562948887040 +1662064562996888064 +1662064563038888960 +1662064563080889856 +1662064563122890752 +1662064563164891648 +1662064563209892608 +1662064563248893440 +1662064563290894336 +1662064563332895232 +1662064563374896128 +1662064563416897024 +1662064563461897984 +1662064563503898880 +1662064563545899776 +1662064563590900736 +1662064563632901632 +1662064563674902528 +1662064563719903488 +1662064563767904512 +1662064563806905344 +1662064563848906240 +1662064563887907072 +1662064563929907968 +1662064563971908864 +1662064564010909696 +1662064564052910592 +1662064564097911552 +1662064564139912448 +1662064564184913408 +1662064564226914304 +1662064564271915264 +1662064564313916160 +1662064564352916992 +1662064564397917952 +1662064564439918848 +1662064564484919808 +1662064564529920768 +1662064564571921664 +1662064564616922624 +1662064564658923520 +1662064564703924480 +1662064564745925376 +1662064564790926336 +1662064564832927232 +1662064564871928064 +1662064564913928960 +1662064564958929920 +1662064565000930816 +1662064565039931648 +1662064565081932544 +1662064565126933504 +1662064565171934464 +1662064565210935296 +1662064565255936256 +1662064565297937152 +1662064565339938048 +1662064565381938944 +1662064565426939904 +1662064565468940800 +1662064565510941696 +1662064565552942592 +1662064565594943488 +1662064565639944448 +1662064565681945344 +1662064565723946240 +1662064565768947200 +1662064565807948032 +1662064565849948928 +1662064565891949824 +1662064565933950720 +1662064565978951680 +1662064566020952576 +1662064566062953472 +1662064566104954368 +1662064566143955200 +1662064566188956160 +1662064566230957056 +1662064566263957760 +1662064566308958720 +1662064566353959680 +1662064566398960640 +1662064566440961536 +1662064566482962432 +1662064566527963392 +1662064566569964288 +1662064566617965312 +1662064566659966208 +1662064566701967104 +1662064566743968000 +1662064566785968896 +1662064566827969792 +1662064566872970752 +1662064566914971648 +1662064566959972608 +1662064567004973568 +1662064567046974464 +1662064567088975360 +1662064567133976320 +1662064567172977152 +1662064567214978048 +1662064567259979008 +1662064567298979840 +1662064567343980800 +1662064567388981760 +1662064567430982656 +1662064567472983552 +1662064567511984384 +1662064567556985344 +1662064567592986112 +1662064567634987008 +1662064567682988032 +1662064567721988864 +1662064567757989632 +1662064567799990528 +1662064567838991360 +1662064567880992256 +1662064567925993216 +1662064567964994048 +1662064568006994944 +1662064568051995904 +1662064568090996736 +1662064568132997632 +1662064568177998592 +1662064568222999552 +1662064568256000256 +1662064568301001216 +1662064568343002112 +1662064568385003008 +1662064568424003840 +1662064568466004736 +1662064568511005696 +1662064568553006592 +1662064568598007552 +1662064568640008448 +1662064568685009408 +1662064568724010240 +1662064568766011136 +1662064568811012096 +1662064568853012992 +1662064568898013952 +1662064568943014912 +1662064568988015872 +1662064569027016704 +1662064569069017600 +1662064569108018432 +1662064569150019328 +1662064569195020288 +1662064569234021120 +1662064569279022080 +1662064569324023040 +1662064569366023936 +1662064569411024896 +1662064569453025792 +1662064569498026752 +1662064569543027712 +1662064569582028544 +1662064569630029568 +1662064569672030464 +1662064569717031424 +1662064569759032320 +1662064569801033216 +1662064569837033984 +1662064569879034880 +1662064569927035904 +1662064569969036800 +1662064570011037696 +1662064570056038656 +1662064570101039616 +1662064570146040576 +1662064570188041472 +1662064570230042368 +1662064570275043328 +1662064570317044224 +1662064570359045120 +1662064570398045952 +1662064570443046912 +1662064570485047808 +1662064570527048704 +1662064570569049600 +1662064570614050560 +1662064570659051520 +1662064570701052416 +1662064570740053248 +1662064570782054144 +1662064570827055104 +1662064570869056000 +1662064570914056960 +1662064570959057920 +1662064571001058816 +1662064571043059712 +1662064571079060480 +1662064571124061440 +1662064571169062400 +1662064571211063296 +1662064571253064192 +1662064571298065152 +1662064571343066112 +1662064571394067200 +1662064571433068032 +1662064571478068992 +1662064571520069888 +1662064571565070848 +1662064571610071808 +1662064571652072704 +1662064571694073600 +1662064571736074496 +1662064571784075520 +1662064571829076480 +1662064571877077504 +1662064571919078400 +1662064571970079488 +1662064572012080384 +1662064572060081408 +1662064572102082304 +1662064572144083200 +1662064572186084096 +1662064572225084928 +1662064572267085824 +1662064572309086720 +1662064572357087744 +1662064572399088640 +1662064572444089600 +1662064572492090624 +1662064572540091648 +1662064572588092672 +1662064572630093568 +1662064572669094400 +1662064572714095360 +1662064572759096320 +1662064572801097216 +1662064572840098048 +1662064572882098944 +1662064572921099776 +1662064572966100736 +1662064573008101632 +1662064573050102528 +1662064573092103424 +1662064573134104320 +1662064573176105216 +1662064573215106048 +1662064573257106944 +1662064573299107840 +1662064573341108736 +1662064573383109632 +1662064573422110464 +1662064573464111360 +1662064573509112320 +1662064573545113088 +1662064573587113984 +1662064573629114880 +1662064573671115776 +1662064573710116608 +1662064573752117504 +1662064573794118400 +1662064573836119296 +1662064573878120192 +1662064573917121024 +1662064573959121920 +1662064574004122880 +1662064574049123840 +1662064574088124672 +1662064574133125632 +1662064574175126528 +1662064574220127488 +1662064574265128448 +1662064574304129280 +1662064574343130112 +1662064574388131072 +1662064574430131968 +1662064574475132928 +1662064574520133888 +1662064574556134656 +1662064574595135488 +1662064574637136384 +1662064574679137280 +1662064574721138176 +1662064574769139200 +1662064574811140096 +1662064574856141056 +1662064574898141952 +1662064574934142720 +1662064574970143488 +1662064575015144448 +1662064575057145344 +1662064575099146240 +1662064575144147200 +1662064575189148160 +1662064575231149056 +1662064575273149952 +1662064575318150912 +1662064575363151872 +1662064575408152832 +1662064575450153728 +1662064575489154560 +1662064575531155456 +1662064575579156480 +1662064575624157440 +1662064575663158272 +1662064575711159296 +1662064575756160256 +1662064575801161216 +1662064575840162048 +1662064575882162944 +1662064575924163840 +1662064575963164672 +1662064576008165632 +1662064576050166528 +1662064576095167488 +1662064576137168384 +1662064576182169344 +1662064576224170240 +1662064576263171072 +1662064576302171904 +1662064576347172864 +1662064576392173824 +1662064576434174720 +1662064576476175616 +1662064576518176512 +1662064576560177408 +1662064576608178432 +1662064576650179328 +1662064576701180416 +1662064576743181312 +1662064576782182144 +1662064576824183040 +1662064576866183936 +1662064576908184832 +1662064576950185728 +1662064576995186688 +1662064577034187520 +1662064577079188480 +1662064577118189312 +1662064577163190272 +1662064577205191168 +1662064577247192064 +1662064577289192960 +1662064577331193856 +1662064577373194752 +1662064577415195648 +1662064577460196608 +1662064577505197568 +1662064577547198464 +1662064577592199424 +1662064577634200320 +1662064577676201216 +1662064577718202112 +1662064577757202944 +1662064577799203840 +1662064577841204736 +1662064577886205696 +1662064577928206592 +1662064577973207552 +1662064578012208384 +1662064578051209216 +1662064578090210048 +1662064578132210944 +1662064578174211840 +1662064578219212800 +1662064578258213632 +1662064578306214656 +1662064578348215552 +1662064578393216512 +1662064578441217536 +1662064578489218560 +1662064578534219520 +1662064578576220416 +1662064578615221248 +1662064578657222144 +1662064578699223040 +1662064578741223936 +1662064578786224896 +1662064578828225792 +1662064578867226624 +1662064578912227584 +1662064578954228480 +1662064578996229376 +1662064579041230336 +1662064579080231168 +1662064579122232064 +1662064579161232896 +1662064579203233792 +1662064579248234752 +1662064579287235584 +1662064579329236480 +1662064579374237440 +1662064579422238464 +1662064579470239488 +1662064579515240448 +1662064579557241344 +1662064579599242240 +1662064579638243072 +1662064579680243968 +1662064579728244992 +1662064579773245952 +1662064579815246848 +1662064579860247808 +1662064579902248704 +1662064579944249600 +1662064579986250496 +1662064580028251392 +1662064580067252224 +1662064580112253184 +1662064580151254016 +1662064580190254848 +1662064580229255680 +1662064580271256576 +1662064580310257408 +1662064580352258304 +1662064580394259200 +1662064580442260224 +1662064580484261120 +1662064580526262016 +1662064580568262912 +1662064580610263808 +1662064580655264768 +1662064580697265664 +1662064580739266560 +1662064580781267456 +1662064580823268352 +1662064580868269312 +1662064580916270336 +1662064580955271168 +1662064581000272128 +1662064581045273088 +1662064581087273984 +1662064581135275008 +1662064581177275904 +1662064581222276864 +1662064581267277824 +1662064581312278784 +1662064581357279744 +1662064581399280640 +1662064581441281536 +1662064581489282560 +1662064581531283456 +1662064581564284160 +1662064581606285056 +1662064581651286016 +1662064581690286848 +1662064581732287744 +1662064581777288704 +1662064581816289536 +1662064581861290496 +1662064581903291392 +1662064581945292288 +1662064581987293184 +1662064582032294144 +1662064582068294912 +1662064582113295872 +1662064582152296704 +1662064582194297600 +1662064582239298560 +1662064582278299392 +1662064582320300288 +1662064582365301248 +1662064582404302080 +1662064582446302976 +1662064582485303808 +1662064582536304896 +1662064582578305792 +1662064582620306688 +1662064582665307648 +1662064582707308544 +1662064582752309504 +1662064582794310400 +1662064582839311360 +1662064582881312256 +1662064582923313152 +1662064582965314048 +1662064583007314944 +1662064583058316032 +1662064583100316928 +1662064583145317888 +1662064583187318784 +1662064583229319680 +1662064583274320640 +1662064583319321600 +1662064583364322560 +1662064583409323520 +1662064583454324480 +1662064583499325440 +1662064583544326400 +1662064583589327360 +1662064583631328256 +1662064583676329216 +1662064583715330048 +1662064583760331008 +1662064583802331904 +1662064583847332864 +1662064583886333696 +1662064583928334592 +1662064583973335552 +1662064584018336512 +1662064584063337472 +1662064584102338304 +1662064584141339136 +1662064584183340032 +1662064584222340864 +1662064584264341760 +1662064584309342720 +1662064584351343616 +1662064584393344512 +1662064584435345408 +1662064584477346304 +1662064584519347200 +1662064584561348096 +1662064584600348928 +1662064584645349888 +1662064584690350848 +1662064584729351680 +1662064584774352640 +1662064584816353536 +1662064584861354496 +1662064584903355392 +1662064584945356288 +1662064584990357248 +1662064585032358144 +1662064585074359040 +1662064585116359936 +1662064585164360960 +1662064585206361856 +1662064585248362752 +1662064585293363712 +1662064585332364544 +1662064585377365504 +1662064585419366400 +1662064585464367360 +1662064585509368320 +1662064585557369344 +1662064585599370240 +1662064585641371136 +1662064585686372096 +1662064585731373056 +1662064585779374080 +1662064585824375040 +1662064585866375936 +1662064585914376960 +1662064585953377792 +1662064586001378816 +1662064586043379712 +1662064586088380672 +1662064586133381632 +1662064586175382528 +1662064586217383424 +1662064586262384384 +1662064586307385344 +1662064586352386304 +1662064586394387200 +1662064586442388224 +1662064586484389120 +1662064586526390016 +1662064586574391040 +1662064586619392000 +1662064586664392960 +1662064586706393856 +1662064586748394752 +1662064586790395648 +1662064586835396608 +1662064586874397440 +1662064586919398400 +1662064586964399360 +1662064587006400256 +1662064587048401152 +1662064587093402112 +1662064587135403008 +1662064587180403968 +1662064587225404928 +1662064587267405824 +1662064587312406784 +1662064587357407744 +1662064587396408576 +1662064587441409536 +1662064587483410432 +1662064587531411456 +1662064587576412416 +1662064587621413376 +1662064587666414336 +1662064587708415232 +1662064587750416128 +1662064587798417152 +1662064587840418048 +1662064587882418944 +1662064587921419776 +1662064587963420672 +1662064588005421568 +1662064588041422336 +1662064588083423232 +1662064588122424064 +1662064588173425152 +1662064588212425984 +1662064588257426944 +1662064588299427840 +1662064588341428736 +1662064588386429696 +1662064588431430656 +1662064588476431616 +1662064588521432576 +1662064588563433472 +1662064588608434432 +1662064588647435264 +1662064588689436160 +1662064588734437120 +1662064588776438016 +1662064588815438848 +1662064588860439808 +1662064588902440704 +1662064588938441472 +1662064588983442432 +1662064589025443328 +1662064589067444224 +1662064589112445184 +1662064589154446080 +1662064589196446976 +1662064589244448000 +1662064589280448768 +1662064589322449664 +1662064589364450560 +1662064589406451456 +1662064589445452288 +1662064589487453184 +1662064589532454144 +1662064589571454976 +1662064589613455872 +1662064589658456832 +1662064589697457664 +1662064589742458624 +1662064589781459456 +1662064589823460352 +1662064589865461248 +1662064589907462144 +1662064589949463040 +1662064589994464000 +1662064590036464896 +1662064590081465856 +1662064590123466752 +1662064590168467712 +1662064590210468608 +1662064590255469568 +1662064590300470528 +1662064590348471552 +1662064590390472448 +1662064590435473408 +1662064590477474304 +1662064590516475136 +1662064590552475904 +1662064590594476800 +1662064590639477760 +1662064590687478784 +1662064590723479552 +1662064590762480384 +1662064590810481408 +1662064590849482240 +1662064590894483200 +1662064590939484160 +1662064590981485056 +1662064591023485952 +1662064591065486848 +1662064591107487744 +1662064591158488832 +1662064591206489856 +1662064591254490880 +1662064591296491776 +1662064591344492800 +1662064591389493760 +1662064591431494656 +1662064591479495680 +1662064591524496640 +1662064591569497600 +1662064591611498496 +1662064591650499328 +1662064591689500160 +1662064591734501120 +1662064591776502016 +1662064591821502976 +1662064591863503872 +1662064591905504768 +1662064591950505728 +1662064591992506624 +1662064592037507584 +1662064592079508480 +1662064592124509440 +1662064592163510272 +1662064592202511104 +1662064592247512064 +1662064592289512960 +1662064592328513792 +1662064592370514688 +1662064592412515584 +1662064592451516416 +1662064592490517248 +1662064592532518144 +1662064592577519104 +1662064592622520064 +1662064592661520896 +1662064592706521856 +1662064592748522752 +1662064592790523648 +1662064592829524480 +1662064592871525376 +1662064592913526272 +1662064592955527168 +1662064593000528128 +1662064593045529088 +1662064593087529984 +1662064593129530880 +1662064593168531712 +1662064593210532608 +1662064593252533504 +1662064593297534464 +1662064593342535424 +1662064593384536320 +1662064593429537280 +1662064593468538112 +1662064593510539008 +1662064593555539968 +1662064593600540928 +1662064593648541952 +1662064593687542784 +1662064593732543744 +1662064593771544576 +1662064593816545536 +1662064593861546496 +1662064593903547392 +1662064593942548224 +1662064593984549120 +1662064594026550016 +1662064594071550976 +1662064594113551872 +1662064594161552896 +1662064594206553856 +1662064594248554752 +1662064594287555584 +1662064594326556416 +1662064594371557376 +1662064594416558336 +1662064594452559104 +1662064594494560000 +1662064594533560832 +1662064594578561792 +1662064594623562752 +1662064594665563648 +1662064594704564480 +1662064594746565376 +1662064594788566272 +1662064594830567168 +1662064594869568000 +1662064594908568832 +1662064594950569728 +1662064594995570688 +1662064595037571584 +1662064595076572416 +1662064595115573248 +1662064595157574144 +1662064595199575040 +1662064595244576000 +1662064595286576896 +1662064595331577856 +1662064595373578752 +1662064595415579648 +1662064595460580608 +1662064595502581504 +1662064595550582528 +1662064595592583424 +1662064595637584384 +1662064595676585216 +1662064595718586112 +1662064595757586944 +1662064595802587904 +1662064595847588864 +1662064595886589696 +1662064595925590528 +1662064595967591424 +1662064596012592384 +1662064596057593344 +1662064596099594240 +1662064596141595136 +1662064596183596032 +1662064596228596992 +1662064596273597952 +1662064596312598784 +1662064596357599744 +1662064596402600704 +1662064596441601536 +1662064596483602432 +1662064596525603328 +1662064596567604224 +1662064596606605056 +1662064596648605952 +1662064596687606784 +1662064596729607680 +1662064596771608576 +1662064596816609536 +1662064596858610432 +1662064596900611328 +1662064596939612160 +1662064596975612928 +1662064597020613888 +1662064597068614912 +1662064597110615808 +1662064597155616768 +1662064597197617664 +1662064597239618560 +1662064597284619520 +1662064597326620416 +1662064597368621312 +1662064597410622208 +1662064597452623104 +1662064597497624064 +1662064597542625024 +1662064597584625920 +1662064597626626816 +1662064597668627712 +1662064597707628544 +1662064597749629440 +1662064597788630272 +1662064597836631296 +1662064597878632192 +1662064597920633088 +1662064597962633984 +1662064598010635008 +1662064598052635904 +1662064598097636864 +1662064598139637760 +1662064598175638528 +1662064598220639488 +1662064598259640320 +1662064598301641216 +1662064598346642176 +1662064598391643136 +1662064598433644032 +1662064598481645056 +1662064598520645888 +1662064598559646720 +1662064598601647616 +1662064598643648512 +1662064598685649408 +1662064598727650304 +1662064598772651264 +1662064598814652160 +1662064598859653120 +1662064598901654016 +1662064598943654912 +1662064598985655808 +1662064599027656704 +1662064599069657600 +1662064599114658560 +1662064599156659456 +1662064599201660416 +1662064599243661312 +1662064599288662272 +1662064599330663168 +1662064599372664064 +1662064599420665088 +1662064599465666048 +1662064599510667008 +1662064599552667904 +1662064599591668736 +1662064599639669760 +1662064599681670656 +1662064599723671552 +1662064599771672576 +1662064599810673408 +1662064599852674304 +1662064599900675328 +1662064599939676160 +1662064599981677056 +1662064600026678016 +1662064600071678976 +1662064600113679872 +1662064600158680832 +1662064600200681728 +1662064600245682688 +1662064600287683584 +1662064600329684480 +1662064600371685376 +1662064600416686336 +1662064600458687232 +1662064600497688064 +1662064600539688960 +1662064600581689856 +1662064600623690752 +1662064600668691712 +1662064600713692672 +1662064600761693696 +1662064600806694656 +1662064600851695616 +1662064600899696640 +1662064600947697664 +1662064600989698560 +1662064601031699456 +1662064601079700480 +1662064601124701440 +1662064601172702464 +1662064601217703424 +1662064601262704384 +1662064601307705344 +1662064601349706240 +1662064601388707072 +1662064601424707840 +1662064601466708736 +1662064601511709696 +1662064601550710528 +1662064601595711488 +1662064601640712448 +1662064601685713408 +1662064601727714304 +1662064601769715200 +1662064601811716096 +1662064601853716992 +1662064601901718016 +1662064601943718912 +1662064601988719872 +1662064602036720896 +1662064602078721792 +1662064602120722688 +1662064602168723712 +1662064602210724608 +1662064602249725440 +1662064602294726400 +1662064602333727232 +1662064602375728128 +1662064602414728960 +1662064602456729856 +1662064602495730688 +1662064602546731776 +1662064602591732736 +1662064602633733632 +1662064602675734528 +1662064602714735360 +1662064602762736384 +1662064602807737344 +1662064602846738176 +1662064602888739072 +1662064602930739968 +1662064602972740864 +1662064603017741824 +1662064603056742656 +1662064603095743488 +1662064603140744448 +1662064603182745344 +1662064603218746112 +1662064603269747200 +1662064603308748032 +1662064603347748864 +1662064603389749760 +1662064603434750720 +1662064603479751680 +1662064603521752576 +1662064603563753472 +1662064603605754368 +1662064603650755328 +1662064603689756160 +1662064603740757248 +1662064603782758144 +1662064603827759104 +1662064603869760000 +1662064603914760960 +1662064603950761728 +1662064603992762624 +1662064604034763520 +1662064604076764416 +1662064604118765312 +1662064604160766208 +1662064604208767232 +1662064604247768064 +1662064604289768960 +1662064604337769984 +1662064604379770880 +1662064604421771776 +1662064604463772672 +1662064604508773632 +1662064604550774528 +1662064604595775488 +1662064604640776448 +1662064604682777344 +1662064604724778240 +1662064604769779200 +1662064604814780160 +1662064604853780992 +1662064604901782016 +1662064604943782912 +1662064604985783808 +1662064605027784704 +1662064605072785664 +1662064605114786560 +1662064605156787456 +1662064605198788352 +1662064605240789248 +1662064605282790144 +1662064605324791040 +1662064605366791936 +1662064605411792896 +1662064605462793984 +1662064605510795008 +1662064605552795904 +1662064605591796736 +1662064605630797568 +1662064605672798464 +1662064605714799360 +1662064605765800448 +1662064605810801408 +1662064605852802304 +1662064605897803264 +1662064605936804096 +1662064605978804992 +1662064606020805888 +1662064606065806848 +1662064606110807808 +1662064606155808768 +1662064606197809664 +1662064606242810624 +1662064606287811584 +1662064606329812480 +1662064606368813312 +1662064606413814272 +1662064606452815104 +1662064606491815936 +1662064606533816832 +1662064606578817792 +1662064606620818688 +1662064606668819712 +1662064606710820608 +1662064606752821504 +1662064606794822400 +1662064606836823296 +1662064606881824256 +1662064606923825152 +1662064606968826112 +1662064607010827008 +1662064607055827968 +1662064607100828928 +1662064607142829824 +1662064607187830784 +1662064607229831680 +1662064607271832576 +1662064607316833536 +1662064607358834432 +1662064607406835456 +1662064607448836352 +1662064607493837312 +1662064607535838208 +1662064607577839104 +1662064607619840000 +1662064607664840960 +1662064607709841920 +1662064607751842816 +1662064607790843648 +1662064607829844480 +1662064607871845376 +1662064607910846208 +1662064607958847232 +1662064608003848192 +1662064608048849152 +1662064608090850048 +1662064608135851008 +1662064608177851904 +1662064608219852800 +1662064608267853824 +1662064608312854784 +1662064608354855680 +1662064608396856576 +1662064608441857536 +1662064608486858496 +1662064608528859392 +1662064608570860288 +1662064608615861248 +1662064608657862144 +1662064608699863040 +1662064608744864000 +1662064608786864896 +1662064608828865792 +1662064608870866688 +1662064608915867648 +1662064608957868544 +1662064608999869440 +1662064609038870272 +1662064609083871232 +1662064609128872192 +1662064609170873088 +1662064609212873984 +1662064609254874880 +1662064609299875840 +1662064609341876736 +1662064609386877696 +1662064609428878592 +1662064609470879488 +1662064609515880448 +1662064609560881408 +1662064609605882368 +1662064609653883392 +1662064609698884352 +1662064609740885248 +1662064609785886208 +1662064609827887104 +1662064609869888000 +1662064609917889024 +1662064609956889856 +1662064610001890816 +1662064610043891712 +1662064610082892544 +1662064610124893440 +1662064610166894336 +1662064610208895232 +1662064610250896128 +1662064610292897024 +1662064610334897920 +1662064610376898816 +1662064610418899712 +1662064610463900672 +1662064610505901568 +1662064610547902464 +1662064610589903360 +1662064610634904320 +1662064610676905216 +1662064610715906048 +1662064610760907008 +1662064610805907968 +1662064610850908928 +1662064610889909760 +1662064610931910656 +1662064610976911616 +1662064611021912576 +1662064611066913536 +1662064611111914496 +1662064611153915392 +1662064611198916352 +1662064611240917248 +1662064611282918144 +1662064611321918976 +1662064611363919872 +1662064611402920704 +1662064611447921664 +1662064611495922688 +1662064611537923584 +1662064611579924480 +1662064611627925504 +1662064611666926336 +1662064611708927232 +1662064611753928192 +1662064611795929088 +1662064611843930112 +1662064611885931008 +1662064611924931840 +1662064611969932800 +1662064612017933824 +1662064612059934720 +1662064612104935680 +1662064612149936640 +1662064612194937600 +1662064612233938432 +1662064612278939392 +1662064612326940416 +1662064612371941376 +1662064612410942208 +1662064612452943104 +1662064612491943936 +1662064612530944768 +1662064612569945600 +1662064612614946560 +1662064612659947520 +1662064612704948480 +1662064612749949440 +1662064612788950272 +1662064612833951232 +1662064612875952128 +1662064612917953024 +1662064612956953856 +1662064613001954816 +1662064613040955648 +1662064613085956608 +1662064613130957568 +1662064613178958592 +1662064613220959488 +1662064613262960384 +1662064613304961280 +1662064613346962176 +1662064613385963008 +1662064613430963968 +1662064613469964800 +1662064613511965696 +1662064613553966592 +1662064613595967488 +1662064613634968320 +1662064613673969152 +1662064613715970048 +1662064613757970944 +1662064613805971968 +1662064613847972864 +1662064613886973696 +1662064613925974528 +1662064613976975616 +1662064614015976448 +1662064614057977344 +1662064614102978304 +1662064614144979200 +1662064614186980096 +1662064614228980992 +1662064614267981824 +1662064614318982912 +1662064614360983808 +1662064614405984768 +1662064614447985664 +1662064614489986560 +1662064614531987456 +1662064614570988288 +1662064614609989120 +1662064614654990080 +1662064614696990976 +1662064614741991936 +1662064614783992832 +1662064614828993792 +1662064614870994688 +1662064614915995648 +1662064614960996608 +1662064615002997504 +1662064615044998400 +1662064615086999296 +1662064615132000256 +1662064615177001216 +1662064615219002112 +1662064615261003008 +1662064615303003904 +1662064615345004800 +1662064615384005632 +1662064615423006464 +1662064615462007296 +1662064615498008064 +1662064615546009088 +1662064615588009984 +1662064615630010880 +1662064615675011840 +1662064615714012672 +1662064615756013568 +1662064615798014464 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt new file mode 100644 index 0000000000..51983432b0 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt @@ -0,0 +1,2076 @@ +1662125073430662912 +1662125073472663808 +1662125073511664640 +1662125073553665536 +1662125073598666496 +1662125073643667456 +1662125073688668416 +1662125073733669376 +1662125073781670400 +1662125073823671296 +1662125073865672192 +1662125073907673088 +1662125073952674048 +1662125073997675008 +1662125074042675968 +1662125074087676928 +1662125074132677888 +1662125074174678784 +1662125074216679680 +1662125074258680576 +1662125074303681536 +1662125074345682432 +1662125074387683328 +1662125074429684224 +1662125074474685184 +1662125074519686144 +1662125074564687104 +1662125074606688000 +1662125074651688960 +1662125074696689920 +1662125074741690880 +1662125074789691904 +1662125074831692800 +1662125074879693824 +1662125074918694656 +1662125074960695552 +1662125074999696384 +1662125075044697344 +1662125075086698240 +1662125075131699200 +1662125075176700160 +1662125075224701184 +1662125075269702144 +1662125075308702976 +1662125075347703808 +1662125075389704704 +1662125075440705792 +1662125075482706688 +1662125075524707584 +1662125075569708544 +1662125075617709568 +1662125075659710464 +1662125075701711360 +1662125075746712320 +1662125075788713216 +1662125075830714112 +1662125075872715008 +1662125075917715968 +1662125075956716800 +1662125076001717760 +1662125076046718720 +1662125076091719680 +1662125076139720704 +1662125076181721600 +1662125076223722496 +1662125076265723392 +1662125076307724288 +1662125076358725376 +1662125076400726272 +1662125076445727232 +1662125076490728192 +1662125076538729216 +1662125076580730112 +1662125076625731072 +1662125076670732032 +1662125076712732928 +1662125076754733824 +1662125076796734720 +1662125076847735808 +1662125076889736704 +1662125076934737664 +1662125076976738560 +1662125077024739584 +1662125077072740608 +1662125077114741504 +1662125077156742400 +1662125077195743232 +1662125077237744128 +1662125077279745024 +1662125077327746048 +1662125077366746880 +1662125077411747840 +1662125077453748736 +1662125077498749696 +1662125077540750592 +1662125077582751488 +1662125077627752448 +1662125077669753344 +1662125077711754240 +1662125077753755136 +1662125077795756032 +1662125077837756928 +1662125077879757824 +1662125077924758784 +1662125077969759744 +1662125078011760640 +1662125078056761600 +1662125078098762496 +1662125078143763456 +1662125078188764416 +1662125078227765248 +1662125078272766208 +1662125078314767104 +1662125078359768064 +1662125078401768960 +1662125078446769920 +1662125078494770944 +1662125078539771904 +1662125078587772928 +1662125078635773952 +1662125078677774848 +1662125078725775872 +1662125078767776768 +1662125078809777664 +1662125078848778496 +1662125078896779520 +1662125078938780416 +1662125078986781440 +1662125079025782272 +1662125079070783232 +1662125079112784128 +1662125079157785088 +1662125079199785984 +1662125079244786944 +1662125079289787904 +1662125079331788800 +1662125079373789696 +1662125079412790528 +1662125079457791488 +1662125079502792448 +1662125079541793280 +1662125079589794304 +1662125079625795072 +1662125079676796160 +1662125079715796992 +1662125079760797952 +1662125079802798848 +1662125079847799808 +1662125079892800768 +1662125079934801664 +1662125079976802560 +1662125080024803584 +1662125080066804480 +1662125080114805504 +1662125080162806528 +1662125080204807424 +1662125080246808320 +1662125080291809280 +1662125080336810240 +1662125080381811200 +1662125080423812096 +1662125080468813056 +1662125080510813952 +1662125080552814848 +1662125080597815808 +1662125080639816704 +1662125080684817664 +1662125080729818624 +1662125080771819520 +1662125080819820544 +1662125080861821440 +1662125080900822272 +1662125080948823296 +1662125080990824192 +1662125081032825088 +1662125081080826112 +1662125081122827008 +1662125081164827904 +1662125081206828800 +1662125081248829696 +1662125081296830720 +1662125081338831616 +1662125081380832512 +1662125081425833472 +1662125081467834368 +1662125081515835392 +1662125081557836288 +1662125081605837312 +1662125081653838336 +1662125081698839296 +1662125081743840256 +1662125081788841216 +1662125081833842176 +1662125081872843008 +1662125081923844096 +1662125081965844992 +1662125082010845952 +1662125082055846912 +1662125082097847808 +1662125082136848640 +1662125082178849536 +1662125082217850368 +1662125082256851200 +1662125082298852096 +1662125082346853120 +1662125082388854016 +1662125082433854976 +1662125082475855872 +1662125082520856832 +1662125082565857792 +1662125082610858752 +1662125082652859648 +1662125082697860608 +1662125082742861568 +1662125082781862400 +1662125082820863232 +1662125082859864064 +1662125082901864960 +1662125082943865856 +1662125082982866688 +1662125083024867584 +1662125083066868480 +1662125083111869440 +1662125083159870464 +1662125083207871488 +1662125083249872384 +1662125083294873344 +1662125083336874240 +1662125083378875136 +1662125083420876032 +1662125083462876928 +1662125083510877952 +1662125083555878912 +1662125083597879808 +1662125083639880704 +1662125083684881664 +1662125083726882560 +1662125083774883584 +1662125083813884416 +1662125083855885312 +1662125083900886272 +1662125083942887168 +1662125083984888064 +1662125084026888960 +1662125084068889856 +1662125084113890816 +1662125084155891712 +1662125084200892672 +1662125084242893568 +1662125084284894464 +1662125084326895360 +1662125084371896320 +1662125084416897280 +1662125084464898304 +1662125084509899264 +1662125084557900288 +1662125084605901312 +1662125084653902336 +1662125084695903232 +1662125084737904128 +1662125084776904960 +1662125084818905856 +1662125084857906688 +1662125084899907584 +1662125084944908544 +1662125084989909504 +1662125085031910400 +1662125085076911360 +1662125085127912448 +1662125085169913344 +1662125085214914304 +1662125085259915264 +1662125085301916160 +1662125085346917120 +1662125085388918016 +1662125085439919104 +1662125085481920000 +1662125085523920896 +1662125085565921792 +1662125085604922624 +1662125085649923584 +1662125085694924544 +1662125085739925504 +1662125085781926400 +1662125085826927360 +1662125085868928256 +1662125085913929216 +1662125085955930112 +1662125086000931072 +1662125086045932032 +1662125086087932928 +1662125086126933760 +1662125086168934656 +1662125086210935552 +1662125086249936384 +1662125086291937280 +1662125086333938176 +1662125086378939136 +1662125086423940096 +1662125086468941056 +1662125086519942144 +1662125086558942976 +1662125086603943936 +1662125086648944896 +1662125086693945856 +1662125086744946944 +1662125086783947776 +1662125086825948672 +1662125086870949632 +1662125086909950464 +1662125086951951360 +1662125086993952256 +1662125087038953216 +1662125087083954176 +1662125087125955072 +1662125087170956032 +1662125087215956992 +1662125087257957888 +1662125087299958784 +1662125087341959680 +1662125087386960640 +1662125087428961536 +1662125087473962496 +1662125087515963392 +1662125087557964288 +1662125087599965184 +1662125087644966144 +1662125087686967040 +1662125087731968000 +1662125087773968896 +1662125087812969728 +1662125087857970688 +1662125087896971520 +1662125087938972416 +1662125087977973248 +1662125088016974080 +1662125088061975040 +1662125088100975872 +1662125088151976960 +1662125088196977920 +1662125088241978880 +1662125088283979776 +1662125088334980864 +1662125088376981760 +1662125088418982656 +1662125088466983680 +1662125088511984640 +1662125088553985536 +1662125088601986560 +1662125088643987456 +1662125088685988352 +1662125088727989248 +1662125088766990080 +1662125088811991040 +1662125088856992000 +1662125088898992896 +1662125088943993856 +1662125088982994688 +1662125089018995456 +1662125089063996416 +1662125089108997376 +1662125089150998272 +1662125089189999104 +1662125089232000000 +1662125089277000960 +1662125089322001920 +1662125089373003008 +1662125089415003904 +1662125089457004800 +1662125089499005696 +1662125089550006784 +1662125089598007808 +1662125089640008704 +1662125089682009600 +1662125089727010560 +1662125089772011520 +1662125089814012416 +1662125089856013312 +1662125089898014208 +1662125089946015232 +1662125089991016192 +1662125090033017088 +1662125090075017984 +1662125090123019008 +1662125090165019904 +1662125090204020736 +1662125090243021568 +1662125090282022400 +1662125090327023360 +1662125090366024192 +1662125090402024960 +1662125090447025920 +1662125090489026816 +1662125090528027648 +1662125090573028608 +1662125090618029568 +1662125090660030464 +1662125090705031424 +1662125090747032320 +1662125090789033216 +1662125090834034176 +1662125090879035136 +1662125090930036224 +1662125090975037184 +1662125091020038144 +1662125091065039104 +1662125091110040064 +1662125091155041024 +1662125091197041920 +1662125091239042816 +1662125091284043776 +1662125091326044672 +1662125091368045568 +1662125091419046656 +1662125091461047552 +1662125091506048512 +1662125091548049408 +1662125091593050368 +1662125091635051264 +1662125091677052160 +1662125091719053056 +1662125091761053952 +1662125091806054912 +1662125091845055744 +1662125091887056640 +1662125091929057536 +1662125091977058560 +1662125092022059520 +1662125092067060480 +1662125092106061312 +1662125092148062208 +1662125092193063168 +1662125092235064064 +1662125092277064960 +1662125092319065856 +1662125092361066752 +1662125092406067712 +1662125092451068672 +1662125092496069632 +1662125092535070464 +1662125092580071424 +1662125092622072320 +1662125092667073280 +1662125092709074176 +1662125092751075072 +1662125092796076032 +1662125092838076928 +1662125092883077888 +1662125092925078784 +1662125092967079680 +1662125093012080640 +1662125093054081536 +1662125093102082560 +1662125093141083392 +1662125093183084288 +1662125093219085056 +1662125093261085952 +1662125093303086848 +1662125093348087808 +1662125093393088768 +1662125093435089664 +1662125093477090560 +1662125093522091520 +1662125093564092416 +1662125093606093312 +1662125093648094208 +1662125093690095104 +1662125093732096000 +1662125093771096832 +1662125093816097792 +1662125093858098688 +1662125093900099584 +1662125093942100480 +1662125093981101312 +1662125094023102208 +1662125094065103104 +1662125094110104064 +1662125094152104960 +1662125094194105856 +1662125094239106816 +1662125094284107776 +1662125094329108736 +1662125094377109760 +1662125094422110720 +1662125094467111680 +1662125094506112512 +1662125094548113408 +1662125094590114304 +1662125094638115328 +1662125094680116224 +1662125094722117120 +1662125094770118144 +1662125094815119104 +1662125094860120064 +1662125094908121088 +1662125094950121984 +1662125094995122944 +1662125095040123904 +1662125095085124864 +1662125095127125760 +1662125095169126656 +1662125095214127616 +1662125095253128448 +1662125095298129408 +1662125095340130304 +1662125095382131200 +1662125095424132096 +1662125095475133184 +1662125095517134080 +1662125095568135168 +1662125095613136128 +1662125095649136896 +1662125095685137664 +1662125095727138560 +1662125095772139520 +1662125095817140480 +1662125095856141312 +1662125095901142272 +1662125095940143104 +1662125095985144064 +1662125096024144896 +1662125096069145856 +1662125096114146816 +1662125096159147776 +1662125096201148672 +1662125096246149632 +1662125096291150592 +1662125096336151552 +1662125096381152512 +1662125096423153408 +1662125096465154304 +1662125096510155264 +1662125096555156224 +1662125096600157184 +1662125096648158208 +1662125096693159168 +1662125096732160000 +1662125096780161024 +1662125096819161856 +1662125096870162944 +1662125096909163776 +1662125096951164672 +1662125096993165568 +1662125097035166464 +1662125097080167424 +1662125097125168384 +1662125097170169344 +1662125097212170240 +1662125097251171072 +1662125097296172032 +1662125097338172928 +1662125097383173888 +1662125097428174848 +1662125097467175680 +1662125097512176640 +1662125097554177536 +1662125097596178432 +1662125097638179328 +1662125097680180224 +1662125097722181120 +1662125097764182016 +1662125097806182912 +1662125097848183808 +1662125097899184896 +1662125097944185856 +1662125097992186880 +1662125098034187776 +1662125098076188672 +1662125098118189568 +1662125098160190464 +1662125098205191424 +1662125098247192320 +1662125098289193216 +1662125098328194048 +1662125098373195008 +1662125098415195904 +1662125098457196800 +1662125098502197760 +1662125098544198656 +1662125098586199552 +1662125098637200640 +1662125098682201600 +1662125098724202496 +1662125098772203520 +1662125098814204416 +1662125098850205184 +1662125098892206080 +1662125098937207040 +1662125098985208064 +1662125099027208960 +1662125099072209920 +1662125099114210816 +1662125099153211648 +1662125099195212544 +1662125099240213504 +1662125099282214400 +1662125099330215424 +1662125099378216448 +1662125099423217408 +1662125099468218368 +1662125099510219264 +1662125099555220224 +1662125099600221184 +1662125099645222144 +1662125099687223040 +1662125099732224000 +1662125099774224896 +1662125099816225792 +1662125099861226752 +1662125099906227712 +1662125099951228672 +1662125099996229632 +1662125100041230592 +1662125100083231488 +1662125100122232320 +1662125100161233152 +1662125100209234176 +1662125100251235072 +1662125100296236032 +1662125100338236928 +1662125100383237888 +1662125100428238848 +1662125100470239744 +1662125100515240704 +1662125100551241472 +1662125100596242432 +1662125100635243264 +1662125100680244224 +1662125100722245120 +1662125100764246016 +1662125100806246912 +1662125100845247744 +1662125100890248704 +1662125100932249600 +1662125100977250560 +1662125101016251392 +1662125101061252352 +1662125101103253248 +1662125101145254144 +1662125101187255040 +1662125101229255936 +1662125101271256832 +1662125101316257792 +1662125101364258816 +1662125101412259840 +1662125101457260800 +1662125101499261696 +1662125101541262592 +1662125101580263424 +1662125101625264384 +1662125101673265408 +1662125101715266304 +1662125101760267264 +1662125101802268160 +1662125101844269056 +1662125101892270080 +1662125101934270976 +1662125101979271936 +1662125102027272960 +1662125102072273920 +1662125102114274816 +1662125102162275840 +1662125102204276736 +1662125102240277504 +1662125102279278336 +1662125102318279168 +1662125102363280128 +1662125102405281024 +1662125102441281792 +1662125102480282624 +1662125102522283520 +1662125102567284480 +1662125102612285440 +1662125102654286336 +1662125102696287232 +1662125102735288064 +1662125102777288960 +1662125102828290048 +1662125102870290944 +1662125102918291968 +1662125102963292928 +1662125103008293888 +1662125103050294784 +1662125103092295680 +1662125103137296640 +1662125103179297536 +1662125103221298432 +1662125103269299456 +1662125103308300288 +1662125103356301312 +1662125103401302272 +1662125103446303232 +1662125103485304064 +1662125103524304896 +1662125103563305728 +1662125103602306560 +1662125103644307456 +1662125103686308352 +1662125103728309248 +1662125103770310144 +1662125103812311040 +1662125103854311936 +1662125103896312832 +1662125103938313728 +1662125103980314624 +1662125104022315520 +1662125104064316416 +1662125104109317376 +1662125104151318272 +1662125104196319232 +1662125104241320192 +1662125104286321152 +1662125104328322048 +1662125104370322944 +1662125104412323840 +1662125104457324800 +1662125104496325632 +1662125104541326592 +1662125104592327680 +1662125104637328640 +1662125104682329600 +1662125104724330496 +1662125104769331456 +1662125104814332416 +1662125104859333376 +1662125104901334272 +1662125104952335360 +1662125104994336256 +1662125105036337152 +1662125105078338048 +1662125105126339072 +1662125105168339968 +1662125105210340864 +1662125105252341760 +1662125105294342656 +1662125105336343552 +1662125105381344512 +1662125105423345408 +1662125105468346368 +1662125105510347264 +1662125105552348160 +1662125105603349248 +1662125105648350208 +1662125105690351104 +1662125105729351936 +1662125105774352896 +1662125105819353856 +1662125105861354752 +1662125105906355712 +1662125105957356800 +1662125106002357760 +1662125106044358656 +1662125106089359616 +1662125106137360640 +1662125106176361472 +1662125106218362368 +1662125106260363264 +1662125106305364224 +1662125106350365184 +1662125106395366144 +1662125106440367104 +1662125106485368064 +1662125106527368960 +1662125106566369792 +1662125106611370752 +1662125106656371712 +1662125106701372672 +1662125106743373568 +1662125106791374592 +1662125106833375488 +1662125106878376448 +1662125106917377280 +1662125106959378176 +1662125107004379136 +1662125107046380032 +1662125107085380864 +1662125107133381888 +1662125107172382720 +1662125107208383488 +1662125107253384448 +1662125107298385408 +1662125107346386432 +1662125107388387328 +1662125107430388224 +1662125107472389120 +1662125107514390016 +1662125107553390848 +1662125107595391744 +1662125107637392640 +1662125107679393536 +1662125107718394368 +1662125107760395264 +1662125107802396160 +1662125107850397184 +1662125107895398144 +1662125107937399040 +1662125107982400000 +1662125108027400960 +1662125108069401856 +1662125108111402752 +1662125108156403712 +1662125108198404608 +1662125108240405504 +1662125108285406464 +1662125108333407488 +1662125108378408448 +1662125108423409408 +1662125108468410368 +1662125108507411200 +1662125108549412096 +1662125108588412928 +1662125108633413888 +1662125108672414720 +1662125108723415808 +1662125108765416704 +1662125108804417536 +1662125108849418496 +1662125108888419328 +1662125108933420288 +1662125108978421248 +1662125109017422080 +1662125109059422976 +1662125109101423872 +1662125109140424704 +1662125109185425664 +1662125109227426560 +1662125109269427456 +1662125109314428416 +1662125109359429376 +1662125109395430144 +1662125109437431040 +1662125109479431936 +1662125109521432832 +1662125109560433664 +1662125109602434560 +1662125109641435392 +1662125109689436416 +1662125109731437312 +1662125109776438272 +1662125109821439232 +1662125109860440064 +1662125109902440960 +1662125109944441856 +1662125109989442816 +1662125110028443648 +1662125110073444608 +1662125110121445632 +1662125110160446464 +1662125110202447360 +1662125110244448256 +1662125110286449152 +1662125110331450112 +1662125110370450944 +1662125110412451840 +1662125110457452800 +1662125110499453696 +1662125110544454656 +1662125110589455616 +1662125110631456512 +1662125110673457408 +1662125110715458304 +1662125110760459264 +1662125110808460288 +1662125110850461184 +1662125110889462016 +1662125110937463040 +1662125110988464128 +1662125111030465024 +1662125111078466048 +1662125111120466944 +1662125111162467840 +1662125111201468672 +1662125111243469568 +1662125111288470528 +1662125111330471424 +1662125111375472384 +1662125111414473216 +1662125111459474176 +1662125111501475072 +1662125111543475968 +1662125111585476864 +1662125111627477760 +1662125111672478720 +1662125111714479616 +1662125111759480576 +1662125111801481472 +1662125111843482368 +1662125111888483328 +1662125111930484224 +1662125111972485120 +1662125112017486080 +1662125112062487040 +1662125112107488000 +1662125112155489024 +1662125112197489920 +1662125112236490752 +1662125112278491648 +1662125112323492608 +1662125112368493568 +1662125112410494464 +1662125112452495360 +1662125112500496384 +1662125112539497216 +1662125112581498112 +1662125112623499008 +1662125112665499904 +1662125112704500736 +1662125112755501824 +1662125112794502656 +1662125112836503552 +1662125112881504512 +1662125112929505536 +1662125112977506560 +1662125113019507456 +1662125113064508416 +1662125113106509312 +1662125113151510272 +1662125113196511232 +1662125113238512128 +1662125113283513088 +1662125113322513920 +1662125113367514880 +1662125113415515904 +1662125113454516736 +1662125113496517632 +1662125113538518528 +1662125113583519488 +1662125113628520448 +1662125113670521344 +1662125113718522368 +1662125113763523328 +1662125113811524352 +1662125113853525248 +1662125113895526144 +1662125113940527104 +1662125113982528000 +1662125114021528832 +1662125114060529664 +1662125114099530496 +1662125114141531392 +1662125114183532288 +1662125114222533120 +1662125114267534080 +1662125114312535040 +1662125114357536000 +1662125114399536896 +1662125114441537792 +1662125114483538688 +1662125114531539712 +1662125114582540800 +1662125114624541696 +1662125114666542592 +1662125114708543488 +1662125114750544384 +1662125114792545280 +1662125114834546176 +1662125114876547072 +1662125114924548096 +1662125114969549056 +1662125115020550144 +1662125115065551104 +1662125115104551936 +1662125115146552832 +1662125115188553728 +1662125115233554688 +1662125115278555648 +1662125115323556608 +1662125115368557568 +1662125115410558464 +1662125115455559424 +1662125115497560320 +1662125115542561280 +1662125115581562112 +1662125115620562944 +1662125115662563840 +1662125115701564672 +1662125115746565632 +1662125115788566528 +1662125115833567488 +1662125115878568448 +1662125115923569408 +1662125115965570304 +1662125116007571200 +1662125116049572096 +1662125116094573056 +1662125116130573824 +1662125116175574784 +1662125116220575744 +1662125116268576768 +1662125116310577664 +1662125116349578496 +1662125116391579392 +1662125116436580352 +1662125116481581312 +1662125116526582272 +1662125116571583232 +1662125116607584000 +1662125116649584896 +1662125116691585792 +1662125116736586752 +1662125116781587712 +1662125116823588608 +1662125116862589440 +1662125116904590336 +1662125116943591168 +1662125116982592000 +1662125117027592960 +1662125117072593920 +1662125117117594880 +1662125117156595712 +1662125117201596672 +1662125117237597440 +1662125117276598272 +1662125117321599232 +1662125117363600128 +1662125117405601024 +1662125117447601920 +1662125117492602880 +1662125117537603840 +1662125117579604736 +1662125117618605568 +1662125117663606528 +1662125117705607424 +1662125117744608256 +1662125117789609216 +1662125117828610048 +1662125117870610944 +1662125117918611968 +1662125117963612928 +1662125118005613824 +1662125118047614720 +1662125118089615616 +1662125118131616512 +1662125118173617408 +1662125118215618304 +1662125118260619264 +1662125118299620096 +1662125118341620992 +1662125118386621952 +1662125118425622784 +1662125118470623744 +1662125118509624576 +1662125118554625536 +1662125118599626496 +1662125118641627392 +1662125118683628288 +1662125118725629184 +1662125118767630080 +1662125118809630976 +1662125118854631936 +1662125118896632832 +1662125118941633792 +1662125118980634624 +1662125119022635520 +1662125119070636544 +1662125119115637504 +1662125119154638336 +1662125119196639232 +1662125119238640128 +1662125119277640960 +1662125119322641920 +1662125119370642944 +1662125119415643904 +1662125119460644864 +1662125119505645824 +1662125119547646720 +1662125119580647424 +1662125119625648384 +1662125119670649344 +1662125119712650240 +1662125119754651136 +1662125119802652160 +1662125119844653056 +1662125119886653952 +1662125119928654848 +1662125119970655744 +1662125120012656640 +1662125120057657600 +1662125120102658560 +1662125120150659584 +1662125120195660544 +1662125120240661504 +1662125120282662400 +1662125120324663296 +1662125120369664256 +1662125120417665280 +1662125120459666176 +1662125120507667200 +1662125120555668224 +1662125120597669120 +1662125120639670016 +1662125120681670912 +1662125120723671808 +1662125120765672704 +1662125120804673536 +1662125120846674432 +1662125120885675264 +1662125120927676160 +1662125120969677056 +1662125121011677952 +1662125121053678848 +1662125121095679744 +1662125121137680640 +1662125121185681664 +1662125121230682624 +1662125121269683456 +1662125121311684352 +1662125121353685248 +1662125121398686208 +1662125121437687040 +1662125121488688128 +1662125121530689024 +1662125121575689984 +1662125121617690880 +1662125121662691840 +1662125121704692736 +1662125121749693696 +1662125121791694592 +1662125121833695488 +1662125121875696384 +1662125121920697344 +1662125121962698240 +1662125122007699200 +1662125122049700096 +1662125122091700992 +1662125122133701888 +1662125122175702784 +1662125122217703680 +1662125122259704576 +1662125122301705472 +1662125122340706304 +1662125122385707264 +1662125122430708224 +1662125122469709056 +1662125122511709952 +1662125122556710912 +1662125122601711872 +1662125122643712768 +1662125122685713664 +1662125122736714752 +1662125122778715648 +1662125122820716544 +1662125122868717568 +1662125122910718464 +1662125122952719360 +1662125122991720192 +1662125123033721088 +1662125123075721984 +1662125123120722944 +1662125123162723840 +1662125123201724672 +1662125123243725568 +1662125123285726464 +1662125123324727296 +1662125123366728192 +1662125123408729088 +1662125123453730048 +1662125123501731072 +1662125123543731968 +1662125123585732864 +1662125123627733760 +1662125123669734656 +1662125123717735680 +1662125123762736640 +1662125123804737536 +1662125123852738560 +1662125123891739392 +1662125123936740352 +1662125123975741184 +1662125124020742144 +1662125124059742976 +1662125124104743936 +1662125124146744832 +1662125124194745856 +1662125124239746816 +1662125124281747712 +1662125124329748736 +1662125124368749568 +1662125124410750464 +1662125124452751360 +1662125124494752256 +1662125124536753152 +1662125124578754048 +1662125124620754944 +1662125124665755904 +1662125124707756800 +1662125124746757632 +1662125124791758592 +1662125124833759488 +1662125124869760256 +1662125124911761152 +1662125124956762112 +1662125124998763008 +1662125125040763904 +1662125125085764864 +1662125125127765760 +1662125125172766720 +1662125125214767616 +1662125125262768640 +1662125125304769536 +1662125125346770432 +1662125125385771264 +1662125125427772160 +1662125125472773120 +1662125125514774016 +1662125125559774976 +1662125125601775872 +1662125125652776960 +1662125125700777984 +1662125125742778880 +1662125125790779904 +1662125125841780992 +1662125125883781888 +1662125125925782784 +1662125125976783872 +1662125126021784832 +1662125126066785792 +1662125126111786752 +1662125126153787648 +1662125126192788480 +1662125126231789312 +1662125126279790336 +1662125126321791232 +1662125126366792192 +1662125126408793088 +1662125126447793920 +1662125126495794944 +1662125126537795840 +1662125126582796800 +1662125126627797760 +1662125126669798656 +1662125126714799616 +1662125126753800448 +1662125126798801408 +1662125126831802112 +1662125126873803008 +1662125126915803904 +1662125126957804800 +1662125127002805760 +1662125127041806592 +1662125127089807616 +1662125127131808512 +1662125127170809344 +1662125127212810240 +1662125127254811136 +1662125127293811968 +1662125127335812864 +1662125127377813760 +1662125127419814656 +1662125127464815616 +1662125127503816448 +1662125127545817344 +1662125127584818176 +1662125127629819136 +1662125127677820160 +1662125127719821056 +1662125127761821952 +1662125127800822784 +1662125127842823680 +1662125127881824512 +1662125127926825472 +1662125127968826368 +1662125128007827200 +1662125128046828032 +1662125128088828928 +1662125128130829824 +1662125128175830784 +1662125128217831680 +1662125128259832576 +1662125128304833536 +1662125128340834304 +1662125128382835200 +1662125128424836096 +1662125128463836928 +1662125128508837888 +1662125128562839040 +1662125128610840064 +1662125128652840960 +1662125128697841920 +1662125128739842816 +1662125128781843712 +1662125128829844736 +1662125128871845632 +1662125128919846656 +1662125128958847488 +1662125129003848448 +1662125129045849344 +1662125129087850240 +1662125129126851072 +1662125129174852096 +1662125129219853056 +1662125129264854016 +1662125129306854912 +1662125129345855744 +1662125129390856704 +1662125129435857664 +1662125129480858624 +1662125129522859520 +1662125129567860480 +1662125129609861376 +1662125129651862272 +1662125129696863232 +1662125129738864128 +1662125129783865088 +1662125129825865984 +1662125129867866880 +1662125129912867840 +1662125129951868672 +1662125129993869568 +1662125130038870528 +1662125130083871488 +1662125130128872448 +1662125130167873280 +1662125130206874112 +1662125130248875008 +1662125130296876032 +1662125130338876928 +1662125130380877824 +1662125130422878720 +1662125130464879616 +1662125130506880512 +1662125130548881408 +1662125130593882368 +1662125130638883328 +1662125130680884224 +1662125130728885248 +1662125130767886080 +1662125130809886976 +1662125130854887936 +1662125130899888896 +1662125130941889792 +1662125130983890688 +1662125131025891584 +1662125131064892416 +1662125131109893376 +1662125131154894336 +1662125131196895232 +1662125131238896128 +1662125131283897088 +1662125131325897984 +1662125131367898880 +1662125131415899904 +1662125131457900800 +1662125131496901632 +1662125131541902592 +1662125131583903488 +1662125131625904384 +1662125131670905344 +1662125131712906240 +1662125131760907264 +1662125131805908224 +1662125131847909120 +1662125131892910080 +1662125131943911168 +1662125131988912128 +1662125132027912960 +1662125132066913792 +1662125132108914688 +1662125132153915648 +1662125132198916608 +1662125132243917568 +1662125132288918528 +1662125132330919424 +1662125132372920320 +1662125132417921280 +1662125132459922176 +1662125132504923136 +1662125132549924096 +1662125132594925056 +1662125132636925952 +1662125132675926784 +1662125132720927744 +1662125132759928576 +1662125132804929536 +1662125132849930496 +1662125132891931392 +1662125132933932288 +1662125132975933184 +1662125133020934144 +1662125133065935104 +1662125133107936000 +1662125133149936896 +1662125133191937792 +1662125133236938752 +1662125133278939648 +1662125133323940608 +1662125133365941504 +1662125133410942464 +1662125133452943360 +1662125133494944256 +1662125133536945152 +1662125133578946048 +1662125133626947072 +1662125133668947968 +1662125133710948864 +1662125133752949760 +1662125133791950592 +1662125133833951488 +1662125133878952448 +1662125133920953344 +1662125133962954240 +1662125134010955264 +1662125134055956224 +1662125134100957184 +1662125134148958208 +1662125134187959040 +1662125134229959936 +1662125134271960832 +1662125134313961728 +1662125134358962688 +1662125134403963648 +1662125134445964544 +1662125134490965504 +1662125134532966400 +1662125134577967360 +1662125134625968384 +1662125134670969344 +1662125134715970304 +1662125134757971200 +1662125134799972096 +1662125134847973120 +1662125134892974080 +1662125134937975040 +1662125134973975808 +1662125135018976768 +1662125135057977600 +1662125135102978560 +1662125135144979456 +1662125135192980480 +1662125135237981440 +1662125135279982336 +1662125135330983424 +1662125135378984448 +1662125135420985344 +1662125135465986304 +1662125135510987264 +1662125135549988096 +1662125135594989056 +1662125135639990016 +1662125135681990912 +1662125135726991872 +1662125135768992768 +1662125135807993600 +1662125135855994624 +1662125135903995648 +1662125135945996544 +1662125135987997440 +1662125136029998336 +1662125136071999232 +1662125136120000256 +1662125136165001216 +1662125136204002048 +1662125136243002880 +1662125136285003776 +1662125136330004736 +1662125136372005632 +1662125136414006528 +1662125136456007424 +1662125136501008384 +1662125136540009216 +1662125136585010176 +1662125136627011072 +1662125136663011840 +1662125136705012736 +1662125136750013696 +1662125136792014592 +1662125136834015488 +1662125136876016384 +1662125136921017344 +1662125136960018176 +1662125136999019008 +1662125137041019904 +1662125137083020800 +1662125137122021632 +1662125137164022528 +1662125137209023488 +1662125137251024384 +1662125137290025216 +1662125137329026048 +1662125137371026944 +1662125137416027904 +1662125137464028928 +1662125137509029888 +1662125137551030784 +1662125137593031680 +1662125137635032576 +1662125137677033472 +1662125137719034368 +1662125137770035456 +1662125137809036288 +1662125137851037184 +1662125137890038016 +1662125137932038912 +1662125137977039872 +1662125138016040704 +1662125138058041600 +1662125138100042496 +1662125138142043392 +1662125138181044224 +1662125138223045120 +1662125138268046080 +1662125138313047040 +1662125138358048000 +1662125138406049024 +1662125138457050112 +1662125138499051008 +1662125138547052032 +1662125138589052928 +1662125138634053888 +1662125138676054784 +1662125138721055744 +1662125138763056640 +1662125138811057664 +1662125138853058560 +1662125138895059456 +1662125138937060352 +1662125138979061248 +1662125139021062144 +1662125139063063040 +1662125139102063872 +1662125139144064768 +1662125139192065792 +1662125139237066752 +1662125139279067648 +1662125139318068480 +1662125139366069504 +1662125139408070400 +1662125139450071296 +1662125139492072192 +1662125139534073088 +1662125139585074176 +1662125139630075136 +1662125139675076096 +1662125139720077056 +1662125139762077952 +1662125139801078784 +1662125139843079680 +1662125139882080512 +1662125139924081408 +1662125139963082240 +1662125140005083136 +1662125140047084032 +1662125140089084928 +1662125140128085760 +1662125140173086720 +1662125140218087680 +1662125140263088640 +1662125140305089536 +1662125140347090432 +1662125140386091264 +1662125140428092160 +1662125140470093056 +1662125140518094080 +1662125140560094976 +1662125140602095872 +1662125140644096768 +1662125140689097728 +1662125140731098624 +1662125140779099648 +1662125140830100736 +1662125140872101632 +1662125140914102528 +1662125140959103488 +1662125141001104384 +1662125141040105216 +1662125141082106112 +1662125141124107008 +1662125141166107904 +1662125141211108864 +1662125141253109760 +1662125141298110720 +1662125141343111680 +1662125141382112512 +1662125141424113408 +1662125141466114304 +1662125141511115264 +1662125141553116160 +1662125141595117056 +1662125141640118016 +1662125141682118912 +1662125141724119808 +1662125141769120768 +1662125141817121792 +1662125141859122688 +1662125141904123648 +1662125141949124608 +1662125141994125568 +1662125142036126464 +1662125142075127296 +1662125142117128192 +1662125142159129088 +1662125142207130112 +1662125142252131072 +1662125142294131968 +1662125142336132864 +1662125142375133696 +1662125142420134656 +1662125142465135616 +1662125142507136512 +1662125142555137536 +1662125142600138496 +1662125142642139392 +1662125142681140224 +1662125142723141120 +1662125142765142016 +1662125142807142912 +1662125142849143808 +1662125142891144704 +1662125142936145664 +1662125142978146560 +1662125143026147584 +1662125143071148544 +1662125143113149440 +1662125143158150400 +1662125143197151232 +1662125143242152192 +1662125143290153216 +1662125143332154112 +1662125143377155072 +1662125143419155968 +1662125143473157120 +1662125143515158016 +1662125143560158976 +1662125143602159872 +1662125143641160704 +1662125143686161664 +1662125143725162496 +1662125143773163520 +1662125143818164480 +1662125143860165376 +1662125143911166464 +1662125143953167360 +1662125143992168192 +1662125144037169152 +1662125144085170176 +1662125144127171072 +1662125144172172032 +1662125144220173056 +1662125144268174080 +1662125144316175104 +1662125144355175936 +1662125144397176832 +1662125144442177792 +1662125144484178688 +1662125144526179584 +1662125144568180480 +1662125144610181376 +1662125144655182336 +1662125144703183360 +1662125144748184320 +1662125144793185280 +1662125144835186176 +1662125144883187200 +1662125144925188096 +1662125144970189056 +1662125145021190144 +1662125145072191232 +1662125145114192128 +1662125145156193024 +1662125145198193920 +1662125145240194816 +1662125145285195776 +1662125145333196800 +1662125145381197824 +1662125145426198784 +1662125145471199744 +1662125145513200640 +1662125145564201728 +1662125145600202496 +1662125145639203328 +1662125145684204288 +1662125145726205184 +1662125145762205952 +1662125145807206912 +1662125145849207808 +1662125145897208832 +1662125145939209728 +1662125145981210624 +1662125146029211648 +1662125146074212608 +1662125146119213568 +1662125146161214464 +1662125146203215360 +1662125146245216256 +1662125146290217216 +1662125146335218176 +1662125146380219136 +1662125146422220032 +1662125146464220928 +1662125146506221824 +1662125146545222656 +1662125146596223744 +1662125146638224640 +1662125146680225536 +1662125146722226432 +1662125146764227328 +1662125146809228288 +1662125146851229184 +1662125146893230080 +1662125146938231040 +1662125146977231872 +1662125147019232768 +1662125147061233664 +1662125147106234624 +1662125147151235584 +1662125147193236480 +1662125147235237376 +1662125147280238336 +1662125147325239296 +1662125147370240256 +1662125147415241216 +1662125147457242112 +1662125147499243008 +1662125147541243904 +1662125147583244800 +1662125147628245760 +1662125147673246720 +1662125147715247616 +1662125147757248512 +1662125147796249344 +1662125147841250304 +1662125147883251200 +1662125147931252224 +1662125147973253120 +1662125148012253952 +1662125148057254912 +1662125148099255808 +1662125148138256640 +1662125148186257664 +1662125148228258560 +1662125148270259456 +1662125148312260352 +1662125148354261248 +1662125148399262208 +1662125148441263104 +1662125148483264000 +1662125148528264960 +1662125148567265792 +1662125148618266880 +1662125148657267712 +1662125148702268672 +1662125148744269568 +1662125148786270464 +1662125148834271488 +1662125148879272448 +1662125148927273472 +1662125148975274496 +1662125149020275456 +1662125149062276352 +1662125149104277248 +1662125149146278144 +1662125149197279232 +1662125149242280192 +1662125149284281088 +1662125149329282048 +1662125149377283072 +1662125149419283968 +1662125149458284800 +1662125149494285568 +1662125149530286336 +1662125149572287232 +1662125149617288192 +1662125149659289088 +1662125149698289920 +1662125149743290880 +1662125149788291840 +1662125149830292736 +1662125149875293696 +1662125149920294656 +1662125149962295552 +1662125150007296512 +1662125150049297408 +1662125150091298304 +1662125150133299200 +1662125150184300288 +1662125150229301248 +1662125150271302144 +1662125150313303040 +1662125150358304000 +1662125150400304896 +1662125150445305856 +1662125150484306688 +1662125150526307584 +1662125150577308672 +1662125150622309632 +1662125150667310592 +1662125150709311488 +1662125150754312448 +1662125150796313344 +1662125150841314304 +1662125150883315200 +1662125150928316160 +1662125150973317120 +1662125151015318016 +1662125151054318848 +1662125151093319680 +1662125151135320576 +1662125151174321408 +1662125151213322240 +1662125151258323200 +1662125151300324096 +1662125151345325056 +1662125151393326080 +1662125151435326976 +1662125151477327872 +1662125151522328832 +1662125151561329664 +1662125151606330624 +1662125151651331584 +1662125151696332544 +1662125151738333440 +1662125151780334336 +1662125151825335296 +1662125151870336256 +1662125151912337152 +1662125151960338176 +1662125152002339072 +1662125152044339968 +1662125152086340864 +1662125152131341824 +1662125152173342720 +1662125152215343616 +1662125152254344448 +1662125152296345344 +1662125152344346368 +1662125152389347328 +1662125152428348160 +1662125152473349120 +1662125152518350080 +1662125152563351040 +1662125152611352064 +1662125152653352960 +1662125152698353920 +1662125152743354880 +1662125152782355712 +1662125152824356608 +1662125152869357568 +1662125152914358528 +1662125152956359424 +1662125152992360192 +1662125153031361024 +1662125153067361792 +1662125153109362688 +1662125153154363648 +1662125153199364608 +1662125153241365504 +1662125153283366400 +1662125153325367296 +1662125153367368192 +1662125153412369152 +1662125153454370048 +1662125153490370816 +1662125153535371776 +1662125153580372736 +1662125153622373632 +1662125153664374528 +1662125153706375424 +1662125153748376320 +1662125153790377216 +1662125153835378176 +1662125153874379008 +1662125153916379904 +1662125153958380800 +1662125154000381696 +1662125154045382656 +1662125154093383680 +1662125154135384576 +1662125154180385536 +1662125154228386560 +1662125154270387456 +1662125154312388352 +1662125154354389248 +1662125154402390272 +1662125154447391232 +1662125154492392192 +1662125154534393088 +1662125154576393984 +1662125154618394880 +1662125154660395776 +1662125154699396608 +1662125154741397504 +1662125154783398400 +1662125154831399424 +1662125154873400320 +1662125154915401216 +1662125154957402112 +1662125154996402944 +1662125155038403840 +1662125155080404736 +1662125155119405568 +1662125155167406592 +1662125155206407424 +1662125155245408256 +1662125155287409152 +1662125155332410112 +1662125155377411072 +1662125155419411968 +1662125155464412928 +1662125155503413760 +1662125155548414720 +1662125155593415680 +1662125155632416512 +1662125155671417344 +1662125155713418240 +1662125155755419136 +1662125155797420032 +1662125155842420992 +1662125155887421952 +1662125155929422848 +1662125155971423744 +1662125156013424640 +1662125156052425472 +1662125156094426368 +1662125156136427264 +1662125156181428224 +1662125156223429120 +1662125156265430016 +1662125156316431104 +1662125156355431936 +1662125156397432832 +1662125156436433664 +1662125156481434624 +1662125156523435520 +1662125156568436480 +1662125156610437376 +1662125156652438272 +1662125156697439232 +1662125156739440128 +1662125156778440960 +1662125156823441920 +1662125156865442816 +1662125156916443904 +1662125156958444800 +1662125157003445760 +1662125157051446784 +1662125157093447680 +1662125157138448640 +1662125157183449600 +1662125157228450560 +1662125157276451584 +1662125157321452544 +1662125157366453504 +1662125157414454528 +1662125157456455424 +1662125157498456320 +1662125157540457216 +1662125157582458112 +1662125157627459072 +1662125157672460032 +1662125157714460928 +1662125157759461888 +1662125157804462848 +1662125157846463744 +1662125157891464704 +1662125157933465600 +1662125157978466560 +1662125158026467584 +1662125158074468608 +1662125158116469504 +1662125158158470400 +1662125158200471296 +1662125158242472192 +1662125158284473088 +1662125158326473984 +1662125158368474880 +1662125158407475712 +1662125158449476608 +1662125158491477504 +1662125158536478464 +1662125158578479360 +1662125158626480384 +1662125158671481344 +1662125158713482240 +1662125158755483136 +1662125158800484096 +1662125158842484992 +1662125158890486016 +1662125158935486976 +1662125158980487936 +1662125159025488896 +1662125159067489792 +1662125159109490688 +1662125159151491584 +1662125159193492480 +1662125159235493376 +1662125159277494272 +1662125159319495168 +1662125159361496064 +1662125159406497024 +1662125159448497920 +1662125159490498816 +1662125159535499776 +1662125159583500800 +1662125159625501696 +1662125159667502592 +1662125159706503424 +1662125159742504192 +1662125159781505024 +1662125159823505920 +1662125159865506816 +1662125159913507840 +1662125159961508864 +1662125160003509760 +1662125160045510656 +1662125160090511616 +1662125160138512640 +1662125160180513536 +1662125160222514432 +1662125160261515264 +1662125160303516160 +1662125160348517120 +1662125160387517952 +1662125160432518912 +1662125160474519808 +1662125160519520768 +1662125160558521600 +1662125160597522432 +1662125160645523456 +1662125160687524352 +1662125160729525248 +1662125160771526144 +1662125160813527040 +1662125160855527936 +1662125160900528896 +1662125160942529792 +1662125160990530816 +1662125161038531840 +1662125161080532736 +1662125161128533760 +1662125161176534784 +1662125161218535680 +1662125161266536704 +1662125161314537728 +1662125161359538688 +1662125161401539584 +1662125161443540480 +1662125161491541504 +1662125161533542400 +1662125161578543360 +1662125161620544256 +1662125161662545152 +1662125161701545984 +1662125161749547008 +1662125161791547904 +1662125161833548800 +1662125161875549696 +1662125161923550720 +1662125161971551744 +1662125162013552640 +1662125162055553536 +1662125162100554496 +1662125162145555456 +1662125162187556352 +1662125162229557248 +1662125162271558144 +1662125162319559168 +1662125162355559936 +1662125162397560832 +1662125162442561792 +1662125162484562688 +1662125162532563712 +1662125162574564608 +1662125162616565504 +1662125162661566464 +1662125162703567360 +1662125162748568320 +1662125162793569280 +1662125162832570112 +1662125162877571072 +1662125162919571968 +1662125162961572864 +1662125163006573824 +1662125163048574720 +1662125163093575680 +1662125163138576640 +1662125163183577600 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt new file mode 100644 index 0000000000..7283c7fd50 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt @@ -0,0 +1,2489 @@ +1662120285510217728 +1662120285552218624 +1662120285594219520 +1662120285636220416 +1662120285681221376 +1662120285723222272 +1662120285768223232 +1662120285810224128 +1662120285858225152 +1662120285897225984 +1662120285936226816 +1662120285981227776 +1662120286023228672 +1662120286065229568 +1662120286107230464 +1662120286149231360 +1662120286191232256 +1662120286233233152 +1662120286281234176 +1662120286323235072 +1662120286371236096 +1662120286413236992 +1662120286455237888 +1662120286497238784 +1662120286539239680 +1662120286581240576 +1662120286620241408 +1662120286662242304 +1662120286701243136 +1662120286740243968 +1662120286782244864 +1662120286827245824 +1662120286875246848 +1662120286920247808 +1662120286968248832 +1662120287010249728 +1662120287052250624 +1662120287097251584 +1662120287139252480 +1662120287181253376 +1662120287220254208 +1662120287265255168 +1662120287307256064 +1662120287352257024 +1662120287397257984 +1662120287436258816 +1662120287475259648 +1662120287517260544 +1662120287559261440 +1662120287601262336 +1662120287646263296 +1662120287688264192 +1662120287733265152 +1662120287772265984 +1662120287814266880 +1662120287862267904 +1662120287907268864 +1662120287952269824 +1662120288000270848 +1662120288039271680 +1662120288087272704 +1662120288135273728 +1662120288177274624 +1662120288225275648 +1662120288267276544 +1662120288309277440 +1662120288354278400 +1662120288396279296 +1662120288438280192 +1662120288483281152 +1662120288528282112 +1662120288576283136 +1662120288624284160 +1662120288666285056 +1662120288708285952 +1662120288747286784 +1662120288792287744 +1662120288834288640 +1662120288873289472 +1662120288918290432 +1662120288963291392 +1662120289008292352 +1662120289050293248 +1662120289092294144 +1662120289131294976 +1662120289176295936 +1662120289218296832 +1662120289260297728 +1662120289311298816 +1662120289356299776 +1662120289398300672 +1662120289440301568 +1662120289485302528 +1662120289527303424 +1662120289569304320 +1662120289608305152 +1662120289653306112 +1662120289695307008 +1662120289734307840 +1662120289773308672 +1662120289812309504 +1662120289854310400 +1662120289896311296 +1662120289938312192 +1662120289983313152 +1662120290025314048 +1662120290067314944 +1662120290115315968 +1662120290157316864 +1662120290202317824 +1662120290247318784 +1662120290292319744 +1662120290340320768 +1662120290385321728 +1662120290430322688 +1662120290478323712 +1662120290526324736 +1662120290568325632 +1662120290613326592 +1662120290652327424 +1662120290694328320 +1662120290730329088 +1662120290772329984 +1662120290814330880 +1662120290853331712 +1662120290898332672 +1662120290937333504 +1662120290979334400 +1662120291021335296 +1662120291060336128 +1662120291108337152 +1662120291150338048 +1662120291195339008 +1662120291240339968 +1662120291291341056 +1662120291336342016 +1662120291381342976 +1662120291423343872 +1662120291477345024 +1662120291519345920 +1662120291567346944 +1662120291606347776 +1662120291648348672 +1662120291690349568 +1662120291735350528 +1662120291777351424 +1662120291825352448 +1662120291870353408 +1662120291912354304 +1662120291954355200 +1662120291996356096 +1662120292041357056 +1662120292080357888 +1662120292119358720 +1662120292167359744 +1662120292209360640 +1662120292251361536 +1662120292293362432 +1662120292335363328 +1662120292377364224 +1662120292419365120 +1662120292470366208 +1662120292512367104 +1662120292560368128 +1662120292602369024 +1662120292647369984 +1662120292692370944 +1662120292734371840 +1662120292776372736 +1662120292818373632 +1662120292860374528 +1662120292902375424 +1662120292947376384 +1662120292989377280 +1662120293031378176 +1662120293076379136 +1662120293118380032 +1662120293160380928 +1662120293202381824 +1662120293244382720 +1662120293289383680 +1662120293331384576 +1662120293376385536 +1662120293418386432 +1662120293463387392 +1662120293505388288 +1662120293547389184 +1662120293592390144 +1662120293634391040 +1662120293679392000 +1662120293724392960 +1662120293766393856 +1662120293811394816 +1662120293856395776 +1662120293895396608 +1662120293940397568 +1662120293988398592 +1662120294033399552 +1662120294078400512 +1662120294123401472 +1662120294168402432 +1662120294213403392 +1662120294249404160 +1662120294291405056 +1662120294330405888 +1662120294372406784 +1662120294420407808 +1662120294462408704 +1662120294507409664 +1662120294546410496 +1662120294588411392 +1662120294633412352 +1662120294684413440 +1662120294729414400 +1662120294774415360 +1662120294816416256 +1662120294861417216 +1662120294903418112 +1662120294951419136 +1662120294996420096 +1662120295044421120 +1662120295083421952 +1662120295128422912 +1662120295170423808 +1662120295218424832 +1662120295263425792 +1662120295305426688 +1662120295347427584 +1662120295389428480 +1662120295434429440 +1662120295476430336 +1662120295521431296 +1662120295566432256 +1662120295605433088 +1662120295647433984 +1662120295692434944 +1662120295734435840 +1662120295776436736 +1662120295818437632 +1662120295866438656 +1662120295911439616 +1662120295953440512 +1662120295995441408 +1662120296037442304 +1662120296082443264 +1662120296130444288 +1662120296169445120 +1662120296208445952 +1662120296250446848 +1662120296295447808 +1662120296337448704 +1662120296379449600 +1662120296421450496 +1662120296457451264 +1662120296499452160 +1662120296541453056 +1662120296589454080 +1662120296637455104 +1662120296682456064 +1662120296724456960 +1662120296766457856 +1662120296808458752 +1662120296850459648 +1662120296892460544 +1662120296937461504 +1662120296979462400 +1662120297021463296 +1662120297066464256 +1662120297111465216 +1662120297153466112 +1662120297201467136 +1662120297246468096 +1662120297288468992 +1662120297327469824 +1662120297372470784 +1662120297414471680 +1662120297459472640 +1662120297504473600 +1662120297552474624 +1662120297597475584 +1662120297639476480 +1662120297684477440 +1662120297726478336 +1662120297765479168 +1662120297804480000 +1662120297843480832 +1662120297885481728 +1662120297927482624 +1662120297972483584 +1662120298005484288 +1662120298053485312 +1662120298095486208 +1662120298137487104 +1662120298179488000 +1662120298227489024 +1662120298269489920 +1662120298311490816 +1662120298350491648 +1662120298395492608 +1662120298446493696 +1662120298491494656 +1662120298533495552 +1662120298575496448 +1662120298617497344 +1662120298662498304 +1662120298713499392 +1662120298755500288 +1662120298800501248 +1662120298842502144 +1662120298884503040 +1662120298926503936 +1662120298968504832 +1662120299010505728 +1662120299052506624 +1662120299094507520 +1662120299136508416 +1662120299178509312 +1662120299220510208 +1662120299262511104 +1662120299307512064 +1662120299352513024 +1662120299391513856 +1662120299433514752 +1662120299481515776 +1662120299523516672 +1662120299568517632 +1662120299613518592 +1662120299658519552 +1662120299700520448 +1662120299742521344 +1662120299787522304 +1662120299832523264 +1662120299874524160 +1662120299916525056 +1662120299961526016 +1662120300006526976 +1662120300048527872 +1662120300084528640 +1662120300126529536 +1662120300171530496 +1662120300216531456 +1662120300261532416 +1662120300303533312 +1662120300348534272 +1662120300390535168 +1662120300432536064 +1662120300474536960 +1662120300516537856 +1662120300564538880 +1662120300609539840 +1662120300651540736 +1662120300693541632 +1662120300735542528 +1662120300777543424 +1662120300822544384 +1662120300864545280 +1662120300915546368 +1662120300960547328 +1662120301002548224 +1662120301044549120 +1662120301086550016 +1662120301128550912 +1662120301176551936 +1662120301221552896 +1662120301260553728 +1662120301308554752 +1662120301353555712 +1662120301401556736 +1662120301443557632 +1662120301485558528 +1662120301527559424 +1662120301572560384 +1662120301614561280 +1662120301662562304 +1662120301704563200 +1662120301746564096 +1662120301785564928 +1662120301827565824 +1662120301869566720 +1662120301911567616 +1662120301950568448 +1662120301995569408 +1662120302037570304 +1662120302085571328 +1662120302130572288 +1662120302175573248 +1662120302220574208 +1662120302265575168 +1662120302307576064 +1662120302346576896 +1662120302391577856 +1662120302439578880 +1662120302484579840 +1662120302532580864 +1662120302574581760 +1662120302616582656 +1662120302658583552 +1662120302697584384 +1662120302742585344 +1662120302787586304 +1662120302829587200 +1662120302871588096 +1662120302916589056 +1662120302958589952 +1662120303000590848 +1662120303051591936 +1662120303099592960 +1662120303141593856 +1662120303183594752 +1662120303231595776 +1662120303279596800 +1662120303321597696 +1662120303360598528 +1662120303399599360 +1662120303450600448 +1662120303495601408 +1662120303537602304 +1662120303576603136 +1662120303618604032 +1662120303657604864 +1662120303702605824 +1662120303750606848 +1662120303792607744 +1662120303837608704 +1662120303879609600 +1662120303930610688 +1662120303975611648 +1662120304017612544 +1662120304059613440 +1662120304104614400 +1662120304149615360 +1662120304191616256 +1662120304236617216 +1662120304278618112 +1662120304320619008 +1662120304362619904 +1662120304401620736 +1662120304443621632 +1662120304485622528 +1662120304530623488 +1662120304578624512 +1662120304623625472 +1662120304665626368 +1662120304710627328 +1662120304755628288 +1662120304800629248 +1662120304848630272 +1662120304893631232 +1662120304938632192 +1662120304980633088 +1662120305022633984 +1662120305067634944 +1662120305112635904 +1662120305148636672 +1662120305196637696 +1662120305235638528 +1662120305274639360 +1662120305319640320 +1662120305364641280 +1662120305403642112 +1662120305445643008 +1662120305490643968 +1662120305535644928 +1662120305577645824 +1662120305619646720 +1662120305664647680 +1662120305703648512 +1662120305745649408 +1662120305790650368 +1662120305838651392 +1662120305883652352 +1662120305928653312 +1662120305970654208 +1662120306012655104 +1662120306054656000 +1662120306102657024 +1662120306150658048 +1662120306192658944 +1662120306237659904 +1662120306282660864 +1662120306324661760 +1662120306369662720 +1662120306417663744 +1662120306462664704 +1662120306507665664 +1662120306549666560 +1662120306591667456 +1662120306633668352 +1662120306678669312 +1662120306723670272 +1662120306765671168 +1662120306810672128 +1662120306855673088 +1662120306897673984 +1662120306939674880 +1662120306978675712 +1662120307017676544 +1662120307065677568 +1662120307104678400 +1662120307149679360 +1662120307191680256 +1662120307236681216 +1662120307281682176 +1662120307323683072 +1662120307365683968 +1662120307407684864 +1662120307449685760 +1662120307491686656 +1662120307527687424 +1662120307572688384 +1662120307614689280 +1662120307656690176 +1662120307707691264 +1662120307752692224 +1662120307794693120 +1662120307836694016 +1662120307878694912 +1662120307923695872 +1662120307971696896 +1662120308016697856 +1662120308058698752 +1662120308100699648 +1662120308142700544 +1662120308181701376 +1662120308226702336 +1662120308271703296 +1662120308313704192 +1662120308355705088 +1662120308403706112 +1662120308451707136 +1662120308496708096 +1662120308538708992 +1662120308580709888 +1662120308622710784 +1662120308661711616 +1662120308709712640 +1662120308751713536 +1662120308790714368 +1662120308835715328 +1662120308880716288 +1662120308922717184 +1662120308964718080 +1662120309003718912 +1662120309045719808 +1662120309090720768 +1662120309135721728 +1662120309177722624 +1662120309216723456 +1662120309258724352 +1662120309300725248 +1662120309345726208 +1662120309390727168 +1662120309435728128 +1662120309474728960 +1662120309516729856 +1662120309561730816 +1662120309603731712 +1662120309645732608 +1662120309690733568 +1662120309729734400 +1662120309777735424 +1662120309819736320 +1662120309864737280 +1662120309915738368 +1662120309957739264 +1662120310002740224 +1662120310044741120 +1662120310092742144 +1662120310134743040 +1662120310179744000 +1662120310224744960 +1662120310266745856 +1662120310311746816 +1662120310353747712 +1662120310395748608 +1662120310440749568 +1662120310482750464 +1662120310527751424 +1662120310572752384 +1662120310611753216 +1662120310662754304 +1662120310704755200 +1662120310746756096 +1662120310788756992 +1662120310839758080 +1662120310881758976 +1662120310923759872 +1662120310971760896 +1662120311016761856 +1662120311061762816 +1662120311109763840 +1662120311151764736 +1662120311190765568 +1662120311241766656 +1662120311283767552 +1662120311325768448 +1662120311367769344 +1662120311412770304 +1662120311454771200 +1662120311505772288 +1662120311547773184 +1662120311592774144 +1662120311634775040 +1662120311676775936 +1662120311721776896 +1662120311763777792 +1662120311808778752 +1662120311850779648 +1662120311892780544 +1662120311937781504 +1662120311982782464 +1662120312027783424 +1662120312063784192 +1662120312108785152 +1662120312150786048 +1662120312195787008 +1662120312234787840 +1662120312279788800 +1662120312327789824 +1662120312369790720 +1662120312411791616 +1662120312453792512 +1662120312495793408 +1662120312540794368 +1662120312588795392 +1662120312636796416 +1662120312678797312 +1662120312723798272 +1662120312765799168 +1662120312804800000 +1662120312849800960 +1662120312894801920 +1662120312939802880 +1662120312981803776 +1662120313026804736 +1662120313068805632 +1662120313110806528 +1662120313152807424 +1662120313197808384 +1662120313242809344 +1662120313284810240 +1662120313326811136 +1662120313371812096 +1662120313413812992 +1662120313455813888 +1662120313497814784 +1662120313545815808 +1662120313584816640 +1662120313626817536 +1662120313668818432 +1662120313713819392 +1662120313755820288 +1662120313797821184 +1662120313839822080 +1662120313884823040 +1662120313929824000 +1662120313977825024 +1662120314031826176 +1662120314073827072 +1662120314115827968 +1662120314160828928 +1662120314202829824 +1662120314247830784 +1662120314295831808 +1662120314340832768 +1662120314379833600 +1662120314421834496 +1662120314466835456 +1662120314508836352 +1662120314553837312 +1662120314598838272 +1662120314637839104 +1662120314682840064 +1662120314724840960 +1662120314772841984 +1662120314811842816 +1662120314856843776 +1662120314898844672 +1662120314940845568 +1662120314988846592 +1662120315033847552 +1662120315078848512 +1662120315123849472 +1662120315168850432 +1662120315210851328 +1662120315252852224 +1662120315294853120 +1662120315345854208 +1662120315390855168 +1662120315435856128 +1662120315489857280 +1662120315537858304 +1662120315582859264 +1662120315630860288 +1662120315675861248 +1662120315717862144 +1662120315762863104 +1662120315807864064 +1662120315849864960 +1662120315891865856 +1662120315933866752 +1662120315975867648 +1662120316017868544 +1662120316062869504 +1662120316104870400 +1662120316149871360 +1662120316191872256 +1662120316230873088 +1662120316275874048 +1662120316317874944 +1662120316362875904 +1662120316404876800 +1662120316449877760 +1662120316494878720 +1662120316539879680 +1662120316581880576 +1662120316620881408 +1662120316665882368 +1662120316704883200 +1662120316746884096 +1662120316791885056 +1662120316836886016 +1662120316878886912 +1662120316917887744 +1662120316962888704 +1662120317001889536 +1662120317049890560 +1662120317100891648 +1662120317142892544 +1662120317187893504 +1662120317232894464 +1662120317277895424 +1662120317322896384 +1662120317367897344 +1662120317409898240 +1662120317454899200 +1662120317496900096 +1662120317544901120 +1662120317586902016 +1662120317628902912 +1662120317673903872 +1662120317715904768 +1662120317757905664 +1662120317802906624 +1662120317844907520 +1662120317886908416 +1662120317934909440 +1662120317976910336 +1662120318018911232 +1662120318060912128 +1662120318102913024 +1662120318147913984 +1662120318192914944 +1662120318231915776 +1662120318270916608 +1662120318315917568 +1662120318357918464 +1662120318399919360 +1662120318447920384 +1662120318492921344 +1662120318534922240 +1662120318576923136 +1662120318618924032 +1662120318663924992 +1662120318708925952 +1662120318753926912 +1662120318798927872 +1662120318843928832 +1662120318891929856 +1662120318936930816 +1662120318978931712 +1662120319017932544 +1662120319062933504 +1662120319104934400 +1662120319149935360 +1662120319191936256 +1662120319236937216 +1662120319278938112 +1662120319323939072 +1662120319365939968 +1662120319413940992 +1662120319455941888 +1662120319500942848 +1662120319542943744 +1662120319587944704 +1662120319632945664 +1662120319680946688 +1662120319725947648 +1662120319770948608 +1662120319812949504 +1662120319854950400 +1662120319899951360 +1662120319941952256 +1662120319986953216 +1662120320028954112 +1662120320073955072 +1662120320115955968 +1662120320160956928 +1662120320202957824 +1662120320247958784 +1662120320295959808 +1662120320340960768 +1662120320379961600 +1662120320424962560 +1662120320469963520 +1662120320511964416 +1662120320556965376 +1662120320601966336 +1662120320646967296 +1662120320688968192 +1662120320727969024 +1662120320769969920 +1662120320814970880 +1662120320862971904 +1662120320904972800 +1662120320946973696 +1662120320988974592 +1662120321033975552 +1662120321075976448 +1662120321120977408 +1662120321162978304 +1662120321210979328 +1662120321255980288 +1662120321306981376 +1662120321348982272 +1662120321393983232 +1662120321438984192 +1662120321477985024 +1662120321522985984 +1662120321561986816 +1662120321603987712 +1662120321651988736 +1662120321693989632 +1662120321732990464 +1662120321780991488 +1662120321822992384 +1662120321858993152 +1662120321900994048 +1662120321942994944 +1662120321987995904 +1662120322026996736 +1662120322068997632 +1662120322110998528 +1662120322149999360 +1662120322195000320 +1662120322237001216 +1662120322285002240 +1662120322330003200 +1662120322372004096 +1662120322417005056 +1662120322459005952 +1662120322501006848 +1662120322543007744 +1662120322585008640 +1662120322624009472 +1662120322666010368 +1662120322708011264 +1662120322750012160 +1662120322789012992 +1662120322828013824 +1662120322882014976 +1662120322924015872 +1662120322975016960 +1662120323014017792 +1662120323056018688 +1662120323101019648 +1662120323146020608 +1662120323185021440 +1662120323227022336 +1662120323272023296 +1662120323317024256 +1662120323359025152 +1662120323401026048 +1662120323443026944 +1662120323488027904 +1662120323530028800 +1662120323575029760 +1662120323620030720 +1662120323668031744 +1662120323710032640 +1662120323749033472 +1662120323794034432 +1662120323836035328 +1662120323875036160 +1662120323920037120 +1662120323959037952 +1662120324004038912 +1662120324046039808 +1662120324091040768 +1662120324139041792 +1662120324178042624 +1662120324223043584 +1662120324265044480 +1662120324304045312 +1662120324343046144 +1662120324385047040 +1662120324427047936 +1662120324469048832 +1662120324517049856 +1662120324559050752 +1662120324601051648 +1662120324640052480 +1662120324682053376 +1662120324724054272 +1662120324766055168 +1662120324808056064 +1662120324853057024 +1662120324901058048 +1662120324943058944 +1662120324988059904 +1662120325036060928 +1662120325078061824 +1662120325120062720 +1662120325159063552 +1662120325204064512 +1662120325255065600 +1662120325300066560 +1662120325342067456 +1662120325384068352 +1662120325429069312 +1662120325468070144 +1662120325510071040 +1662120325549071872 +1662120325603073024 +1662120325642073856 +1662120325687074816 +1662120325726075648 +1662120325768076544 +1662120325810077440 +1662120325852078336 +1662120325894079232 +1662120325939080192 +1662120325984081152 +1662120326026082048 +1662120326074083072 +1662120326119084032 +1662120326164084992 +1662120326209085952 +1662120326257086976 +1662120326302087936 +1662120326344088832 +1662120326386089728 +1662120326428090624 +1662120326470091520 +1662120326512092416 +1662120326554093312 +1662120326596094208 +1662120326638095104 +1662120326683096064 +1662120326725096960 +1662120326767097856 +1662120326809098752 +1662120326857099776 +1662120326902100736 +1662120326947101696 +1662120326995102720 +1662120327040103680 +1662120327088104704 +1662120327133105664 +1662120327175106560 +1662120327220107520 +1662120327268108544 +1662120327310109440 +1662120327355110400 +1662120327394111232 +1662120327436112128 +1662120327490113280 +1662120327532114176 +1662120327574115072 +1662120327619116032 +1662120327661116928 +1662120327706117888 +1662120327748118784 +1662120327793119744 +1662120327832120576 +1662120327874121472 +1662120327919122432 +1662120327964123392 +1662120328009124352 +1662120328054125312 +1662120328099126272 +1662120328144127232 +1662120328189128192 +1662120328231129088 +1662120328273129984 +1662120328312130816 +1662120328354131712 +1662120328396132608 +1662120328441133568 +1662120328486134528 +1662120328531135488 +1662120328573136384 +1662120328612137216 +1662120328660138240 +1662120328705139200 +1662120328747140096 +1662120328795141120 +1662120328837142016 +1662120328879142912 +1662120328921143808 +1662120328963144704 +1662120329005145600 +1662120329047146496 +1662120329089147392 +1662120329137148416 +1662120329182149376 +1662120329227150336 +1662120329272151296 +1662120329317152256 +1662120329362153216 +1662120329410154240 +1662120329455155200 +1662120329497156096 +1662120329536156928 +1662120329581157888 +1662120329623158784 +1662120329668159744 +1662120329713160704 +1662120329758161664 +1662120329800162560 +1662120329842163456 +1662120329884164352 +1662120329926165248 +1662120329971166208 +1662120330010167040 +1662120330052167936 +1662120330100168960 +1662120330145169920 +1662120330190170880 +1662120330235171840 +1662120330277172736 +1662120330316173568 +1662120330364174592 +1662120330406175488 +1662120330448176384 +1662120330487177216 +1662120330526178048 +1662120330571179008 +1662120330613179904 +1662120330658180864 +1662120330703181824 +1662120330748182784 +1662120330793183744 +1662120330838184704 +1662120330877185536 +1662120330928186624 +1662120330967187456 +1662120331006188288 +1662120331051189248 +1662120331090190080 +1662120331132190976 +1662120331174191872 +1662120331219192832 +1662120331261193728 +1662120331306194688 +1662120331354195712 +1662120331393196544 +1662120331435197440 +1662120331477198336 +1662120331513199104 +1662120331561200128 +1662120331609201152 +1662120331648201984 +1662120331690202880 +1662120331735203840 +1662120331780204800 +1662120331825205760 +1662120331864206592 +1662120331906207488 +1662120331951208448 +1662120331996209408 +1662120332038210304 +1662120332080211200 +1662120332125212160 +1662120332164212992 +1662120332206213888 +1662120332251214848 +1662120332293215744 +1662120332335216640 +1662120332374217472 +1662120332416218368 +1662120332458219264 +1662120332500220160 +1662120332545221120 +1662120332584221952 +1662120332629222912 +1662120332674223872 +1662120332719224832 +1662120332761225728 +1662120332806226688 +1662120332848227584 +1662120332890228480 +1662120332932229376 +1662120332974230272 +1662120333019231232 +1662120333064232192 +1662120333106233088 +1662120333154234112 +1662120333199235072 +1662120333238235904 +1662120333286236928 +1662120333328237824 +1662120333367238656 +1662120333409239552 +1662120333448240384 +1662120333490241280 +1662120333529242112 +1662120333571243008 +1662120333610243840 +1662120333649244672 +1662120333691245568 +1662120333736246528 +1662120333781247488 +1662120333826248448 +1662120333868249344 +1662120333913250304 +1662120333958251264 +1662120334003252224 +1662120334048253184 +1662120334090254080 +1662120334132254976 +1662120334171255808 +1662120334213256704 +1662120334258257664 +1662120334303258624 +1662120334348259584 +1662120334393260544 +1662120334438261504 +1662120334480262400 +1662120334525263360 +1662120334570264320 +1662120334612265216 +1662120334657266176 +1662120334702267136 +1662120334744268032 +1662120334795269120 +1662120334837270016 +1662120334882270976 +1662120334918271744 +1662120334960272640 +1662120335002273536 +1662120335047274496 +1662120335095275520 +1662120335137276416 +1662120335185277440 +1662120335230278400 +1662120335272279296 +1662120335314280192 +1662120335362281216 +1662120335404282112 +1662120335449283072 +1662120335485283840 +1662120335530284800 +1662120335572285696 +1662120335614286592 +1662120335656287488 +1662120335701288448 +1662120335746289408 +1662120335788290304 +1662120335833291264 +1662120335878292224 +1662120335923293184 +1662120335962294016 +1662120336010295040 +1662120336052295936 +1662120336088296704 +1662120336127297536 +1662120336172298496 +1662120336214299392 +1662120336250300160 +1662120336292301056 +1662120336334301952 +1662120336376302848 +1662120336427303936 +1662120336475304960 +1662120336517305856 +1662120336562306816 +1662120336601307648 +1662120336637308416 +1662120336679309312 +1662120336724310272 +1662120336763311104 +1662120336799311872 +1662120336838312704 +1662120336883313664 +1662120336922314496 +1662120336970315520 +1662120337015316480 +1662120337057317376 +1662120337102318336 +1662120337141319168 +1662120337186320128 +1662120337231321088 +1662120337276322048 +1662120337324323072 +1662120337369324032 +1662120337414324992 +1662120337459325952 +1662120337504326912 +1662120337546327808 +1662120337591328768 +1662120337636329728 +1662120337675330560 +1662120337711331328 +1662120337756332288 +1662120337801333248 +1662120337843334144 +1662120337882334976 +1662120337924335872 +1662120337969336832 +1662120338014337792 +1662120338059338752 +1662120338104339712 +1662120338146340608 +1662120338191341568 +1662120338233342464 +1662120338275343360 +1662120338323344384 +1662120338368345344 +1662120338416346368 +1662120338461347328 +1662120338503348224 +1662120338548349184 +1662120338590350080 +1662120338632350976 +1662120338674351872 +1662120338713352704 +1662120338752353536 +1662120338797354496 +1662120338842355456 +1662120338890356480 +1662120338932357376 +1662120338974358272 +1662120339016359168 +1662120339055360000 +1662120339100360960 +1662120339145361920 +1662120339190362880 +1662120339241363968 +1662120339286364928 +1662120339334365952 +1662120339382366976 +1662120339427367936 +1662120339466368768 +1662120339502369536 +1662120339544370432 +1662120339586371328 +1662120339625372160 +1662120339667373056 +1662120339706373888 +1662120339748374784 +1662120339793375744 +1662120339832376576 +1662120339874377472 +1662120339916378368 +1662120339958379264 +1662120340000380160 +1662120340042381056 +1662120340084381952 +1662120340126382848 +1662120340171383808 +1662120340216384768 +1662120340258385664 +1662120340306386688 +1662120340351387648 +1662120340393388544 +1662120340432389376 +1662120340480390400 +1662120340522391296 +1662120340564392192 +1662120340609393152 +1662120340651394048 +1662120340696395008 +1662120340738395904 +1662120340780396800 +1662120340825397760 +1662120340873398784 +1662120340912399616 +1662120340957400576 +1662120341002401536 +1662120341044402432 +1662120341089403392 +1662120341131404288 +1662120341176405248 +1662120341215406080 +1662120341263407104 +1662120341305408000 +1662120341344408832 +1662120341383409664 +1662120341428410624 +1662120341470411520 +1662120341512412416 +1662120341560413440 +1662120341605414400 +1662120341650415360 +1662120341692416256 +1662120341734417152 +1662120341773417984 +1662120341815418880 +1662120341857419776 +1662120341899420672 +1662120341938421504 +1662120341980422400 +1662120342025423360 +1662120342067424256 +1662120342112425216 +1662120342160426240 +1662120342202427136 +1662120342244428032 +1662120342286428928 +1662120342328429824 +1662120342373430784 +1662120342418431744 +1662120342466432768 +1662120342514433792 +1662120342556434688 +1662120342595435520 +1662120342637436416 +1662120342676437248 +1662120342718438144 +1662120342760439040 +1662120342799439872 +1662120342838440704 +1662120342877441536 +1662120342925442560 +1662120342964443392 +1662120343009444352 +1662120343048445184 +1662120343090446080 +1662120343135447040 +1662120343177447936 +1662120343222448896 +1662120343264449792 +1662120343309450752 +1662120343351451648 +1662120343402452736 +1662120343447453696 +1662120343489454592 +1662120343534455552 +1662120343579456512 +1662120343618457344 +1662120343663458304 +1662120343711459328 +1662120343762460416 +1662120343801461248 +1662120343849462272 +1662120343891463168 +1662120343936464128 +1662120343978465024 +1662120344023465984 +1662120344062466816 +1662120344107467776 +1662120344146468608 +1662120344188469504 +1662120344230470400 +1662120344275471360 +1662120344314472192 +1662120344356473088 +1662120344401474048 +1662120344443474944 +1662120344491475968 +1662120344533476864 +1662120344581477888 +1662120344620478720 +1662120344665479680 +1662120344713480704 +1662120344758481664 +1662120344800482560 +1662120344842483456 +1662120344884484352 +1662120344926485248 +1662120344968486144 +1662120345010487040 +1662120345055488000 +1662120345100488960 +1662120345145489920 +1662120345187490816 +1662120345229491712 +1662120345268492544 +1662120345310493440 +1662120345358494464 +1662120345397495296 +1662120345439496192 +1662120345484497152 +1662120345526498048 +1662120345568498944 +1662120345613499904 +1662120345655500800 +1662120345697501696 +1662120345736502528 +1662120345781503488 +1662120345826504448 +1662120345874505472 +1662120345919506432 +1662120345961507328 +1662120346006508288 +1662120346051509248 +1662120346096510208 +1662120346138511104 +1662120346180512000 +1662120346219512832 +1662120346264513792 +1662120346309514752 +1662120346354515712 +1662120346399516672 +1662120346441517568 +1662120346486518528 +1662120346528519424 +1662120346573520384 +1662120346618521344 +1662120346660522240 +1662120346702523136 +1662120346744524032 +1662120346786524928 +1662120346828525824 +1662120346876526848 +1662120346915527680 +1662120346957528576 +1662120347005529600 +1662120347047530496 +1662120347086531328 +1662120347128532224 +1662120347170533120 +1662120347212534016 +1662120347257534976 +1662120347299535872 +1662120347344536832 +1662120347389537792 +1662120347431538688 +1662120347476539648 +1662120347518540544 +1662120347560541440 +1662120347608542464 +1662120347653543424 +1662120347695544320 +1662120347737545216 +1662120347779546112 +1662120347824547072 +1662120347863547904 +1662120347905548800 +1662120347947549696 +1662120347986550528 +1662120348031551488 +1662120348073552384 +1662120348118553344 +1662120348157554176 +1662120348202555136 +1662120348244556032 +1662120348289556992 +1662120348331557888 +1662120348376558848 +1662120348421559808 +1662120348460560640 +1662120348502561536 +1662120348544562432 +1662120348589563392 +1662120348637564416 +1662120348679565312 +1662120348718566144 +1662120348760567040 +1662120348802567936 +1662120348841568768 +1662120348880569600 +1662120348922570496 +1662120348964571392 +1662120349009572352 +1662120349057573376 +1662120349102574336 +1662120349144575232 +1662120349186576128 +1662120349231577088 +1662120349273577984 +1662120349318578944 +1662120349363579904 +1662120349402580736 +1662120349444581632 +1662120349489582592 +1662120349531583488 +1662120349573584384 +1662120349612585216 +1662120349651586048 +1662120349696587008 +1662120349738587904 +1662120349780588800 +1662120349822589696 +1662120349864590592 +1662120349906591488 +1662120349948592384 +1662120349990593280 +1662120350032594176 +1662120350077595136 +1662120350122596096 +1662120350164596992 +1662120350209597952 +1662120350251598848 +1662120350293599744 +1662120350338600704 +1662120350380601600 +1662120350425602560 +1662120350467603456 +1662120350509604352 +1662120350551605248 +1662120350596606208 +1662120350638607104 +1662120350683608064 +1662120350728609024 +1662120350770609920 +1662120350812610816 +1662120350857611776 +1662120350902612736 +1662120350944613632 +1662120350986614528 +1662120351028615424 +1662120351067616256 +1662120351109617152 +1662120351151618048 +1662120351193618944 +1662120351235619840 +1662120351280620800 +1662120351325621760 +1662120351367622656 +1662120351409623552 +1662120351451624448 +1662120351496625408 +1662120351547626496 +1662120351589627392 +1662120351637628416 +1662120351679629312 +1662120351721630208 +1662120351766631168 +1662120351811632128 +1662120351856633088 +1662120351898633984 +1662120351940634880 +1662120351985635840 +1662120352027636736 +1662120352069637632 +1662120352111638528 +1662120352153639424 +1662120352195640320 +1662120352240641280 +1662120352285642240 +1662120352324643072 +1662120352366643968 +1662120352408644864 +1662120352447645696 +1662120352489646592 +1662120352534647552 +1662120352573648384 +1662120352621649408 +1662120352663650304 +1662120352705651200 +1662120352750652160 +1662120352795653120 +1662120352837654016 +1662120352882654976 +1662120352924655872 +1662120352972656896 +1662120353011657728 +1662120353053658624 +1662120353098659584 +1662120353143660544 +1662120353185661440 +1662120353227662336 +1662120353272663296 +1662120353320664320 +1662120353365665280 +1662120353410666240 +1662120353452667136 +1662120353494668032 +1662120353539668992 +1662120353581669888 +1662120353632670976 +1662120353683672064 +1662120353725672960 +1662120353767673856 +1662120353812674816 +1662120353854675712 +1662120353902676736 +1662120353947677696 +1662120353992678656 +1662120354037679616 +1662120354079680512 +1662120354121681408 +1662120354166682368 +1662120354208683264 +1662120354250684160 +1662120354292685056 +1662120354334685952 +1662120354376686848 +1662120354418687744 +1662120354463688704 +1662120354505689600 +1662120354547690496 +1662120354592691456 +1662120354637692416 +1662120354682693376 +1662120354727694336 +1662120354775695360 +1662120354817696256 +1662120354859697152 +1662120354901698048 +1662120354940698880 +1662120354982699776 +1662120355024700672 +1662120355066701568 +1662120355114702592 +1662120355162703616 +1662120355210704640 +1662120355249705472 +1662120355297706496 +1662120355336707328 +1662120355378708224 +1662120355420709120 +1662120355459709952 +1662120355504710912 +1662120355555712000 +1662120355600712960 +1662120355648713984 +1662120355690714880 +1662120355732715776 +1662120355777716736 +1662120355819717632 +1662120355861718528 +1662120355903719424 +1662120355945720320 +1662120355987721216 +1662120356029722112 +1662120356077723136 +1662120356122724096 +1662120356161724928 +1662120356203725824 +1662120356245726720 +1662120356290727680 +1662120356338728704 +1662120356383729664 +1662120356428730624 +1662120356470731520 +1662120356518732544 +1662120356560733440 +1662120356605734400 +1662120356647735296 +1662120356689736192 +1662120356731737088 +1662120356773737984 +1662120356815738880 +1662120356857739776 +1662120356896740608 +1662120356944741632 +1662120356986742528 +1662120357025743360 +1662120357070744320 +1662120357109745152 +1662120357154746112 +1662120357196747008 +1662120357241747968 +1662120357277748736 +1662120357319749632 +1662120357361750528 +1662120357406751488 +1662120357454752512 +1662120357499753472 +1662120357541754368 +1662120357586755328 +1662120357625756160 +1662120357664756992 +1662120357712758016 +1662120357754758912 +1662120357793759744 +1662120357835760640 +1662120357880761600 +1662120357925762560 +1662120357973763584 +1662120358015764480 +1662120358060765440 +1662120358102766336 +1662120358147767296 +1662120358195768320 +1662120358237769216 +1662120358285770240 +1662120358327771136 +1662120358375772160 +1662120358417773056 +1662120358459773952 +1662120358501774848 +1662120358543775744 +1662120358591776768 +1662120358636777728 +1662120358678778624 +1662120358726779648 +1662120358771780608 +1662120358813781504 +1662120358852782336 +1662120358894783232 +1662120358933784064 +1662120358975784960 +1662120359020785920 +1662120359065786880 +1662120359107787776 +1662120359158788864 +1662120359200789760 +1662120359242790656 +1662120359284791552 +1662120359326792448 +1662120359368793344 +1662120359407794176 +1662120359452795136 +1662120359494796032 +1662120359539796992 +1662120359581797888 +1662120359623798784 +1662120359671799808 +1662120359713800704 +1662120359755801600 +1662120359803802624 +1662120359845803520 +1662120359887804416 +1662120359926805248 +1662120359971806208 +1662120360013807104 +1662120360064808192 +1662120360106809088 +1662120360148809984 +1662120360190810880 +1662120360232811776 +1662120360274812672 +1662120360316813568 +1662120360361814528 +1662120360403815424 +1662120360445816320 +1662120360487817216 +1662120360529818112 +1662120360571819008 +1662120360613819904 +1662120360658820864 +1662120360703821824 +1662120360748822784 +1662120360787823616 +1662120360829824512 +1662120360877825536 +1662120360919826432 +1662120360964827392 +1662120361009828352 +1662120361054829312 +1662120361105830400 +1662120361150831360 +1662120361189832192 +1662120361231833088 +1662120361276834048 +1662120361318834944 +1662120361360835840 +1662120361408836864 +1662120361450837760 +1662120361489838592 +1662120361531839488 +1662120361573840384 +1662120361615841280 +1662120361660842240 +1662120361702843136 +1662120361747844096 +1662120361786844928 +1662120361831845888 +1662120361876846848 +1662120361918847744 +1662120361963848704 +1662120362008849664 +1662120362053850624 +1662120362092851456 +1662120362137852416 +1662120362179853312 +1662120362224854272 +1662120362266855168 +1662120362308856064 +1662120362347856896 +1662120362389857792 +1662120362428858624 +1662120362470859520 +1662120362515860480 +1662120362554861312 +1662120362596862208 +1662120362641863168 +1662120362680864000 +1662120362725864960 +1662120362767865856 +1662120362815866880 +1662120362857867776 +1662120362905868800 +1662120362947869696 +1662120362995870720 +1662120363037871616 +1662120363082872576 +1662120363124873472 +1662120363166874368 +1662120363208875264 +1662120363247876096 +1662120363289876992 +1662120363331877888 +1662120363373878784 +1662120363415879680 +1662120363454880512 +1662120363499881472 +1662120363544882432 +1662120363589883392 +1662120363634884352 +1662120363676885248 +1662120363718886144 +1662120363760887040 +1662120363802887936 +1662120363847888896 +1662120363886889728 +1662120363928890624 +1662120363973891584 +1662120364018892544 +1662120364060893440 +1662120364102894336 +1662120364147895296 +1662120364192896256 +1662120364231897088 +1662120364273897984 +1662120364315898880 +1662120364360899840 +1662120364405900800 +1662120364447901696 +1662120364489902592 +1662120364531903488 +1662120364573904384 +1662120364618905344 +1662120364666906368 +1662120364708907264 +1662120364756908288 +1662120364798909184 +1662120364843910144 +1662120364888911104 +1662120364930912000 +1662120364975912960 +1662120365020913920 +1662120365065914880 +1662120365110915840 +1662120365158916864 +1662120365200917760 +1662120365242918656 +1662120365284919552 +1662120365323920384 +1662120365365921280 +1662120365407922176 +1662120365449923072 +1662120365488923904 +1662120365527924736 +1662120365566925568 +1662120365611926528 +1662120365653927424 +1662120365698928384 +1662120365743929344 +1662120365788930304 +1662120365830931200 +1662120365872932096 +1662120365917933056 +1662120365959933952 +1662120365998934784 +1662120366040935680 +1662120366082936576 +1662120366124937472 +1662120366166938368 +1662120366211939328 +1662120366253940224 +1662120366301941248 +1662120366343942144 +1662120366397943296 +1662120366442944256 +1662120366484945152 +1662120366529946112 +1662120366574947072 +1662120366619948032 +1662120366661948928 +1662120366706949888 +1662120366748950784 +1662120366790951680 +1662120366835952640 +1662120366874953472 +1662120366916954368 +1662120366955955200 +1662120366994956032 +1662120367039956992 +1662120367081957888 +1662120367126958848 +1662120367168959744 +1662120367210960640 +1662120367249961472 +1662120367294962432 +1662120367336963328 +1662120367375964160 +1662120367420965120 +1662120367465966080 +1662120367507966976 +1662120367546967808 +1662120367591968768 +1662120367636969728 +1662120367675970560 +1662120367714971392 +1662120367759972352 +1662120367801973248 +1662120367846974208 +1662120367888975104 +1662120367933976064 +1662120367975976960 +1662120368020977920 +1662120368065978880 +1662120368110979840 +1662120368152980736 +1662120368194981632 +1662120368236982528 +1662120368275983360 +1662120368320984320 +1662120368359985152 +1662120368404986112 +1662120368446987008 +1662120368485987840 +1662120368530988800 +1662120368575989760 +1662120368617990656 +1662120368662991616 +1662120368704992512 +1662120368746993408 +1662120368791994368 +1662120368833995264 +1662120368875996160 +1662120368920997120 +1662120368965998080 +1662120369010999040 +1662120369056000000 +1662120369101000960 +1662120369146001920 +1662120369188002816 +1662120369230003712 +1662120369272004608 +1662120369317005568 +1662120369359006464 +1662120369404007424 +1662120369449008384 +1662120369500009472 +1662120369542010368 +1662120369584011264 +1662120369623012096 +1662120369665012992 +1662120369704013824 +1662120369749014784 +1662120369794015744 +1662120369836016640 +1662120369878017536 +1662120369923018496 +1662120369965019392 +1662120370007020288 +1662120370046021120 +1662120370088022016 +1662120370130022912 +1662120370175023872 +1662120370217024768 +1662120370259025664 +1662120370298026496 +1662120370340027392 +1662120370385028352 +1662120370427029248 +1662120370469030144 +1662120370511031040 +1662120370556032000 +1662120370604033024 +1662120370652034048 +1662120370697035008 +1662120370739035904 +1662120370781036800 +1662120370826037760 +1662120370877038848 +1662120370919039744 +1662120370961040640 +1662120371000041472 +1662120371045042432 +1662120371087043328 +1662120371126044160 +1662120371162044928 +1662120371207045888 +1662120371252046848 +1662120371294047744 +1662120371336048640 +1662120371381049600 +1662120371423050496 +1662120371468051456 +1662120371510052352 +1662120371552053248 +1662120371597054208 +1662120371642055168 +1662120371690056192 +1662120371735057152 +1662120371786058240 +1662120371828059136 +1662120371867059968 +1662120371912060928 +1662120371960061952 +1662120372005062912 +1662120372053063936 +1662120372098064896 +1662120372143065856 +1662120372185066752 +1662120372227067648 +1662120372272068608 +1662120372317069568 +1662120372362070528 +1662120372407071488 +1662120372452072448 +1662120372494073344 +1662120372536074240 +1662120372578075136 +1662120372623076096 +1662120372668077056 +1662120372713078016 +1662120372755078912 +1662120372800079872 +1662120372839080704 +1662120372881081600 +1662120372923082496 +1662120372968083456 +1662120373016084480 +1662120373055085312 +1662120373097086208 +1662120373139087104 +1662120373178087936 +1662120373220088832 +1662120373262089728 +1662120373307090688 +1662120373355091712 +1662120373394092544 +1662120373436093440 +1662120373481094400 +1662120373523095296 +1662120373565096192 +1662120373604097024 +1662120373652098048 +1662120373697099008 +1662120373748100096 +1662120373790100992 +1662120373832101888 +1662120373874102784 +1662120373919103744 +1662120373961104640 +1662120374000105472 +1662120374045106432 +1662120374090107392 +1662120374138108416 +1662120374183109376 +1662120374225110272 +1662120374270111232 +1662120374312112128 +1662120374354113024 +1662120374396113920 +1662120374438114816 +1662120374480115712 +1662120374525116672 +1662120374564117504 +1662120374609118464 +1662120374651119360 +1662120374699120384 +1662120374741121280 +1662120374786122240 +1662120374831123200 +1662120374873124096 +1662120374918125056 +1662120374966126080 +1662120375008126976 +1662120375056128000 +1662120375101128960 +1662120375146129920 +1662120375188130816 +1662120375236131840 +1662120375278132736 +1662120375323133696 +1662120375365134592 +1662120375413135616 +1662120375455136512 +1662120375497137408 +1662120375539138304 +1662120375581139200 +1662120375626140160 +1662120375668141056 +1662120375707141888 +1662120375752142848 +1662120375794143744 +1662120375839144704 +1662120375884145664 +1662120375929146624 +1662120375968147456 +1662120376010148352 +1662120376052149248 +1662120376094150144 +1662120376136151040 +1662120376175151872 +1662120376226152960 +1662120376268153856 +1662120376310154752 +1662120376355155712 +1662120376394156544 +1662120376436157440 +1662120376481158400 +1662120376523159296 +1662120376562160128 +1662120376604161024 +1662120376646161920 +1662120376688162816 +1662120376730163712 +1662120376775164672 +1662120376817165568 +1662120376859166464 +1662120376907167488 +1662120376952168448 +1662120376991169280 +1662120377036170240 +1662120377081171200 +1662120377123172096 +1662120377165172992 +1662120377204173824 +1662120377246174720 +1662120377288175616 +1662120377330176512 +1662120377372177408 +1662120377414178304 +1662120377456179200 +1662120377495180032 +1662120377537180928 +1662120377579181824 +1662120377621182720 +1662120377666183680 +1662120377711184640 +1662120377759185664 +1662120377801186560 +1662120377843187456 +1662120377882188288 +1662120377927189248 +1662120377966190080 +1662120378011191040 +1662120378053191936 +1662120378098192896 +1662120378140193792 +1662120378185194752 +1662120378224195584 +1662120378266196480 +1662120378308197376 +1662120378350198272 +1662120378392199168 +1662120378440200192 +1662120378482201088 +1662120378527202048 +1662120378569202944 +1662120378611203840 +1662120378656204800 +1662120378701205760 +1662120378746206720 +1662120378791207680 +1662120378833208576 +1662120378875209472 +1662120378917210368 +1662120378959211264 +1662120378998212096 +1662120379040212992 +1662120379082213888 +1662120379121214720 +1662120379160215552 +1662120379202216448 +1662120379247217408 +1662120379289218304 +1662120379331219200 +1662120379373220096 +1662120379418221056 +1662120379460221952 +1662120379505222912 +1662120379547223808 +1662120379604225024 +1662120379652226048 +1662120379691226880 +1662120379733227776 +1662120379775228672 +1662120379820229632 +1662120379868230656 +1662120379913231616 +1662120379955232512 +1662120379997233408 +1662120380042234368 +1662120380078235136 +1662120380123236096 +1662120380165236992 +1662120380216238080 +1662120380258238976 +1662120380300239872 +1662120380339240704 +1662120380384241664 +1662120380426242560 +1662120380468243456 +1662120380513244416 +1662120380564245504 +1662120380609246464 +1662120380654247424 +1662120380693248256 +1662120380735249152 +1662120380777250048 +1662120380816250880 +1662120380858251776 +1662120380906252800 +1662120380954253824 +1662120380999254784 +1662120381041255680 +1662120381083256576 +1662120381128257536 +1662120381170258432 +1662120381212259328 +1662120381251260160 +1662120381293261056 +1662120381335261952 +1662120381377262848 +1662120381428263936 +1662120381473264896 +1662120381512265728 +1662120381557266688 +1662120381599267584 +1662120381641268480 +1662120381686269440 +1662120381734270464 +1662120381776271360 +1662120381815272192 +1662120381857273088 +1662120381902274048 +1662120381950275072 +1662120381995276032 +1662120382037276928 +1662120382082277888 +1662120382127278848 +1662120382169279744 +1662120382214280704 +1662120382256281600 +1662120382301282560 +1662120382343283456 +1662120382385284352 +1662120382424285184 +1662120382463286016 +1662120382508286976 +1662120382547287808 +1662120382589288704 +1662120382631289600 +1662120382676290560 +1662120382721291520 +1662120382763292416 +1662120382808293376 +1662120382850294272 +1662120382898295296 +1662120382937296128 +1662120382976296960 +1662120383018297856 +1662120383063298816 +1662120383105299712 +1662120383147300608 +1662120383192301568 +1662120383234302464 +1662120383279303424 +1662120383321304320 +1662120383366305280 +1662120383417306368 +1662120383462307328 +1662120383504308224 +1662120383552309248 +1662120383594310144 +1662120383636311040 +1662120383678311936 +1662120383720312832 +1662120383768313856 +1662120383813314816 +1662120383858315776 +1662120383903316736 +1662120383945317632 +1662120383987318528 +1662120384032319488 +1662120384071320320 +1662120384113321216 +1662120384155322112 +1662120384200323072 +1662120384242323968 +1662120384287324928 +1662120384329325824 +1662120384371326720 +1662120384413327616 +1662120384455328512 +1662120384500329472 +1662120384542330368 +1662120384587331328 +1662120384632332288 +1662120384674333184 +1662120384719334144 +1662120384761335040 +1662120384803335936 +1662120384845336832 +1662120384890337792 +1662120384935338752 +1662120384974339584 +1662120385025340672 +1662120385070341632 +1662120385112342528 +1662120385160343552 +1662120385202344448 +1662120385241345280 +1662120385283346176 +1662120385325347072 +1662120385370348032 +1662120385418349056 +1662120385463350016 +1662120385514351104 +1662120385556352000 +1662120385598352896 +1662120385637353728 +1662120385679354624 +1662120385721355520 +1662120385766356480 +1662120385805357312 +1662120385847358208 +1662120385889359104 +1662120385934360064 +1662120385976360960 +1662120386021361920 +1662120386066362880 +1662120386108363776 +1662120386147364608 +1662120386186365440 +1662120386231366400 +1662120386270367232 +1662120386315368192 +1662120386360369152 +1662120386405370112 +1662120386447371008 +1662120386486371840 +1662120386531372800 +1662120386576373760 +1662120386615374592 +1662120386660375552 +1662120386699376384 +1662120386738377216 +1662120386783378176 +1662120386822379008 +1662120386870380032 +1662120386912380928 +1662120386951381760 +1662120386993382656 +1662120387032383488 +1662120387083384576 +1662120387122385408 +1662120387164386304 +1662120387206387200 +1662120387248388096 +1662120387293389056 +1662120387335389952 +1662120387371390720 +1662120387416391680 +1662120387461392640 +1662120387503393536 +1662120387548394496 +1662120387590395392 +1662120387629396224 +1662120387668397056 +1662120387713398016 +1662120387755398912 +1662120387800399872 +1662120387842400768 +1662120387887401728 +1662120387929402624 +1662120387971403520 +1662120388016404480 +1662120388055405312 +1662120388097406208 +1662120388142407168 +1662120388184408064 +1662120388223408896 +1662120388265409792 +1662120388304410624 +1662120388346411520 +1662120388388412416 +1662120388430413312 +1662120388472414208 +1662120388520415232 +1662120388565416192 +1662120388607417088 +1662120388649417984 +1662120388688418816 +1662120388733419776 +1662120388778420736 +1662120388823421696 +1662120388862422528 +1662120388904423424 +1662120388946424320 +1662120388991425280 +1662120389036426240 +1662120389078427136 +1662120389123428096 +1662120389165428992 +1662120389204429824 +1662120389252430848 +1662120389291431680 +1662120389333432576 +1662120389375433472 +1662120389414434304 +1662120389456435200 +1662120389498436096 +1662120389540436992 +1662120389585437952 +1662120389627438848 +1662120389669439744 +1662120389711440640 +1662120389756441600 +1662120389798442496 +1662120389846443520 +1662120389888444416 +1662120389933445376 +1662120389972446208 +1662120390014447104 +1662120390056448000 +1662120390101448960 +1662120390143449856 +1662120390185450752 +1662120390233451776 +1662120390278452736 +1662120390323453696 +1662120390365454592 +1662120390410455552 +1662120390455456512 +1662120390497457408 +1662120390533458176 +1662120390575459072 +1662120390617459968 +1662120390659460864 +1662120390704461824 +1662120390749462784 +1662120390791463680 +1662120390836464640 +1662120390878465536 +1662120390923466496 +1662120390974467584 +1662120391013468416 +1662120391055469312 +1662120391097470208 +1662120391145471232 +1662120391187472128 +1662120391229473024 +1662120391271473920 +1662120391319474944 +1662120391358475776 +1662120391403476736 +1662120391445477632 +1662120391487478528 +1662120391529479424 +1662120391571480320 +1662120391613481216 +1662120391655482112 +1662120391700483072 +1662120391739483904 +1662120391784484864 +1662120391835485952 +1662120391883486976 +1662120391925487872 +1662120391967488768 +1662120392012489728 +1662120392057490688 +1662120392099491584 +1662120392144492544 +1662120392186493440 +1662120392231494400 +1662120392273495296 +1662120392312496128 +1662120392357497088 +1662120392399497984 +1662120392444498944 +1662120392492499968 +1662120392543501056 +1662120392585501952 +1662120392630502912 +1662120392669503744 +1662120392711504640 +1662120392753505536 +1662120392801506560 +1662120392846507520 +1662120392891508480 +1662120392933509376 +1662120392981510400 +1662120393026511360 +1662120393068512256 +1662120393113513216 +1662120393158514176 +1662120393200515072 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track0.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track0.txt new file mode 100644 index 0000000000..d40335079d --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track0.txt @@ -0,0 +1,2847 @@ +1661868173547958016 +1661868173589958912 +1661868173628959744 +1661868173676960768 +1661868173715961600 +1661868173760962560 +1661868173802963456 +1661868173844964352 +1661868173886965248 +1661868173931966208 +1661868173973967104 +1661868174021968128 +1661868174063969024 +1661868174105969920 +1661868174147970816 +1661868174183971584 +1661868174225972480 +1661868174264973312 +1661868174306974208 +1661868174354975232 +1661868174399976192 +1661868174441977088 +1661868174483977984 +1661868174525978880 +1661868174564979712 +1661868174603980544 +1661868174645981440 +1661868174693982464 +1661868174735983360 +1661868174780984320 +1661868174828985344 +1661868174870986240 +1661868174912987136 +1661868174960988160 +1661868175002989056 +1661868175044989952 +1661868175086990848 +1661868175128991744 +1661868175170992640 +1661868175209993472 +1661868175251994368 +1661868175302995456 +1661868175341996288 +1661868175383997184 +1661868175425998080 +1661868175470999040 +1661868175509999872 +1661868175549000704 +1661868175591001600 +1661868175639002624 +1661868175681003520 +1661868175723004416 +1661868175765005312 +1661868175810006272 +1661868175849007104 +1661868175897008128 +1661868175939009024 +1661868175981009920 +1661868176029010944 +1661868176071011840 +1661868176113012736 +1661868176152013568 +1661868176197014528 +1661868176242015488 +1661868176284016384 +1661868176323017216 +1661868176368018176 +1661868176410019072 +1661868176452019968 +1661868176497020928 +1661868176536021760 +1661868176578022656 +1661868176617023488 +1661868176659024384 +1661868176701025280 +1661868176743026176 +1661868176785027072 +1661868176824027904 +1661868176869028864 +1661868176914029824 +1661868176953030656 +1661868176992031488 +1661868177034032384 +1661868177076033280 +1661868177118034176 +1661868177163035136 +1661868177208036096 +1661868177244036864 +1661868177283037696 +1661868177325038592 +1661868177367039488 +1661868177409040384 +1661868177451041280 +1661868177493042176 +1661868177535043072 +1661868177580044032 +1661868177625044992 +1661868177670045952 +1661868177712046848 +1661868177748047616 +1661868177793048576 +1661868177838049536 +1661868177877050368 +1661868177916051200 +1661868177958052096 +1661868178003053056 +1661868178048054016 +1661868178090054912 +1661868178132055808 +1661868178171056640 +1661868178207057408 +1661868178249058304 +1661868178297059328 +1661868178339060224 +1661868178384061184 +1661868178426062080 +1661868178468062976 +1661868178510063872 +1661868178546064640 +1661868178588065536 +1661868178630066432 +1661868178669067264 +1661868178711068160 +1661868178759069184 +1661868178804070144 +1661868178846071040 +1661868178888071936 +1661868178930072832 +1661868178972073728 +1661868179014074624 +1661868179059075584 +1661868179107076608 +1661868179152077568 +1661868179191078400 +1661868179233079296 +1661868179278080256 +1661868179320081152 +1661868179362082048 +1661868179407083008 +1661868179452083968 +1661868179494084864 +1661868179539085824 +1661868179581086720 +1661868179623087616 +1661868179665088512 +1661868179713089536 +1661868179758090496 +1661868179803091456 +1661868179845092352 +1661868179887093248 +1661868179926094080 +1661868179968094976 +1661868180010095872 +1661868180049096704 +1661868180088097536 +1661868180130098432 +1661868180175099392 +1661868180217100288 +1661868180256101120 +1661868180298102016 +1661868180340102912 +1661868180385103872 +1661868180427104768 +1661868180466105600 +1661868180508106496 +1661868180550107392 +1661868180589108224 +1661868180628109056 +1661868180670109952 +1661868180715110912 +1661868180760111872 +1661868180802112768 +1661868180844113664 +1661868180886114560 +1661868180922115328 +1661868180967116288 +1661868181009117184 +1661868181051118080 +1661868181090118912 +1661868181132119808 +1661868181174120704 +1661868181216121600 +1661868181258122496 +1661868181303123456 +1661868181348124416 +1661868181387125248 +1661868181432126208 +1661868181474127104 +1661868181516128000 +1661868181558128896 +1661868181597129728 +1661868181636130560 +1661868181678131456 +1661868181720132352 +1661868181762133248 +1661868181804134144 +1661868181846135040 +1661868181885135872 +1661868181927136768 +1661868181966137600 +1661868182008138496 +1661868182050139392 +1661868182095140352 +1661868182140141312 +1661868182182142208 +1661868182221143040 +1661868182263143936 +1661868182302144768 +1661868182344145664 +1661868182386146560 +1661868182428147456 +1661868182464148224 +1661868182506149120 +1661868182551150080 +1661868182590150912 +1661868182635151872 +1661868182677152768 +1661868182716153600 +1661868182758154496 +1661868182800155392 +1661868182839156224 +1661868182884157184 +1661868182926158080 +1661868182971159040 +1661868183010159872 +1661868183049160704 +1661868183091161600 +1661868183130162432 +1661868183172163328 +1661868183214164224 +1661868183256165120 +1661868183298166016 +1661868183340166912 +1661868183382167808 +1661868183427168768 +1661868183469169664 +1661868183511170560 +1661868183550171392 +1661868183595172352 +1661868183637173248 +1661868183679174144 +1661868183718174976 +1661868183769176064 +1661868183811176960 +1661868183850177792 +1661868183892178688 +1661868183931179520 +1661868183973180416 +1661868184018181376 +1661868184060182272 +1661868184102183168 +1661868184147184128 +1661868184192185088 +1661868184240186112 +1661868184282187008 +1661868184324187904 +1661868184366188800 +1661868184411189760 +1661868184447190528 +1661868184486191360 +1661868184528192256 +1661868184573193216 +1661868184618194176 +1661868184660195072 +1661868184705196032 +1661868184747196928 +1661868184786197760 +1661868184831198720 +1661868184873199616 +1661868184921200640 +1661868184960201472 +1661868185005202432 +1661868185047203328 +1661868185086204160 +1661868185125204992 +1661868185170205952 +1661868185215206912 +1661868185257207808 +1661868185299208704 +1661868185341209600 +1661868185383210496 +1661868185422211328 +1661868185464212224 +1661868185506213120 +1661868185545213952 +1661868185590214912 +1661868185632215808 +1661868185671216640 +1661868185707217408 +1661868185752218368 +1661868185794219264 +1661868185839220224 +1661868185875220992 +1661868185914221824 +1661868185962222848 +1661868186004223744 +1661868186046224640 +1661868186091225600 +1661868186130226432 +1661868186175227392 +1661868186220228352 +1661868186262229248 +1661868186307230208 +1661868186349231104 +1661868186391232000 +1661868186433232896 +1661868186478233856 +1661868186520234752 +1661868186562235648 +1661868186601236480 +1661868186643237376 +1661868186679238144 +1661868186718238976 +1661868186760239872 +1661868186805240832 +1661868186844241664 +1661868186883242496 +1661868186925243392 +1661868186964244224 +1661868187006245120 +1661868187048246016 +1661868187090246912 +1661868187129247744 +1661868187174248704 +1661868187216249600 +1661868187255250432 +1661868187297251328 +1661868187339252224 +1661868187381253120 +1661868187423254016 +1661868187465254912 +1661868187507255808 +1661868187549256704 +1661868187597257728 +1661868187639258624 +1661868187681259520 +1661868187726260480 +1661868187768261376 +1661868187807262208 +1661868187846263040 +1661868187888263936 +1661868187930264832 +1661868187978265856 +1661868188020266752 +1661868188062267648 +1661868188101268480 +1661868188143269376 +1661868188185270272 +1661868188224271104 +1661868188263271936 +1661868188302272768 +1661868188341273600 +1661868188380274432 +1661868188419275264 +1661868188464276224 +1661868188509277184 +1661868188551278080 +1661868188596279040 +1661868188641280000 +1661868188686280960 +1661868188728281856 +1661868188776282880 +1661868188824283904 +1661868188869284864 +1661868188911285760 +1661868188950286592 +1661868188992287488 +1661868189034288384 +1661868189079289344 +1661868189121290240 +1661868189163291136 +1661868189205292032 +1661868189247292928 +1661868189292293888 +1661868189328294656 +1661868189370295552 +1661868189412296448 +1661868189457297408 +1661868189502298368 +1661868189541299200 +1661868189580300032 +1661868189616300800 +1661868189661301760 +1661868189703302656 +1661868189742303488 +1661868189784304384 +1661868189832305408 +1661868189871306240 +1661868189913307136 +1661868189949307904 +1661868189988308736 +1661868190030309632 +1661868190072310528 +1661868190114311424 +1661868190156312320 +1661868190195313152 +1661868190237314048 +1661868190276314880 +1661868190321315840 +1661868190363316736 +1661868190405317632 +1661868190441318400 +1661868190486319360 +1661868190528320256 +1661868190570321152 +1661868190609321984 +1661868190654322944 +1661868190699323904 +1661868190741324800 +1661868190780325632 +1661868190822326528 +1661868190864327424 +1661868190906328320 +1661868190945329152 +1661868190990330112 +1661868191041331200 +1661868191086332160 +1661868191128333056 +1661868191170333952 +1661868191212334848 +1661868191254335744 +1661868191296336640 +1661868191338337536 +1661868191377338368 +1661868191425339392 +1661868191464340224 +1661868191509341184 +1661868191554342144 +1661868191596343040 +1661868191638343936 +1661868191683344896 +1661868191722345728 +1661868191776346880 +1661868191818347776 +1661868191857348608 +1661868191902349568 +1661868191941350400 +1661868191983351296 +1661868192028352256 +1661868192070353152 +1661868192112354048 +1661868192151354880 +1661868192193355776 +1661868192235356672 +1661868192277357568 +1661868192319358464 +1661868192361359360 +1661868192400360192 +1661868192442361088 +1661868192484361984 +1661868192526362880 +1661868192568363776 +1661868192613364736 +1661868192655365632 +1661868192700366592 +1661868192739367424 +1661868192781368320 +1661868192823369216 +1661868192862370048 +1661868192907371008 +1661868192946371840 +1661868192988372736 +1661868193027373568 +1661868193066374400 +1661868193105375232 +1661868193147376128 +1661868193192377088 +1661868193234377984 +1661868193276378880 +1661868193318379776 +1661868193354380544 +1661868193396381440 +1661868193441382400 +1661868193489383424 +1661868193531384320 +1661868193570385152 +1661868193609385984 +1661868193651386880 +1661868193693387776 +1661868193735388672 +1661868193789389824 +1661868193828390656 +1661868193870391552 +1661868193909392384 +1661868193951393280 +1661868193993394176 +1661868194038395136 +1661868194074395904 +1661868194119396864 +1661868194161397760 +1661868194203398656 +1661868194245399552 +1661868194287400448 +1661868194329401344 +1661868194371402240 +1661868194413403136 +1661868194455404032 +1661868194497404928 +1661868194539405824 +1661868194581406720 +1661868194620407552 +1661868194662408448 +1661868194707409408 +1661868194752410368 +1661868194791411200 +1661868194830412032 +1661868194869412864 +1661868194914413824 +1661868194956414720 +1661868194998415616 +1661868195040416512 +1661868195079417344 +1661868195121418240 +1661868195163419136 +1661868195205420032 +1661868195244420864 +1661868195286421760 +1661868195331422720 +1661868195376423680 +1661868195418424576 +1661868195460425472 +1661868195508426496 +1661868195550427392 +1661868195592428288 +1661868195640429312 +1661868195682430208 +1661868195724431104 +1661868195769432064 +1661868195811432960 +1661868195853433856 +1661868195895434752 +1661868195931435520 +1661868195973436416 +1661868196015437312 +1661868196060438272 +1661868196102439168 +1661868196147440128 +1661868196195441152 +1661868196237442048 +1661868196285443072 +1661868196330444032 +1661868196375444992 +1661868196414445824 +1661868196453446656 +1661868196495447552 +1661868196537448448 +1661868196579449344 +1661868196624450304 +1661868196666451200 +1661868196711452160 +1661868196747452928 +1661868196789453824 +1661868196831454720 +1661868196873455616 +1661868196921456640 +1661868196969457664 +1661868197020458752 +1661868197059459584 +1661868197098460416 +1661868197140461312 +1661868197182462208 +1661868197221463040 +1661868197263463936 +1661868197302464768 +1661868197344465664 +1661868197386466560 +1661868197428467456 +1661868197470468352 +1661868197509469184 +1661868197554470144 +1661868197593470976 +1661868197635471872 +1661868197677472768 +1661868197716473600 +1661868197758474496 +1661868197800475392 +1661868197848476416 +1661868197890477312 +1661868197932478208 +1661868197971479040 +1661868198010479872 +1661868198052480768 +1661868198100481792 +1661868198139482624 +1661868198181483520 +1661868198220484352 +1661868198262485248 +1661868198304486144 +1661868198349487104 +1661868198394488064 +1661868198439489024 +1661868198481489920 +1661868198523490816 +1661868198559491584 +1661868198604492544 +1661868198646493440 +1661868198685494272 +1661868198730495232 +1661868198775496192 +1661868198817497088 +1661868198862498048 +1661868198904498944 +1661868198946499840 +1661868198988500736 +1661868199030501632 +1661868199072502528 +1661868199114503424 +1661868199156504320 +1661868199198505216 +1661868199243506176 +1661868199285507072 +1661868199333508096 +1661868199375508992 +1661868199420509952 +1661868199462510848 +1661868199504511744 +1661868199546512640 +1661868199588513536 +1661868199630514432 +1661868199672515328 +1661868199714516224 +1661868199753517056 +1661868199795517952 +1661868199834518784 +1661868199876519680 +1661868199915520512 +1661868199954521344 +1661868199996522240 +1661868200038523136 +1661868200080524032 +1661868200119524864 +1661868200158525696 +1661868200200526592 +1661868200242527488 +1661868200284528384 +1661868200329529344 +1661868200365530112 +1661868200410531072 +1661868200452531968 +1661868200491532800 +1661868200533533696 +1661868200572534528 +1661868200614535424 +1661868200662536448 +1661868200710537472 +1661868200755538432 +1661868200797539328 +1661868200836540160 +1661868200872540928 +1661868200914541824 +1661868200956542720 +1661868200998543616 +1661868201037544448 +1661868201076545280 +1661868201118546176 +1661868201154546944 +1661868201193547776 +1661868201235548672 +1661868201280549632 +1661868201319550464 +1661868201364551424 +1661868201406552320 +1661868201451553280 +1661868201493554176 +1661868201532555008 +1661868201574555904 +1661868201616556800 +1661868201658557696 +1661868201700558592 +1661868201739559424 +1661868201778560256 +1661868201820561152 +1661868201862562048 +1661868201913563136 +1661868201955564032 +1661868202000564992 +1661868202042565888 +1661868202084566784 +1661868202129567744 +1661868202168568576 +1661868202210569472 +1661868202252570368 +1661868202288571136 +1661868202330572032 +1661868202372572928 +1661868202414573824 +1661868202462574848 +1661868202504575744 +1661868202546576640 +1661868202588577536 +1661868202630578432 +1661868202675579392 +1661868202717580288 +1661868202756581120 +1661868202801582080 +1661868202846583040 +1661868202885583872 +1661868202927584768 +1661868202972585728 +1661868203011586560 +1661868203056587520 +1661868203101588480 +1661868203140589312 +1661868203182590208 +1661868203230591232 +1661868203272592128 +1661868203314593024 +1661868203359593984 +1661868203401594880 +1661868203443595776 +1661868203485596672 +1661868203527597568 +1661868203569598464 +1661868203611599360 +1661868203653600256 +1661868203695601152 +1661868203737602048 +1661868203779602944 +1661868203824603904 +1661868203863604736 +1661868203905605632 +1661868203947606528 +1661868203989607424 +1661868204034608384 +1661868204079609344 +1661868204121610240 +1661868204163611136 +1661868204205612032 +1661868204247612928 +1661868204289613824 +1661868204328614656 +1661868204367615488 +1661868204400616192 +1661868204442617088 +1661868204490618112 +1661868204532619008 +1661868204574619904 +1661868204616620800 +1661868204658621696 +1661868204697622528 +1661868204733623296 +1661868204775624192 +1661868204820625152 +1661868204856625920 +1661868204898626816 +1661868204943627776 +1661868204988628736 +1661868205033629696 +1661868205075630592 +1661868205114631424 +1661868205156632320 +1661868205204633344 +1661868205249634304 +1661868205288635136 +1661868205330636032 +1661868205372636928 +1661868205414637824 +1661868205456638720 +1661868205498639616 +1661868205537640448 +1661868205579641344 +1661868205621642240 +1661868205654642944 +1661868205696643840 +1661868205738644736 +1661868205789645824 +1661868205828646656 +1661868205870647552 +1661868205915648512 +1661868205960649472 +1661868206002650368 +1661868206044651264 +1661868206083652096 +1661868206125652992 +1661868206170653952 +1661868206212654848 +1661868206254655744 +1661868206299656704 +1661868206341657600 +1661868206380658432 +1661868206422659328 +1661868206467660288 +1661868206509661184 +1661868206548662016 +1661868206590662912 +1661868206638663936 +1661868206677664768 +1661868206722665728 +1661868206767666688 +1661868206809667584 +1661868206851668480 +1661868206890669312 +1661868206932670208 +1661868206971671040 +1661868207013671936 +1661868207055672832 +1661868207097673728 +1661868207139674624 +1661868207187675648 +1661868207229676544 +1661868207271677440 +1661868207313678336 +1661868207355679232 +1661868207397680128 +1661868207442681088 +1661868207487682048 +1661868207526682880 +1661868207568683776 +1661868207613684736 +1661868207658685696 +1661868207700686592 +1661868207742687488 +1661868207790688512 +1661868207829689344 +1661868207868690176 +1661868207913691136 +1661868207955692032 +1661868207997692928 +1661868208039693824 +1661868208084694784 +1661868208132695808 +1661868208177696768 +1661868208216697600 +1661868208255698432 +1661868208297699328 +1661868208339700224 +1661868208375700992 +1661868208417701888 +1661868208459702784 +1661868208501703680 +1661868208549704704 +1661868208591705600 +1661868208630706432 +1661868208672707328 +1661868208714708224 +1661868208756709120 +1661868208795709952 +1661868208831710720 +1661868208876711680 +1661868208918712576 +1661868208960713472 +1661868209002714368 +1661868209047715328 +1661868209089716224 +1661868209131717120 +1661868209173718016 +1661868209218718976 +1661868209260719872 +1661868209299720704 +1661868209341721600 +1661868209386722560 +1661868209434723584 +1661868209476724480 +1661868209518725376 +1661868209563726336 +1661868209608727296 +1661868209647728128 +1661868209686728960 +1661868209731729920 +1661868209773730816 +1661868209809731584 +1661868209851732480 +1661868209899733504 +1661868209941734400 +1661868209980735232 +1661868210022736128 +1661868210067737088 +1661868210109737984 +1661868210148738816 +1661868210187739648 +1661868210226740480 +1661868210268741376 +1661868210310742272 +1661868210349743104 +1661868210391744000 +1661868210430744832 +1661868210472745728 +1661868210514746624 +1661868210556747520 +1661868210601748480 +1661868210640749312 +1661868210682750208 +1661868210724751104 +1661868210766752000 +1661868210811752960 +1661868210856753920 +1661868210898754816 +1661868210937755648 +1661868210979756544 +1661868211021757440 +1661868211063758336 +1661868211102759168 +1661868211150760192 +1661868211195761152 +1661868211237762048 +1661868211273762816 +1661868211315763712 +1661868211357764608 +1661868211396765440 +1661868211441766400 +1661868211480767232 +1661868211522768128 +1661868211567769088 +1661868211606769920 +1661868211648770816 +1661868211687771648 +1661868211729772544 +1661868211771773440 +1661868211813774336 +1661868211861775360 +1661868211906776320 +1661868211948777216 +1661868211993778176 +1661868212041779200 +1661868212083780096 +1661868212131781120 +1661868212173782016 +1661868212215782912 +1661868212257783808 +1661868212302784768 +1661868212347785728 +1661868212386786560 +1661868212431787520 +1661868212473788416 +1661868212515789312 +1661868212557790208 +1661868212599791104 +1661868212641792000 +1661868212683792896 +1661868212725793792 +1661868212767794688 +1661868212809795584 +1661868212851796480 +1661868212893797376 +1661868212935798272 +1661868212971799040 +1661868213016800000 +1661868213055800832 +1661868213094801664 +1661868213139802624 +1661868213178803456 +1661868213220804352 +1661868213259805184 +1661868213307806208 +1661868213343806976 +1661868213391808000 +1661868213430808832 +1661868213475809792 +1661868213523810816 +1661868213568811776 +1661868213610812672 +1661868213649813504 +1661868213691814400 +1661868213733815296 +1661868213772816128 +1661868213814817024 +1661868213850817792 +1661868213892818688 +1661868213937819648 +1661868213979820544 +1661868214015821312 +1661868214060822272 +1661868214099823104 +1661868214141824000 +1661868214180824832 +1661868214222825728 +1661868214264826624 +1661868214306827520 +1661868214351828480 +1661868214393829376 +1661868214432830208 +1661868214471831040 +1661868214513831936 +1661868214555832832 +1661868214594833664 +1661868214636834560 +1661868214678835456 +1661868214720836352 +1661868214762837248 +1661868214807838208 +1661868214849839104 +1661868214885839872 +1661868214927840768 +1661868214972841728 +1661868215014842624 +1661868215059843584 +1661868215101844480 +1661868215140845312 +1661868215188846336 +1661868215230847232 +1661868215278848256 +1661868215320849152 +1661868215362850048 +1661868215401850880 +1661868215443851776 +1661868215488852736 +1661868215530853632 +1661868215569854464 +1661868215611855360 +1661868215650856192 +1661868215692857088 +1661868215734857984 +1661868215776858880 +1661868215815859712 +1661868215860860672 +1661868215902861568 +1661868215944862464 +1661868215986863360 +1661868216034864384 +1661868216076865280 +1661868216121866240 +1661868216163867136 +1661868216202867968 +1661868216250868992 +1661868216295869952 +1661868216337870848 +1661868216385871872 +1661868216427872768 +1661868216475873792 +1661868216520874752 +1661868216562875648 +1661868216607876608 +1661868216649877504 +1661868216700878592 +1661868216742879488 +1661868216784880384 +1661868216823881216 +1661868216865882112 +1661868216913883136 +1661868216952883968 +1661868216991884800 +1661868217033885696 +1661868217075886592 +1661868217117887488 +1661868217162888448 +1661868217198889216 +1661868217240890112 +1661868217282891008 +1661868217321891840 +1661868217363892736 +1661868217405893632 +1661868217447894528 +1661868217489895424 +1661868217534896384 +1661868217576897280 +1661868217618898176 +1661868217666899200 +1661868217711900160 +1661868217753901056 +1661868217795901952 +1661868217837902848 +1661868217879903744 +1661868217921904640 +1661868217963905536 +1661868218005906432 +1661868218047907328 +1661868218092908288 +1661868218134909184 +1661868218182910208 +1661868218224911104 +1661868218266912000 +1661868218305912832 +1661868218350913792 +1661868218392914688 +1661868218437915648 +1661868218479916544 +1661868218521917440 +1661868218563918336 +1661868218605919232 +1661868218644920064 +1661868218686920960 +1661868218728921856 +1661868218770922752 +1661868218815923712 +1661868218857924608 +1661868218896925440 +1661868218944926464 +1661868218986927360 +1661868219028928256 +1661868219073929216 +1661868219115930112 +1661868219154930944 +1661868219202931968 +1661868219247932928 +1661868219295933952 +1661868219343934976 +1661868219385935872 +1661868219430936832 +1661868219469937664 +1661868219511938560 +1661868219553939456 +1661868219595940352 +1661868219637941248 +1661868219676942080 +1661868219715942912 +1661868219757943808 +1661868219796944640 +1661868219841945600 +1661868219883946496 +1661868219925947392 +1661868219967948288 +1661868220006949120 +1661868220045949952 +1661868220087950848 +1661868220129951744 +1661868220174952704 +1661868220213953536 +1661868220252954368 +1661868220291955200 +1661868220333956096 +1661868220375956992 +1661868220420957952 +1661868220462958848 +1661868220504959744 +1661868220549960704 +1661868220594961664 +1661868220636962560 +1661868220678963456 +1661868220717964288 +1661868220762965248 +1661868220804966144 +1661868220855967232 +1661868220897968128 +1661868220942969088 +1661868220984969984 +1661868221026970880 +1661868221068971776 +1661868221107972608 +1661868221146973440 +1661868221185974272 +1661868221224975104 +1661868221269976064 +1661868221311976960 +1661868221350977792 +1661868221395978752 +1661868221440979712 +1661868221479980544 +1661868221518981376 +1661868221560982272 +1661868221602983168 +1661868221647984128 +1661868221686984960 +1661868221731985920 +1661868221779986944 +1661868221821987840 +1661868221866988800 +1661868221908989696 +1661868221947990528 +1661868221995991552 +1661868222034992384 +1661868222076993280 +1661868222121994240 +1661868222166995200 +1661868222211996160 +1661868222253997056 +1661868222292997888 +1661868222331998720 +1661868222373999616 +1661868222416000512 +1661868222458001408 +1661868222500002304 +1661868222548003328 +1661868222584004096 +1661868222626004992 +1661868222671005952 +1661868222713006848 +1661868222764007936 +1661868222806008832 +1661868222848009728 +1661868222890010624 +1661868222932011520 +1661868222974012416 +1661868223022013440 +1661868223070014464 +1661868223109015296 +1661868223151016192 +1661868223190017024 +1661868223241018112 +1661868223283019008 +1661868223328019968 +1661868223367020800 +1661868223409021696 +1661868223457022720 +1661868223499023616 +1661868223541024512 +1661868223583025408 +1661868223625026304 +1661868223670027264 +1661868223709028096 +1661868223751028992 +1661868223793029888 +1661868223841030912 +1661868223883031808 +1661868223925032704 +1661868223967033600 +1661868224006034432 +1661868224045035264 +1661868224087036160 +1661868224129037056 +1661868224168037888 +1661868224207038720 +1661868224261039872 +1661868224300040704 +1661868224342041600 +1661868224384042496 +1661868224432043520 +1661868224474044416 +1661868224519045376 +1661868224561046272 +1661868224603047168 +1661868224645048064 +1661868224687048960 +1661868224732049920 +1661868224774050816 +1661868224816051712 +1661868224855052544 +1661868224897053440 +1661868224939054336 +1661868224981055232 +1661868225023056128 +1661868225074057216 +1661868225116058112 +1661868225161059072 +1661868225203059968 +1661868225248060928 +1661868225290061824 +1661868225338062848 +1661868225380063744 +1661868225422064640 +1661868225467065600 +1661868225509066496 +1661868225545067264 +1661868225590068224 +1661868225638069248 +1661868225686070272 +1661868225728071168 +1661868225770072064 +1661868225818073088 +1661868225860073984 +1661868225902074880 +1661868225944075776 +1661868225992076800 +1661868226034077696 +1661868226076078592 +1661868226118079488 +1661868226160080384 +1661868226199081216 +1661868226241082112 +1661868226289083136 +1661868226334084096 +1661868226376084992 +1661868226418085888 +1661868226454086656 +1661868226496087552 +1661868226535088384 +1661868226586089472 +1661868226628090368 +1661868226670091264 +1661868226709092096 +1661868226751092992 +1661868226799094016 +1661868226838094848 +1661868226883095808 +1661868226925096704 +1661868226967097600 +1661868227012098560 +1661868227054099456 +1661868227093100288 +1661868227141101312 +1661868227186102272 +1661868227225103104 +1661868227270104064 +1661868227312104960 +1661868227354105856 +1661868227396106752 +1661868227441107712 +1661868227483108608 +1661868227525109504 +1661868227567110400 +1661868227609111296 +1661868227651112192 +1661868227690113024 +1661868227732113920 +1661868227774114816 +1661868227819115776 +1661868227867116800 +1661868227912117760 +1661868227954118656 +1661868227996119552 +1661868228038120448 +1661868228086121472 +1661868228134122496 +1661868228179123456 +1661868228221124352 +1661868228263125248 +1661868228305126144 +1661868228353127168 +1661868228395128064 +1661868228434128896 +1661868228479129856 +1661868228524130816 +1661868228569131776 +1661868228611132672 +1661868228656133632 +1661868228698134528 +1661868228737135360 +1661868228776136192 +1661868228824137216 +1661868228866138112 +1661868228908139008 +1661868228950139904 +1661868228992140800 +1661868229031141632 +1661868229073142528 +1661868229124143616 +1661868229166144512 +1661868229208145408 +1661868229253146368 +1661868229295147264 +1661868229337148160 +1661868229379149056 +1661868229421149952 +1661868229463150848 +1661868229508151808 +1661868229547152640 +1661868229592153600 +1661868229634154496 +1661868229673155328 +1661868229715156224 +1661868229757157120 +1661868229796157952 +1661868229838158848 +1661868229880159744 +1661868229931160832 +1661868229973161728 +1661868230015162624 +1661868230057163520 +1661868230099164416 +1661868230141165312 +1661868230186166272 +1661868230228167168 +1661868230270168064 +1661868230309168896 +1661868230354169856 +1661868230396170752 +1661868230435171584 +1661868230480172544 +1661868230525173504 +1661868230561174272 +1661868230603175168 +1661868230642176000 +1661868230684176896 +1661868230723177728 +1661868230765178624 +1661868230807179520 +1661868230849180416 +1661868230891181312 +1661868230936182272 +1661868230978183168 +1661868231020184064 +1661868231059184896 +1661868231104185856 +1661868231146186752 +1661868231191187712 +1661868231233188608 +1661868231275189504 +1661868231317190400 +1661868231356191232 +1661868231401192192 +1661868231443193088 +1661868231482193920 +1661868231524194816 +1661868231569195776 +1661868231611196672 +1661868231653197568 +1661868231692198400 +1661868231731199232 +1661868231770200064 +1661868231812200960 +1661868231857201920 +1661868231902202880 +1661868231944203776 +1661868231986204672 +1661868232031205632 +1661868232070206464 +1661868232112207360 +1661868232157208320 +1661868232199209216 +1661868232241210112 +1661868232283211008 +1661868232328211968 +1661868232370212864 +1661868232412213760 +1661868232454214656 +1661868232496215552 +1661868232532216320 +1661868232574217216 +1661868232616218112 +1661868232652218880 +1661868232691219712 +1661868232733220608 +1661868232775221504 +1661868232817222400 +1661868232859223296 +1661868232901224192 +1661868232946225152 +1661868232991226112 +1661868233030226944 +1661868233075227904 +1661868233117228800 +1661868233159229696 +1661868233204230656 +1661868233240231424 +1661868233282232320 +1661868233324233216 +1661868233363234048 +1661868233405234944 +1661868233441235712 +1661868233483236608 +1661868233528237568 +1661868233576238592 +1661868233624239616 +1661868233669240576 +1661868233711241472 +1661868233756242432 +1661868233798243328 +1661868233840244224 +1661868233882245120 +1661868233924246016 +1661868233963246848 +1661868234005247744 +1661868234053248768 +1661868234095249664 +1661868234134250496 +1661868234179251456 +1661868234221252352 +1661868234263253248 +1661868234305254144 +1661868234347255040 +1661868234389255936 +1661868234431256832 +1661868234473257728 +1661868234518258688 +1661868234560259584 +1661868234602260480 +1661868234644261376 +1661868234686262272 +1661868234728263168 +1661868234770264064 +1661868234812264960 +1661868234848265728 +1661868234890266624 +1661868234929267456 +1661868234974268416 +1661868235013269248 +1661868235055270144 +1661868235103271168 +1661868235148272128 +1661868235187272960 +1661868235232273920 +1661868235274274816 +1661868235319275776 +1661868235361276672 +1661868235403277568 +1661868235448278528 +1661868235499279616 +1661868235544280576 +1661868235589281536 +1661868235631282432 +1661868235670283264 +1661868235715284224 +1661868235760285184 +1661868235802286080 +1661868235850287104 +1661868235892288000 +1661868235937288960 +1661868235979289856 +1661868236021290752 +1661868236069291776 +1661868236111292672 +1661868236153293568 +1661868236195294464 +1661868236240295424 +1661868236282296320 +1661868236333297408 +1661868236375298304 +1661868236417299200 +1661868236462300160 +1661868236507301120 +1661868236543301888 +1661868236585302784 +1661868236627303680 +1661868236666304512 +1661868236708305408 +1661868236756306432 +1661868236795307264 +1661868236834308096 +1661868236870308864 +1661868236915309824 +1661868236957310720 +1661868237005311744 +1661868237047312640 +1661868237089313536 +1661868237134314496 +1661868237176315392 +1661868237218316288 +1661868237263317248 +1661868237302318080 +1661868237344318976 +1661868237383319808 +1661868237425320704 +1661868237467321600 +1661868237506322432 +1661868237557323520 +1661868237599324416 +1661868237641325312 +1661868237683326208 +1661868237725327104 +1661868237770328064 +1661868237809328896 +1661868237851329792 +1661868237899330816 +1661868237941331712 +1661868237989332736 +1661868238028333568 +1661868238073334528 +1661868238118335488 +1661868238160336384 +1661868238202337280 +1661868238241338112 +1661868238292339200 +1661868238337340160 +1661868238379341056 +1661868238421341952 +1661868238463342848 +1661868238505343744 +1661868238547344640 +1661868238583345408 +1661868238628346368 +1661868238667347200 +1661868238709348096 +1661868238757349120 +1661868238799350016 +1661868238844350976 +1661868238889351936 +1661868238928352768 +1661868238967353600 +1661868239003354368 +1661868239045355264 +1661868239090356224 +1661868239138357248 +1661868239183358208 +1661868239234359296 +1661868239279360256 +1661868239321361152 +1661868239369362176 +1661868239411363072 +1661868239456364032 +1661868239504365056 +1661868239546365952 +1661868239591366912 +1661868239633367808 +1661868239678368768 +1661868239717369600 +1661868239759370496 +1661868239810371584 +1661868239852372480 +1661868239894373376 +1661868239936374272 +1661868239975375104 +1661868240023376128 +1661868240065377024 +1661868240107377920 +1661868240149378816 +1661868240191379712 +1661868240236380672 +1661868240281381632 +1661868240320382464 +1661868240359383296 +1661868240398384128 +1661868240437384960 +1661868240479385856 +1661868240521386752 +1661868240560387584 +1661868240599388416 +1661868240641389312 +1661868240683390208 +1661868240728391168 +1661868240770392064 +1661868240815393024 +1661868240857393920 +1661868240902394880 +1661868240947395840 +1661868240986396672 +1661868241028397568 +1661868241070398464 +1661868241121399552 +1661868241166400512 +1661868241208401408 +1661868241247402240 +1661868241289403136 +1661868241331404032 +1661868241373404928 +1661868241418405888 +1661868241460406784 +1661868241505407744 +1661868241544408576 +1661868241583409408 +1661868241625410304 +1661868241667411200 +1661868241709412096 +1661868241754413056 +1661868241796413952 +1661868241838414848 +1661868241880415744 +1661868241925416704 +1661868241979417856 +1661868242021418752 +1661868242060419584 +1661868242099420416 +1661868242141421312 +1661868242183422208 +1661868242225423104 +1661868242267424000 +1661868242312424960 +1661868242354425856 +1661868242390426624 +1661868242432427520 +1661868242471428352 +1661868242507429120 +1661868242549430016 +1661868242591430912 +1661868242633431808 +1661868242675432704 +1661868242717433600 +1661868242759434496 +1661868242801435392 +1661868242843436288 +1661868242885437184 +1661868242927438080 +1661868242969438976 +1661868243011439872 +1661868243053440768 +1661868243095441664 +1661868243140442624 +1661868243182443520 +1661868243221444352 +1661868243272445440 +1661868243317446400 +1661868243359447296 +1661868243401448192 +1661868243440449024 +1661868243488450048 +1661868243533451008 +1661868243575451904 +1661868243617452800 +1661868243656453632 +1661868243698454528 +1661868243740455424 +1661868243782456320 +1661868243824457216 +1661868243866458112 +1661868243914459136 +1661868243956460032 +1661868243998460928 +1661868244043461888 +1661868244085462784 +1661868244127463680 +1661868244172464640 +1661868244220465664 +1661868244265466624 +1661868244304467456 +1661868244349468416 +1661868244394469376 +1661868244439470336 +1661868244481471232 +1661868244520472064 +1661868244559472896 +1661868244601473792 +1661868244649474816 +1661868244691475712 +1661868244736476672 +1661868244778477568 +1661868244823478528 +1661868244865479424 +1661868244913480448 +1661868244961481472 +1661868245012482560 +1661868245054483456 +1661868245096484352 +1661868245138485248 +1661868245180486144 +1661868245222487040 +1661868245267488000 +1661868245309488896 +1661868245351489792 +1661868245396490752 +1661868245438491648 +1661868245483492608 +1661868245525493504 +1661868245570494464 +1661868245615495424 +1661868245657496320 +1661868245702497280 +1661868245741498112 +1661868245783499008 +1661868245822499840 +1661868245867500800 +1661868245909501696 +1661868245951502592 +1661868245993503488 +1661868246038504448 +1661868246080505344 +1661868246125506304 +1661868246182507520 +1661868246224508416 +1661868246263509248 +1661868246302510080 +1661868246344510976 +1661868246389511936 +1661868246434512896 +1661868246476513792 +1661868246521514752 +1661868246563515648 +1661868246602516480 +1661868246638517248 +1661868246686518272 +1661868246725519104 +1661868246767520000 +1661868246809520896 +1661868246851521792 +1661868246893522688 +1661868246944523776 +1661868246986524672 +1661868247028525568 +1661868247076526592 +1661868247118527488 +1661868247151528192 +1661868247190529024 +1661868247238530048 +1661868247280530944 +1661868247325531904 +1661868247370532864 +1661868247415533824 +1661868247457534720 +1661868247499535616 +1661868247541536512 +1661868247580537344 +1661868247622538240 +1661868247664539136 +1661868247709540096 +1661868247751540992 +1661868247790541824 +1661868247832542720 +1661868247874543616 +1661868247925544704 +1661868247967545600 +1661868248015546624 +1661868248057547520 +1661868248099548416 +1661868248141549312 +1661868248183550208 +1661868248222551040 +1661868248264551936 +1661868248312552960 +1661868248354553856 +1661868248399554816 +1661868248444555776 +1661868248486556672 +1661868248528557568 +1661868248567558400 +1661868248606559232 +1661868248645560064 +1661868248693561088 +1661868248735561984 +1661868248777562880 +1661868248819563776 +1661868248861564672 +1661868248906565632 +1661868248945566464 +1661868248987567360 +1661868249029568256 +1661868249077569280 +1661868249119570176 +1661868249164571136 +1661868249206572032 +1661868249248572928 +1661868249299574016 +1661868249341574912 +1661868249386575872 +1661868249425576704 +1661868249470577664 +1661868249509578496 +1661868249554579456 +1661868249599580416 +1661868249641581312 +1661868249686582272 +1661868249728583168 +1661868249767584000 +1661868249806584832 +1661868249851585792 +1661868249896586752 +1661868249932587520 +1661868249974588416 +1661868250016589312 +1661868250055590144 +1661868250097591040 +1661868250139591936 +1661868250181592832 +1661868250223593728 +1661868250265594624 +1661868250304595456 +1661868250343596288 +1661868250385597184 +1661868250430598144 +1661868250472599040 +1661868250523600128 +1661868250574601216 +1661868250619602176 +1661868250658603008 +1661868250703603968 +1661868250754605056 +1661868250796605952 +1661868250838606848 +1661868250880607744 +1661868250922608640 +1661868250964609536 +1661868251006610432 +1661868251048611328 +1661868251090612224 +1661868251129613056 +1661868251177614080 +1661868251219614976 +1661868251261615872 +1661868251303616768 +1661868251342617600 +1661868251384618496 +1661868251426619392 +1661868251471620352 +1661868251513621248 +1661868251555622144 +1661868251597623040 +1661868251642624000 +1661868251693625088 +1661868251732625920 +1661868251771626752 +1661868251810627584 +1661868251855628544 +1661868251897629440 +1661868251939630336 +1661868251984631296 +1661868252035632384 +1661868252074633216 +1661868252122634240 +1661868252164635136 +1661868252206636032 +1661868252245636864 +1661868252287637760 +1661868252338638848 +1661868252380639744 +1661868252422640640 +1661868252464641536 +1661868252506642432 +1661868252545643264 +1661868252590644224 +1661868252632645120 +1661868252677646080 +1661868252722647040 +1661868252764647936 +1661868252806648832 +1661868252842649600 +1661868252884650496 +1661868252938651648 +1661868252980652544 +1661868253022653440 +1661868253064654336 +1661868253100655104 +1661868253145656064 +1661868253184656896 +1661868253226657792 +1661868253268658688 +1661868253307659520 +1661868253349660416 +1661868253391661312 +1661868253433662208 +1661868253478663168 +1661868253520664064 +1661868253562664960 +1661868253610665984 +1661868253652666880 +1661868253694667776 +1661868253736668672 +1661868253778669568 +1661868253817670400 +1661868253859671296 +1661868253901672192 +1661868253943673088 +1661868253985673984 +1661868254027674880 +1661868254069675776 +1661868254111676672 +1661868254153677568 +1661868254195678464 +1661868254234679296 +1661868254279680256 +1661868254318681088 +1661868254360681984 +1661868254402682880 +1661868254444683776 +1661868254489684736 +1661868254534685696 +1661868254582686720 +1661868254624687616 +1661868254666688512 +1661868254708689408 +1661868254750690304 +1661868254798691328 +1661868254843692288 +1661868254885693184 +1661868254924694016 +1661868254969694976 +1661868255011695872 +1661868255053696768 +1661868255095697664 +1661868255137698560 +1661868255179699456 +1661868255224700416 +1661868255266701312 +1661868255317702400 +1661868255359703296 +1661868255398704128 +1661868255437704960 +1661868255479705856 +1661868255518706688 +1661868255557707520 +1661868255599708416 +1661868255641709312 +1661868255680710144 +1661868255722711040 +1661868255761711872 +1661868255803712768 +1661868255845713664 +1661868255887714560 +1661868255932715520 +1661868255977716480 +1661868256019717376 +1661868256061718272 +1661868256103719168 +1661868256145720064 +1661868256196721152 +1661868256238722048 +1661868256280722944 +1661868256319723776 +1661868256361724672 +1661868256403725568 +1661868256442726400 +1661868256490727424 +1661868256529728256 +1661868256568729088 +1661868256607729920 +1661868256649730816 +1661868256691731712 +1661868256727732480 +1661868256766733312 +1661868256808734208 +1661868256847735040 +1661868256892736000 +1661868256934736896 +1661868256979737856 +1661868257021738752 +1661868257063739648 +1661868257105740544 +1661868257150741504 +1661868257192742400 +1661868257234743296 +1661868257276744192 +1661868257318745088 +1661868257360745984 +1661868257408747008 +1661868257450747904 +1661868257492748800 +1661868257534749696 +1661868257582750720 +1661868257621751552 +1661868257663752448 +1661868257702753280 +1661868257741754112 +1661868257783755008 +1661868257828755968 +1661868257873756928 +1661868257915757824 +1661868257960758784 +1661868257999759616 +1661868258044760576 +1661868258092761600 +1661868258134762496 +1661868258170763264 +1661868258209764096 +1661868258251764992 +1661868258293765888 +1661868258332766720 +1661868258374767616 +1661868258416768512 +1661868258458769408 +1661868258503770368 +1661868258545771264 +1661868258587772160 +1661868258629773056 +1661868258674774016 +1661868258713774848 +1661868258749775616 +1661868258788776448 +1661868258830777344 +1661868258872778240 +1661868258914779136 +1661868258950779904 +1661868258992780800 +1661868259034781696 +1661868259073782528 +1661868259118783488 +1661868259160784384 +1661868259202785280 +1661868259244786176 +1661868259286787072 +1661868259328787968 +1661868259373788928 +1661868259415789824 +1661868259460790784 +1661868259502791680 +1661868259544792576 +1661868259592793600 +1661868259631794432 +1661868259673795328 +1661868259715796224 +1661868259757797120 +1661868259799798016 +1661868259838798848 +1661868259883799808 +1661868259928800768 +1661868259973801728 +1661868260015802624 +1661868260054803456 +1661868260096804352 +1661868260138805248 +1661868260180806144 +1661868260219806976 +1661868260261807872 +1661868260303808768 +1661868260348809728 +1661868260390810624 +1661868260432811520 +1661868260477812480 +1661868260519813376 +1661868260564814336 +1661868260606815232 +1661868260648816128 +1661868260690817024 +1661868260732817920 +1661868260774818816 +1661868260816819712 +1661868260861820672 +1661868260903821568 +1661868260939822336 +1661868260981823232 +1661868261020824064 +1661868261059824896 +1661868261104825856 +1661868261149826816 +1661868261188827648 +1661868261224828416 +1661868261272829440 +1661868261314830336 +1661868261359831296 +1661868261398832128 +1661868261443833088 +1661868261488834048 +1661868261530834944 +1661868261572835840 +1661868261620836864 +1661868261662837760 +1661868261707838720 +1661868261752839680 +1661868261791840512 +1661868261833841408 +1661868261875842304 +1661868261923843328 +1661868261965844224 +1661868262010845184 +1661868262052846080 +1661868262100847104 +1661868262139847936 +1661868262178848768 +1661868262217849600 +1661868262259850496 +1661868262301851392 +1661868262343852288 +1661868262388853248 +1661868262430854144 +1661868262472855040 +1661868262511855872 +1661868262559856896 +1661868262601857792 +1661868262646858752 +1661868262691859712 +1661868262733860608 +1661868262775861504 +1661868262820862464 +1661868262868863488 +1661868262907864320 +1661868262949865216 +1661868262991866112 +1661868263033867008 +1661868263075867904 +1661868263117868800 +1661868263159869696 +1661868263198870528 +1661868263240871424 +1661868263279872256 +1661868263321873152 +1661868263363874048 +1661868263408875008 +1661868263444875776 +1661868263486876672 +1661868263528877568 +1661868263567878400 +1661868263609879296 +1661868263651880192 +1661868263696881152 +1661868263738882048 +1661868263780882944 +1661868263822883840 +1661868263867884800 +1661868263906885632 +1661868263954886656 +1661868263996887552 +1661868264035888384 +1661868264074889216 +1661868264119890176 +1661868264161891072 +1661868264203891968 +1661868264242892800 +1661868264287893760 +1661868264329894656 +1661868264371895552 +1661868264413896448 +1661868264461897472 +1661868264500898304 +1661868264539899136 +1661868264584900096 +1661868264626900992 +1661868264665901824 +1661868264707902720 +1661868264752903680 +1661868264800904704 +1661868264851905792 +1661868264893906688 +1661868264935907584 +1661868264977908480 +1661868265016909312 +1661868265058910208 +1661868265100911104 +1661868265142912000 +1661868265187912960 +1661868265229913856 +1661868265274914816 +1661868265322915840 +1661868265361916672 +1661868265403917568 +1661868265445918464 +1661868265484919296 +1661868265526920192 +1661868265565921024 +1661868265619922176 +1661868265664923136 +1661868265706924032 +1661868265748924928 +1661868265790925824 +1661868265829926656 +1661868265874927616 +1661868265916928512 +1661868265955929344 +1661868265997930240 +1661868266036931072 +1661868266081932032 +1661868266123932928 +1661868266162933760 +1661868266204934656 +1661868266246935552 +1661868266288936448 +1661868266330937344 +1661868266369938176 +1661868266408939008 +1661868266450939904 +1661868266492940800 +1661868266540941824 +1661868266588942848 +1661868266633943808 +1661868266675944704 +1661868266729945856 +1661868266768946688 +1661868266813947648 +1661868266852948480 +1661868266894949376 +1661868266939950336 +1661868266978951168 +1661868267020952064 +1661868267065953024 +1661868267110953984 +1661868267149954816 +1661868267194955776 +1661868267236956672 +1661868267278957568 +1661868267317958400 +1661868267359959296 +1661868267398960128 +1661868267440961024 +1661868267485961984 +1661868267527962880 +1661868267569963776 +1661868267611964672 +1661868267650965504 +1661868267686966272 +1661868267728967168 +1661868267770968064 +1661868267818969088 +1661868267860969984 +1661868267902970880 +1661868267950971904 +1661868268001972992 +1661868268043973888 +1661868268091974912 +1661868268133975808 +1661868268175976704 +1661868268217977600 +1661868268259978496 +1661868268301979392 +1661868268340980224 +1661868268382981120 +1661868268427982080 +1661868268472983040 +1661868268511983872 +1661868268553984768 +1661868268598985728 +1661868268640986624 +1661868268685987584 +1661868268727988480 +1661868268766989312 +1661868268811990272 +1661868268853991168 +1661868268892992000 +1661868268937992960 +1661868268979993856 +1661868269021994752 +1661868269063995648 +1661868269105996544 +1661868269147997440 +1661868269192998400 +1661868269234999296 +1661868269277000192 +1661868269316001024 +1661868269361001984 +1661868269400002816 +1661868269442003712 +1661868269484004608 +1661868269529005568 +1661868269568006400 +1661868269607007232 +1661868269649008128 +1661868269694009088 +1661868269736009984 +1661868269784011008 +1661868269829011968 +1661868269877012992 +1661868269919013888 +1661868269961014784 +1661868270009015808 +1661868270051016704 +1661868270096017664 +1661868270147018752 +1661868270186019584 +1661868270225020416 +1661868270264021248 +1661868270300022016 +1661868270339022848 +1661868270384023808 +1661868270423024640 +1661868270474025728 +1661868270516026624 +1661868270558027520 +1661868270600028416 +1661868270639029248 +1661868270681030144 +1661868270723031040 +1661868270762031872 +1661868270807032832 +1661868270849033728 +1661868270897034752 +1661868270939035648 +1661868270978036480 +1661868271026037504 +1661868271071038464 +1661868271113039360 +1661868271152040192 +1661868271194041088 +1661868271248042240 +1661868271290043136 +1661868271335044096 +1661868271380045056 +1661868271422045952 +1661868271467046912 +1661868271506047744 +1661868271545048576 +1661868271587049472 +1661868271629050368 +1661868271668051200 +1661868271713052160 +1661868271758053120 +1661868271803054080 +1661868271845054976 +1661868271887055872 +1661868271929056768 +1661868271971057664 +1661868272010058496 +1661868272052059392 +1661868272094060288 +1661868272136061184 +1661868272181062144 +1661868272223063040 +1661868272265063936 +1661868272307064832 +1661868272352065792 +1661868272391066624 +1661868272427067392 +1661868272469068288 +1661868272508069120 +1661868272550070016 +1661868272592070912 +1661868272631071744 +1661868272673072640 +1661868272715073536 +1661868272757074432 +1661868272796075264 +1661868272838076160 +1661868272880077056 +1661868272922077952 +1661868272964078848 +1661868273006079744 +1661868273045080576 +1661868273087081472 +1661868273129082368 +1661868273171083264 +1661868273213084160 +1661868273255085056 +1661868273297085952 +1661868273342086912 +1661868273387087872 +1661868273429088768 +1661868273471089664 +1661868273516090624 +1661868273558091520 +1661868273606092544 +1661868273651093504 +1661868273693094400 +1661868273735095296 +1661868273777096192 +1661868273822097152 +1661868273864098048 +1661868273909099008 +1661868273957100032 +1661868273999100928 +1661868274041101824 +1661868274092102912 +1661868274131103744 +1661868274173104640 +1661868274215105536 +1661868274260106496 +1661868274299107328 +1661868274341108224 +1661868274386109184 +1661868274428110080 +1661868274476111104 +1661868274521112064 +1661868274566113024 +1661868274605113856 +1661868274656114944 +1661868274701115904 +1661868274743116800 +1661868274785117696 +1661868274827118592 +1661868274869119488 +1661868274911120384 +1661868274953121280 +1661868274989122048 +1661868275031122944 +1661868275070123776 +1661868275109124608 +1661868275151125504 +1661868275193126400 +1661868275238127360 +1661868275280128256 +1661868275322129152 +1661868275364130048 +1661868275403130880 +1661868275451131904 +1661868275493132800 +1661868275538133760 +1661868275580134656 +1661868275622135552 +1661868275670136576 +1661868275706137344 +1661868275745138176 +1661868275784139008 +1661868275829139968 +1661868275874140928 +1661868275916141824 +1661868275958142720 +1661868275997143552 +1661868276039144448 +1661868276081145344 +1661868276123146240 +1661868276168147200 +1661868276210148096 +1661868276249148928 +1661868276291149824 +1661868276333150720 +1661868276378151680 +1661868276417152512 +1661868276459153408 +1661868276501154304 +1661868276546155264 +1661868276588156160 +1661868276630157056 +1661868276675158016 +1661868276717158912 +1661868276759159808 +1661868276804160768 +1661868276846161664 +1661868276885162496 +1661868276924163328 +1661868276963164160 +1661868277002164992 +1661868277044165888 +1661868277086166784 +1661868277128167680 +1661868277170168576 +1661868277215169536 +1661868277260170496 +1661868277308171520 +1661868277347172352 +1661868277389173248 +1661868277431174144 +1661868277470174976 +1661868277512175872 +1661868277554176768 +1661868277596177664 +1661868277641178624 +1661868277686179584 +1661868277728180480 +1661868277770181376 +1661868277812182272 +1661868277851183104 +1661868277893184000 +1661868277932184832 +1661868277971185664 +1661868278013186560 +1661868278055187456 +1661868278100188416 +1661868278145189376 +1661868278187190272 +1661868278229191168 +1661868278271192064 +1661868278310192896 +1661868278349193728 +1661868278391194624 +1661868278427195392 +1661868278469196288 +1661868278511197184 +1661868278550198016 +1661868278598199040 +1661868278637199872 +1661868278676200704 +1661868278721201664 +1661868278763202560 +1661868278805203456 +1661868278847204352 +1661868278886205184 +1661868278925206016 +1661868278967206912 +1661868279009207808 +1661868279048208640 +1661868279090209536 +1661868279132210432 +1661868279177211392 +1661868279216212224 +1661868279264213248 +1661868279309214208 +1661868279351215104 +1661868279393216000 +1661868279435216896 +1661868279477217792 +1661868279522218752 +1661868279570219776 +1661868279612220672 +1661868279651221504 +1661868279687222272 +1661868279732223232 +1661868279774224128 +1661868279816225024 +1661868279858225920 +1661868279900226816 +1661868279945227776 +1661868279990228736 +1661868280035229696 +1661868280077230592 +1661868280125231616 +1661868280167232512 +1661868280209233408 +1661868280251234304 +1661868280293235200 +1661868280338236160 +1661868280380237056 +1661868280422237952 +1661868280464238848 +1661868280503239680 +1661868280548240640 +1661868280590241536 +1661868280635242496 +1661868280680243456 +1661868280722244352 +1661868280764245248 +1661868280800246016 +1661868280851247104 +1661868280905248256 +1661868280956249344 +1661868280998250240 +1661868281040251136 +1661868281082252032 +1661868281124252928 +1661868281166253824 +1661868281208254720 +1661868281253255680 +1661868281292256512 +1661868281337257472 +1661868281379258368 +1661868281424259328 +1661868281466260224 +1661868281511261184 +1661868281550262016 +1661868281592262912 +1661868281631263744 +1661868281676264704 +1661868281718265600 +1661868281763266560 +1661868281808267520 +1661868281850268416 +1661868281892269312 +1661868281937270272 +1661868281985271296 +1661868282024272128 +1661868282066273024 +1661868282111273984 +1661868282159275008 +1661868282204275968 +1661868282249276928 +1661868282288277760 +1661868282330278656 +1661868282378279680 +1661868282417280512 +1661868282459281408 +1661868282513282560 +1661868282555283456 +1661868282597284352 +1661868282639285248 +1661868282681286144 +1661868282726287104 +1661868282768288000 +1661868282813288960 +1661868282852289792 +1661868282894290688 +1661868282939291648 +1661868282984292608 +1661868283023293440 +1661868283068294400 +1661868283116295424 +1661868283158296320 +1661868283203297280 +1661868283245298176 +1661868283284299008 +1661868283329299968 +1661868283371300864 +1661868283419301888 +1661868283461302784 +1661868283500303616 +1661868283548304640 +1661868283590305536 +1661868283638306560 +1661868283677307392 +1661868283725308416 +1661868283770309376 +1661868283812310272 +1661868283857311232 +1661868283899312128 +1661868283941313024 +1661868283989314048 +1661868284028314880 +1661868284067315712 +1661868284109316608 +1661868284157317632 +1661868284199318528 +1661868284247319552 +1661868284286320384 +1661868284328321280 +1661868284379322368 +1661868284421323264 +1661868284457324032 +1661868284496324864 +1661868284538325760 +1661868284580326656 +1661868284622327552 +1661868284667328512 +1661868284709329408 +1661868284763330560 +1661868284805331456 +1661868284850332416 +1661868284895333376 +1661868284937334272 +1661868284976335104 +1661868285021336064 +1661868285066337024 +1661868285105337856 +1661868285156338944 +1661868285201339904 +1661868285243340800 +1661868285294341888 +1661868285336342784 +1661868285378343680 +1661868285420344576 +1661868285459345408 +1661868285501346304 +1661868285543347200 +1661868285585348096 +1661868285624348928 +1661868285666349824 +1661868285711350784 +1661868285753351680 +1661868285795352576 +1661868285834353408 +1661868285885354496 +1661868285927355392 +1661868285969356288 +1661868286011357184 +1661868286050358016 +1661868286089358848 +1661868286131359744 +1661868286176360704 +1661868286221361664 +1661868286263362560 +1661868286314363648 +1661868286353364480 +1661868286398365440 +1661868286440366336 +1661868286482367232 +1661868286524368128 +1661868286560368896 +1661868286602369792 +1661868286644370688 +1661868286686371584 +1661868286728372480 +1661868286770373376 +1661868286821374464 +1661868286863375360 +1661868286908376320 +1661868286950377216 +1661868286992378112 +1661868287037379072 +1661868287079379968 +1661868287127380992 +1661868287169381888 +1661868287208382720 +1661868287253383680 +1661868287298384640 +1661868287340385536 +1661868287382386432 +1661868287424387328 +1661868287466388224 +1661868287508389120 +1661868287550390016 +1661868287592390912 +1661868287634391808 +1661868287676392704 +1661868287718393600 +1661868287760394496 +1661868287805395456 +1661868287847396352 +1661868287895397376 +1661868287937398272 +1661868287976399104 +1661868288015399936 +1661868288063400960 +1661868288105401856 +1661868288147402752 +1661868288189403648 +1661868288231404544 +1661868288273405440 +1661868288315406336 +1661868288354407168 +1661868288396408064 +1661868288438408960 +1661868288483409920 +1661868288525410816 +1661868288570411776 +1661868288606412544 +1661868288648413440 +1661868288690414336 +1661868288732415232 +1661868288774416128 +1661868288816417024 +1661868288858417920 +1661868288900418816 +1661868288951419904 +1661868288993420800 +1661868289041421824 +1661868289083422720 +1661868289128423680 +1661868289170424576 +1661868289212425472 +1661868289257426432 +1661868289296427264 +1661868289338428160 +1661868289380429056 +1661868289428430080 +1661868289476431104 +1661868289518432000 +1661868289560432896 +1661868289602433792 +1661868289641434624 +1661868289683435520 +1661868289725436416 +1661868289767437312 +1661868289809438208 +1661868289851439104 +1661868289890439936 +1661868289935440896 +1661868289983441920 +1661868290025442816 +1661868290067443712 +1661868290115444736 +1661868290154445568 +1661868290199446528 +1661868290244447488 +1661868290289448448 +1661868290328449280 +1661868290364450048 +1661868290412451072 +1661868290454451968 +1661868290496452864 +1661868290535453696 +1661868290580454656 +1661868290622455552 +1661868290664456448 +1661868290706457344 +1661868290754458368 +1661868290802459392 +1661868290841460224 +1661868290883461120 +1661868290925462016 +1661868290967462912 +1661868291015463936 +1661868291060464896 +1661868291102465792 +1661868291144466688 +1661868291186467584 +1661868291231468544 +1661868291270469376 +1661868291312470272 +1661868291354471168 +1661868291396472064 +1661868291438472960 +1661868291483473920 +1661868291525474816 +1661868291567475712 +1661868291609476608 +1661868291648477440 +1661868291690478336 +1661868291732479232 +1661868291771480064 +1661868291813480960 +1661868291855481856 +1661868291900482816 +1661868291942483712 +1661868291984484608 +1661868292026485504 +1661868292071486464 +1661868292113487360 +1661868292152488192 +1661868292194489088 +1661868292233489920 +1661868292281490944 +1661868292320491776 +1661868292359492608 +1661868292401493504 +1661868292443494400 +1661868292485495296 +1661868292530496256 +1661868292572497152 +1661868292614498048 +1661868292656498944 +1661868292698499840 +1661868292743500800 +1661868292785501696 +1661868292821502464 +1661868292869503488 +1661868292911504384 +1661868292959505408 +1661868293001506304 +1661868293043507200 +1661868293085508096 +1661868293130509056 +1661868293175510016 +1661868293217510912 +1661868293265511936 +1661868293313512960 +1661868293352513792 +1661868293391514624 +1661868293430515456 +1661868293472516352 +1661868293520517376 +1661868293562518272 +1661868293601519104 +1661868293643520000 +1661868293685520896 +1661868293730521856 +1661868293772522752 +1661868293811523584 +1661868293853524480 +1661868293898525440 +1661868293940526336 +1661868293985527296 +1661868294027528192 +1661868294069529088 +1661868294111529984 +1661868294162531072 +1661868294204531968 +1661868294246532864 +1661868294285533696 +1661868294324534528 +1661868294366535424 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track1.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track1.txt new file mode 100644 index 0000000000..f8502440d4 --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track1.txt @@ -0,0 +1,2030 @@ +1662015311059723520 +1662015311101724416 +1662015311146725376 +1662015311203726592 +1662015311248727552 +1662015311293728512 +1662015311335729408 +1662015311377730304 +1662015311422731264 +1662015311464732160 +1662015311506733056 +1662015311548733952 +1662015311590734848 +1662015311635735808 +1662015311677736704 +1662015311719737600 +1662015311761738496 +1662015311809739520 +1662015311857740544 +1662015311902741504 +1662015311944742400 +1662015311986743296 +1662015312031744256 +1662015312076745216 +1662015312130746368 +1662015312169747200 +1662015312208748032 +1662015312253748992 +1662015312295749888 +1662015312340750848 +1662015312379751680 +1662015312424752640 +1662015312463753472 +1662015312508754432 +1662015312550755328 +1662015312592756224 +1662015312631757056 +1662015312679758080 +1662015312724759040 +1662015312766759936 +1662015312811760896 +1662015312856761856 +1662015312901762816 +1662015312943763712 +1662015312985764608 +1662015313027765504 +1662015313075766528 +1662015313117767424 +1662015313159768320 +1662015313201769216 +1662015313240770048 +1662015313282770944 +1662015313327771904 +1662015313369772800 +1662015313411773696 +1662015313456774656 +1662015313498775552 +1662015313540776448 +1662015313591777536 +1662015313630778368 +1662015313672779264 +1662015313717780224 +1662015313756781056 +1662015313801782016 +1662015313843782912 +1662015313885783808 +1662015313927784704 +1662015313972785664 +1662015314014786560 +1662015314056787456 +1662015314101788416 +1662015314143789312 +1662015314185790208 +1662015314227791104 +1662015314272792064 +1662015314317793024 +1662015314362793984 +1662015314413795072 +1662015314455795968 +1662015314497796864 +1662015314539797760 +1662015314581798656 +1662015314626799616 +1662015314668800512 +1662015314716801536 +1662015314761802496 +1662015314803803392 +1662015314848804352 +1662015314896805376 +1662015314938806272 +1662015314980807168 +1662015315028808192 +1662015315073809152 +1662015315115810048 +1662015315154810880 +1662015315199811840 +1662015315238812672 +1662015315280813568 +1662015315328814592 +1662015315379815680 +1662015315427816704 +1662015315475817728 +1662015315532818944 +1662015315577819904 +1662015315619820800 +1662015315670821888 +1662015315721822976 +1662015315766823936 +1662015315814824960 +1662015315859825920 +1662015315904826880 +1662015315949827840 +1662015315991828736 +1662015316033829632 +1662015316078830592 +1662015316126831616 +1662015316174832640 +1662015316219833600 +1662015316270834688 +1662015316315835648 +1662015316366836736 +1662015316414837760 +1662015316462838784 +1662015316507839744 +1662015316552840704 +1662015316597841664 +1662015316648842752 +1662015316690843648 +1662015316729844480 +1662015316774845440 +1662015316822846464 +1662015316867847424 +1662015316909848320 +1662015316951849216 +1662015316993850112 +1662015317038851072 +1662015317083852032 +1662015317128852992 +1662015317170853888 +1662015317218854912 +1662015317260855808 +1662015317302856704 +1662015317344857600 +1662015317389858560 +1662015317434859520 +1662015317473860352 +1662015317515861248 +1662015317560862208 +1662015317605863168 +1662015317647864064 +1662015317692865024 +1662015317740866048 +1662015317782866944 +1662015317830867968 +1662015317872868864 +1662015317914869760 +1662015317962870784 +1662015318010871808 +1662015318058872832 +1662015318109873920 +1662015318148874752 +1662015318193875712 +1662015318235876608 +1662015318280877568 +1662015318325878528 +1662015318367879424 +1662015318412880384 +1662015318454881280 +1662015318499882240 +1662015318547883264 +1662015318589884160 +1662015318631885056 +1662015318682886144 +1662015318727887104 +1662015318769888000 +1662015318814888960 +1662015318859889920 +1662015318907890944 +1662015318952891904 +1662015318994892800 +1662015319036893696 +1662015319078894592 +1662015319120895488 +1662015319162896384 +1662015319207897344 +1662015319249898240 +1662015319291899136 +1662015319339900160 +1662015319387901184 +1662015319432902144 +1662015319474903040 +1662015319516903936 +1662015319561904896 +1662015319609905920 +1662015319654906880 +1662015319699907840 +1662015319741908736 +1662015319792909824 +1662015319840910848 +1662015319891911936 +1662015319939912960 +1662015319981913856 +1662015320023914752 +1662015320077915904 +1662015320125916928 +1662015320167917824 +1662015320209918720 +1662015320251919616 +1662015320296920576 +1662015320338921472 +1662015320389922560 +1662015320437923584 +1662015320485924608 +1662015320530925568 +1662015320575926528 +1662015320617927424 +1662015320659928320 +1662015320704929280 +1662015320746930176 +1662015320791931136 +1662015320839932160 +1662015320881933056 +1662015320926934016 +1662015320968934912 +1662015321010935808 +1662015321058936832 +1662015321103937792 +1662015321145938688 +1662015321193939712 +1662015321241940736 +1662015321283941632 +1662015321328942592 +1662015321373943552 +1662015321415944448 +1662015321454945280 +1662015321499946240 +1662015321541947136 +1662015321592948224 +1662015321637949184 +1662015321685950208 +1662015321727951104 +1662015321775952128 +1662015321817953024 +1662015321859953920 +1662015321901954816 +1662015321943955712 +1662015321985956608 +1662015322033957632 +1662015322084958720 +1662015322126959616 +1662015322171960576 +1662015322222961664 +1662015322267962624 +1662015322309963520 +1662015322351964416 +1662015322396965376 +1662015322438966272 +1662015322483967232 +1662015322528968192 +1662015322567969024 +1662015322609969920 +1662015322651970816 +1662015322699971840 +1662015322741972736 +1662015322786973696 +1662015322828974592 +1662015322876975616 +1662015322918976512 +1662015322966977536 +1662015323008978432 +1662015323059979520 +1662015323101980416 +1662015323143981312 +1662015323188982272 +1662015323230983168 +1662015323272984064 +1662015323314984960 +1662015323359985920 +1662015323404986880 +1662015323455987968 +1662015323494988800 +1662015323542989824 +1662015323584990720 +1662015323629991680 +1662015323671992576 +1662015323713993472 +1662015323755994368 +1662015323803995392 +1662015323848996352 +1662015323896997376 +1662015323938998272 +1662015323980999168 +1662015324026000128 +1662015324071001088 +1662015324113001984 +1662015324164003072 +1662015324206003968 +1662015324251004928 +1662015324293005824 +1662015324338006784 +1662015324386007808 +1662015324431008768 +1662015324473009664 +1662015324515010560 +1662015324560011520 +1662015324605012480 +1662015324653013504 +1662015324695014400 +1662015324740015360 +1662015324785016320 +1662015324827017216 +1662015324875018240 +1662015324917019136 +1662015324965020160 +1662015325013021184 +1662015325055022080 +1662015325100023040 +1662015325145024000 +1662015325190024960 +1662015325232025856 +1662015325274026752 +1662015325322027776 +1662015325367028736 +1662015325412029696 +1662015325457030656 +1662015325505031680 +1662015325547032576 +1662015325592033536 +1662015325634034432 +1662015325676035328 +1662015325718036224 +1662015325760037120 +1662015325805038080 +1662015325847038976 +1662015325889039872 +1662015325934040832 +1662015325985041920 +1662015326036043008 +1662015326084044032 +1662015326126044928 +1662015326177046016 +1662015326225047040 +1662015326276048128 +1662015326321049088 +1662015326363049984 +1662015326408050944 +1662015326453051904 +1662015326495052800 +1662015326537053696 +1662015326582054656 +1662015326627055616 +1662015326681056768 +1662015326723057664 +1662015326771058688 +1662015326813059584 +1662015326855060480 +1662015326897061376 +1662015326942062336 +1662015326987063296 +1662015327029064192 +1662015327074065152 +1662015327116066048 +1662015327161067008 +1662015327203067904 +1662015327245068800 +1662015327290069760 +1662015327335070720 +1662015327380071680 +1662015327419072512 +1662015327464073472 +1662015327509074432 +1662015327554075392 +1662015327596076288 +1662015327644077312 +1662015327686078208 +1662015327731079168 +1662015327776080128 +1662015327818081024 +1662015327863081984 +1662015327905082880 +1662015327950083840 +1662015327992084736 +1662015328034085632 +1662015328076086528 +1662015328118087424 +1662015328163088384 +1662015328205089280 +1662015328247090176 +1662015328292091136 +1662015328334092032 +1662015328376092928 +1662015328418093824 +1662015328457094656 +1662015328499095552 +1662015328544096512 +1662015328589097472 +1662015328634098432 +1662015328682099456 +1662015328724100352 +1662015328775101440 +1662015328820102400 +1662015328868103424 +1662015328907104256 +1662015328955105280 +1662015329012106496 +1662015329066107648 +1662015329108108544 +1662015329153109504 +1662015329198110464 +1662015329243111424 +1662015329288112384 +1662015329336113408 +1662015329378114304 +1662015329423115264 +1662015329468116224 +1662015329513117184 +1662015329555118080 +1662015329597118976 +1662015329639119872 +1662015329681120768 +1662015329726121728 +1662015329771122688 +1662015329816123648 +1662015329861124608 +1662015329906125568 +1662015329948126464 +1662015329996127488 +1662015330044128512 +1662015330086129408 +1662015330134130432 +1662015330185131520 +1662015330227132416 +1662015330272133376 +1662015330320134400 +1662015330368135424 +1662015330413136384 +1662015330458137344 +1662015330506138368 +1662015330548139264 +1662015330596140288 +1662015330638141184 +1662015330683142144 +1662015330725143040 +1662015330770144000 +1662015330815144960 +1662015330857145856 +1662015330914147072 +1662015330959148032 +1662015331010149120 +1662015331049149952 +1662015331094150912 +1662015331136151808 +1662015331178152704 +1662015331223153664 +1662015331265154560 +1662015331310155520 +1662015331355156480 +1662015331397157376 +1662015331442158336 +1662015331487159296 +1662015331529160192 +1662015331571161088 +1662015331619162112 +1662015331667163136 +1662015331709164032 +1662015331751164928 +1662015331796165888 +1662015331847166976 +1662015331895168000 +1662015331940168960 +1662015331994170112 +1662015332039171072 +1662015332081171968 +1662015332123172864 +1662015332165173760 +1662015332213174784 +1662015332255175680 +1662015332300176640 +1662015332342177536 +1662015332384178432 +1662015332432179456 +1662015332477180416 +1662015332525181440 +1662015332567182336 +1662015332609183232 +1662015332654184192 +1662015332699185152 +1662015332747186176 +1662015332792187136 +1662015332837188096 +1662015332885189120 +1662015332930190080 +1662015332972190976 +1662015333017191936 +1662015333065192960 +1662015333107193856 +1662015333149194752 +1662015333191195648 +1662015333242196736 +1662015333293197824 +1662015333335198720 +1662015333380199680 +1662015333422200576 +1662015333470201600 +1662015333515202560 +1662015333557203456 +1662015333602204416 +1662015333647205376 +1662015333689206272 +1662015333734207232 +1662015333776208128 +1662015333821209088 +1662015333863209984 +1662015333905210880 +1662015333947211776 +1662015333992212736 +1662015334037213696 +1662015334082214656 +1662015334124215552 +1662015334169216512 +1662015334214217472 +1662015334259218432 +1662015334301219328 +1662015334343220224 +1662015334385221120 +1662015334427222016 +1662015334472222976 +1662015334520224000 +1662015334559224832 +1662015334604225792 +1662015334649226752 +1662015334694227712 +1662015334739228672 +1662015334781229568 +1662015334826230528 +1662015334874231552 +1662015334925232640 +1662015334967233536 +1662015335018234624 +1662015335063235584 +1662015335111236608 +1662015335153237504 +1662015335195238400 +1662015335240239360 +1662015335285240320 +1662015335330241280 +1662015335369242112 +1662015335423243264 +1662015335465244160 +1662015335507245056 +1662015335552246016 +1662015335597246976 +1662015335639247872 +1662015335690248960 +1662015335735249920 +1662015335774250752 +1662015335822251776 +1662015335864252672 +1662015335909253632 +1662015335957254656 +1662015336005255680 +1662015336047256576 +1662015336101257728 +1662015336149258752 +1662015336191259648 +1662015336233260544 +1662015336275261440 +1662015336317262336 +1662015336365263360 +1662015336407264256 +1662015336449265152 +1662015336497266176 +1662015336536267008 +1662015336581267968 +1662015336626268928 +1662015336671269888 +1662015336716270848 +1662015336767271936 +1662015336812272896 +1662015336857273856 +1662015336902274816 +1662015336950275840 +1662015336992276736 +1662015337034277632 +1662015337076278528 +1662015337118279424 +1662015337163280384 +1662015337208281344 +1662015337250282240 +1662015337295283200 +1662015337343284224 +1662015337385285120 +1662015337427286016 +1662015337469286912 +1662015337517287936 +1662015337568289024 +1662015337610289920 +1662015337652290816 +1662015337694291712 +1662015337733292544 +1662015337778293504 +1662015337826294528 +1662015337871295488 +1662015337913296384 +1662015337958297344 +1662015338000298240 +1662015338042299136 +1662015338087300096 +1662015338135301120 +1662015338177302016 +1662015338219302912 +1662015338258303744 +1662015338300304640 +1662015338345305600 +1662015338396306688 +1662015338438307584 +1662015338474308352 +1662015338519309312 +1662015338561310208 +1662015338606311168 +1662015338645312000 +1662015338687312896 +1662015338732313856 +1662015338774314752 +1662015338816315648 +1662015338858316544 +1662015338900317440 +1662015338942318336 +1662015338984319232 +1662015339026320128 +1662015339068321024 +1662015339113321984 +1662015339161323008 +1662015339206323968 +1662015339248324864 +1662015339296325888 +1662015339338326784 +1662015339380327680 +1662015339422328576 +1662015339467329536 +1662015339509330432 +1662015339551331328 +1662015339596332288 +1662015339641333248 +1662015339686334208 +1662015339728335104 +1662015339770336000 +1662015339809336832 +1662015339857337856 +1662015339902338816 +1662015339944339712 +1662015339986340608 +1662015340028341504 +1662015340079342592 +1662015340121343488 +1662015340163344384 +1662015340205345280 +1662015340259346432 +1662015340301347328 +1662015340346348288 +1662015340388349184 +1662015340433350144 +1662015340475351040 +1662015340520352000 +1662015340565352960 +1662015340613353984 +1662015340655354880 +1662015340697355776 +1662015340745356800 +1662015340793357824 +1662015340835358720 +1662015340874359552 +1662015340919360512 +1662015340964361472 +1662015341006362368 +1662015341051363328 +1662015341093364224 +1662015341141365248 +1662015341183366144 +1662015341225367040 +1662015341270368000 +1662015341312368896 +1662015341354369792 +1662015341399370752 +1662015341438371584 +1662015341480372480 +1662015341525373440 +1662015341570374400 +1662015341615375360 +1662015341663376384 +1662015341705377280 +1662015341750378240 +1662015341798379264 +1662015341840380160 +1662015341882381056 +1662015341930382080 +1662015341969382912 +1662015342011383808 +1662015342053384704 +1662015342095385600 +1662015342140386560 +1662015342185387520 +1662015342230388480 +1662015342278389504 +1662015342326390528 +1662015342371391488 +1662015342416392448 +1662015342458393344 +1662015342500394240 +1662015342539395072 +1662015342581395968 +1662015342632397056 +1662015342674397952 +1662015342716398848 +1662015342764399872 +1662015342803400704 +1662015342845401600 +1662015342884402432 +1662015342926403328 +1662015342968404224 +1662015343013405184 +1662015343055406080 +1662015343097406976 +1662015343148408064 +1662015343193409024 +1662015343238409984 +1662015343286411008 +1662015343331411968 +1662015343373412864 +1662015343418413824 +1662015343466414848 +1662015343511415808 +1662015343553416704 +1662015343595417600 +1662015343637418496 +1662015343685419520 +1662015343727420416 +1662015343772421376 +1662015343823422464 +1662015343865423360 +1662015343907424256 +1662015343952425216 +1662015343997426176 +1662015344039427072 +1662015344084428032 +1662015344129428992 +1662015344177430016 +1662015344219430912 +1662015344264431872 +1662015344315432960 +1662015344357433856 +1662015344405434880 +1662015344447435776 +1662015344495436800 +1662015344537437696 +1662015344585438720 +1662015344627439616 +1662015344672440576 +1662015344717441536 +1662015344759442432 +1662015344810443520 +1662015344855444480 +1662015344894445312 +1662015344939446272 +1662015344987447296 +1662015345029448192 +1662015345074449152 +1662015345119450112 +1662015345161451008 +1662015345206451968 +1662015345248452864 +1662015345296453888 +1662015345338454784 +1662015345380455680 +1662015345428456704 +1662015345476457728 +1662015345521458688 +1662015345560459520 +1662015345608460544 +1662015345656461568 +1662015345695462400 +1662015345737463296 +1662015345779464192 +1662015345824465152 +1662015345866466048 +1662015345914467072 +1662015345956467968 +1662015346001468928 +1662015346052470016 +1662015346094470912 +1662015346136471808 +1662015346184472832 +1662015346229473792 +1662015346277474816 +1662015346322475776 +1662015346364476672 +1662015346406477568 +1662015346448478464 +1662015346490479360 +1662015346535480320 +1662015346577481216 +1662015346622482176 +1662015346661483008 +1662015346706483968 +1662015346748484864 +1662015346790485760 +1662015346835486720 +1662015346883487744 +1662015346922488576 +1662015346964489472 +1662015347009490432 +1662015347051491328 +1662015347093492224 +1662015347138493184 +1662015347180494080 +1662015347222494976 +1662015347270496000 +1662015347315496960 +1662015347354497792 +1662015347396498688 +1662015347438499584 +1662015347483500544 +1662015347525501440 +1662015347567502336 +1662015347609503232 +1662015347663504384 +1662015347705505280 +1662015347750506240 +1662015347798507264 +1662015347840508160 +1662015347885509120 +1662015347933510144 +1662015347975511040 +1662015348017511936 +1662015348062512896 +1662015348107513856 +1662015348155514880 +1662015348197515776 +1662015348239516672 +1662015348284517632 +1662015348332518656 +1662015348377519616 +1662015348419520512 +1662015348464521472 +1662015348509522432 +1662015348557523456 +1662015348602524416 +1662015348644525312 +1662015348683526144 +1662015348725527040 +1662015348770528000 +1662015348812528896 +1662015348854529792 +1662015348899530752 +1662015348944531712 +1662015348992532736 +1662015349034533632 +1662015349076534528 +1662015349121535488 +1662015349163536384 +1662015349205537280 +1662015349247538176 +1662015349292539136 +1662015349343540224 +1662015349391541248 +1662015349433542144 +1662015349475543040 +1662015349517543936 +1662015349562544896 +1662015349604545792 +1662015349649546752 +1662015349694547712 +1662015349739548672 +1662015349781549568 +1662015349826550528 +1662015349865551360 +1662015349907552256 +1662015349949553152 +1662015349994554112 +1662015350045555200 +1662015350090556160 +1662015350135557120 +1662015350177558016 +1662015350219558912 +1662015350255559680 +1662015350297560576 +1662015350339561472 +1662015350387562496 +1662015350438563584 +1662015350480564480 +1662015350522565376 +1662015350564566272 +1662015350606567168 +1662015350651568128 +1662015350693569024 +1662015350738569984 +1662015350786571008 +1662015350831571968 +1662015350873572864 +1662015350918573824 +1662015350963574784 +1662015351005575680 +1662015351050576640 +1662015351095577600 +1662015351140578560 +1662015351182579456 +1662015351224580352 +1662015351269581312 +1662015351314582272 +1662015351359583232 +1662015351398584064 +1662015351443585024 +1662015351488585984 +1662015351530586880 +1662015351575587840 +1662015351626588928 +1662015351668589824 +1662015351716590848 +1662015351767591936 +1662015351809592832 +1662015351857593856 +1662015351905594880 +1662015351950595840 +1662015351992596736 +1662015352037597696 +1662015352082598656 +1662015352127599616 +1662015352166600448 +1662015352214601472 +1662015352256602368 +1662015352298603264 +1662015352340604160 +1662015352373604864 +1662015352412605696 +1662015352454606592 +1662015352499607552 +1662015352544608512 +1662015352592609536 +1662015352637610496 +1662015352679611392 +1662015352724612352 +1662015352769613312 +1662015352814614272 +1662015352859615232 +1662015352901616128 +1662015352949617152 +1662015352994618112 +1662015353036619008 +1662015353081619968 +1662015353126620928 +1662015353174621952 +1662015353219622912 +1662015353264623872 +1662015353309624832 +1662015353351625728 +1662015353396626688 +1662015353438627584 +1662015353483628544 +1662015353525629440 +1662015353564630272 +1662015353606631168 +1662015353648632064 +1662015353690632960 +1662015353738633984 +1662015353780634880 +1662015353822635776 +1662015353861636608 +1662015353909637632 +1662015353954638592 +1662015353993639424 +1662015354035640320 +1662015354083641344 +1662015354122642176 +1662015354164643072 +1662015354209644032 +1662015354251644928 +1662015354299645952 +1662015354341646848 +1662015354380647680 +1662015354425648640 +1662015354470649600 +1662015354512650496 +1662015354554651392 +1662015354599652352 +1662015354647653376 +1662015354689654272 +1662015354731655168 +1662015354779656192 +1662015354824657152 +1662015354863657984 +1662015354911659008 +1662015354953659904 +1662015354992660736 +1662015355037661696 +1662015355085662720 +1662015355130663680 +1662015355172664576 +1662015355217665536 +1662015355259666432 +1662015355301667328 +1662015355343668224 +1662015355388669184 +1662015355433670144 +1662015355475671040 +1662015355520672000 +1662015355565672960 +1662015355604673792 +1662015355649674752 +1662015355691675648 +1662015355739676672 +1662015355781677568 +1662015355823678464 +1662015355865679360 +1662015355907680256 +1662015355949681152 +1662015355997682176 +1662015356042683136 +1662015356087684096 +1662015356129684992 +1662015356174685952 +1662015356216686848 +1662015356261687808 +1662015356303688704 +1662015356351689728 +1662015356399690752 +1662015356441691648 +1662015356480692480 +1662015356522693376 +1662015356564694272 +1662015356612695296 +1662015356654696192 +1662015356699697152 +1662015356741698048 +1662015356783698944 +1662015356828699904 +1662015356864700672 +1662015356906701568 +1662015356951702528 +1662015356993703424 +1662015357035704320 +1662015357083705344 +1662015357128706304 +1662015357170707200 +1662015357212708096 +1662015357254708992 +1662015357293709824 +1662015357338710784 +1662015357383711744 +1662015357428712704 +1662015357482713856 +1662015357524714752 +1662015357566715648 +1662015357611716608 +1662015357659717632 +1662015357704718592 +1662015357746719488 +1662015357794720512 +1662015357836721408 +1662015357884722432 +1662015357929723392 +1662015357971724288 +1662015358013725184 +1662015358058726144 +1662015358103727104 +1662015358145728000 +1662015358187728896 +1662015358241730048 +1662015358280730880 +1662015358325731840 +1662015358367732736 +1662015358409733632 +1662015358451734528 +1662015358493735424 +1662015358544736512 +1662015358586737408 +1662015358631738368 +1662015358676739328 +1662015358718740224 +1662015358763741184 +1662015358811742208 +1662015358853743104 +1662015358895744000 +1662015358943745024 +1662015358988745984 +1662015359036747008 +1662015359078747904 +1662015359123748864 +1662015359165749760 +1662015359207750656 +1662015359246751488 +1662015359294752512 +1662015359336753408 +1662015359381754368 +1662015359423755264 +1662015359462756096 +1662015359504756992 +1662015359546757888 +1662015359588758784 +1662015359630759680 +1662015359675760640 +1662015359714761472 +1662015359756762368 +1662015359798763264 +1662015359843764224 +1662015359888765184 +1662015359927766016 +1662015359969766912 +1662015360011767808 +1662015360053768704 +1662015360098769664 +1662015360143770624 +1662015360185771520 +1662015360230772480 +1662015360275773440 +1662015360320774400 +1662015360371775488 +1662015360413776384 +1662015360452777216 +1662015360503778304 +1662015360542779136 +1662015360590780160 +1662015360635781120 +1662015360680782080 +1662015360722782976 +1662015360767783936 +1662015360812784896 +1662015360863785984 +1662015360905786880 +1662015360947787776 +1662015360989788672 +1662015361037789696 +1662015361079790592 +1662015361121791488 +1662015361169792512 +1662015361214793472 +1662015361259794432 +1662015361301795328 +1662015361346796288 +1662015361394797312 +1662015361436798208 +1662015361478799104 +1662015361520800000 +1662015361571801088 +1662015361613801984 +1662015361658802944 +1662015361700803840 +1662015361751804928 +1662015361793805824 +1662015361838806784 +1662015361880807680 +1662015361922808576 +1662015361967809536 +1662015362012810496 +1662015362054811392 +1662015362099812352 +1662015362144813312 +1662015362189814272 +1662015362234815232 +1662015362279816192 +1662015362321817088 +1662015362363817984 +1662015362408818944 +1662015362444819712 +1662015362480820480 +1662015362522821376 +1662015362567822336 +1662015362612823296 +1662015362654824192 +1662015362702825216 +1662015362744826112 +1662015362792827136 +1662015362840828160 +1662015362885829120 +1662015362927830016 +1662015362969830912 +1662015363014831872 +1662015363056832768 +1662015363098833664 +1662015363140834560 +1662015363185835520 +1662015363230836480 +1662015363269837312 +1662015363311838208 +1662015363353839104 +1662015363401840128 +1662015363446841088 +1662015363494842112 +1662015363536843008 +1662015363581843968 +1662015363623844864 +1662015363665845760 +1662015363716846848 +1662015363758847744 +1662015363800848640 +1662015363842849536 +1662015363884850432 +1662015363926851328 +1662015363971852288 +1662015364016853248 +1662015364061854208 +1662015364106855168 +1662015364151856128 +1662015364196857088 +1662015364241858048 +1662015364283858944 +1662015364325859840 +1662015364370860800 +1662015364421861888 +1662015364469862912 +1662015364508863744 +1662015364556864768 +1662015364601865728 +1662015364643866624 +1662015364685867520 +1662015364730868480 +1662015364778869504 +1662015364823870464 +1662015364865871360 +1662015364904872192 +1662015364946873088 +1662015364991874048 +1662015365042875136 +1662015365087876096 +1662015365129876992 +1662015365177878016 +1662015365225879040 +1662015365267879936 +1662015365315880960 +1662015365357881856 +1662015365399882752 +1662015365441883648 +1662015365483884544 +1662015365525885440 +1662015365570886400 +1662015365612887296 +1662015365657888256 +1662015365696889088 +1662015365741890048 +1662015365783890944 +1662015365828891904 +1662015365870892800 +1662015365915893760 +1662015365960894720 +1662015366002895616 +1662015366050896640 +1662015366092897536 +1662015366137898496 +1662015366179899392 +1662015366224900352 +1662015366266901248 +1662015366314902272 +1662015366359903232 +1662015366407904256 +1662015366449905152 +1662015366503906304 +1662015366545907200 +1662015366590908160 +1662015366635909120 +1662015366680910080 +1662015366722910976 +1662015366773912064 +1662015366818913024 +1662015366863913984 +1662015366914915072 +1662015366959916032 +1662015367004916992 +1662015367046917888 +1662015367091918848 +1662015367145920000 +1662015367190920960 +1662015367232921856 +1662015367274922752 +1662015367319923712 +1662015367364924672 +1662015367409925632 +1662015367451926528 +1662015367496927488 +1662015367538928384 +1662015367583929344 +1662015367628930304 +1662015367667931136 +1662015367712932096 +1662015367757933056 +1662015367799933952 +1662015367841934848 +1662015367880935680 +1662015367922936576 +1662015367970937600 +1662015368012938496 +1662015368054939392 +1662015368099940352 +1662015368144941312 +1662015368183942144 +1662015368228943104 +1662015368273944064 +1662015368315944960 +1662015368360945920 +1662015368402946816 +1662015368453947904 +1662015368495948800 +1662015368537949696 +1662015368579950592 +1662015368627951616 +1662015368672952576 +1662015368723953664 +1662015368768954624 +1662015368816955648 +1662015368861956608 +1662015368900957440 +1662015368948958464 +1662015368990959360 +1662015369035960320 +1662015369077961216 +1662015369119962112 +1662015369158962944 +1662015369200963840 +1662015369242964736 +1662015369284965632 +1662015369329966592 +1662015369377967616 +1662015369419968512 +1662015369461969408 +1662015369509970432 +1662015369560971520 +1662015369602972416 +1662015369641973248 +1662015369686974208 +1662015369725975040 +1662015369770976000 +1662015369809976832 +1662015369854977792 +1662015369896978688 +1662015369935979520 +1662015369977980416 +1662015370022981376 +1662015370064982272 +1662015370103983104 +1662015370151984128 +1662015370196985088 +1662015370238985984 +1662015370280986880 +1662015370322987776 +1662015370373988864 +1662015370415989760 +1662015370457990656 +1662015370502991616 +1662015370547992576 +1662015370592993536 +1662015370640994560 +1662015370682995456 +1662015370724996352 +1662015370775997440 +1662015370820998400 +1662015370862999296 +1662015370908000256 +1662015370950001152 +1662015370995002112 +1662015371040003072 +1662015371085004032 +1662015371133005056 +1662015371172005888 +1662015371214006784 +1662015371256007680 +1662015371298008576 +1662015371340009472 +1662015371385010432 +1662015371430011392 +1662015371478012416 +1662015371526013440 +1662015371571014400 +1662015371616015360 +1662015371661016320 +1662015371703017216 +1662015371742018048 +1662015371781018880 +1662015371826019840 +1662015371865020672 +1662015371913021696 +1662015371958022656 +1662015372003023616 +1662015372045024512 +1662015372087025408 +1662015372129026304 +1662015372177027328 +1662015372216028160 +1662015372258029056 +1662015372303030016 +1662015372345030912 +1662015372384031744 +1662015372438032896 +1662015372483033856 +1662015372525034752 +1662015372570035712 +1662015372615036672 +1662015372660037632 +1662015372702038528 +1662015372747039488 +1662015372792040448 +1662015372834041344 +1662015372876042240 +1662015372915043072 +1662015372960044032 +1662015373005044992 +1662015373047045888 +1662015373089046784 +1662015373134047744 +1662015373179048704 +1662015373227049728 +1662015373278050816 +1662015373323051776 +1662015373368052736 +1662015373416053760 +1662015373464054784 +1662015373512055808 +1662015373557056768 +1662015373590057472 +1662015373635058432 +1662015373677059328 +1662015373722060288 +1662015373770061312 +1662015373812062208 +1662015373854063104 +1662015373896064000 +1662015373941064960 +1662015373986065920 +1662015374028066816 +1662015374070067712 +1662015374112068608 +1662015374157069568 +1662015374199070464 +1662015374244071424 +1662015374292072448 +1662015374334073344 +1662015374373074176 +1662015374415075072 +1662015374460076032 +1662015374511077120 +1662015374553078016 +1662015374595078912 +1662015374643079936 +1662015374697081088 +1662015374742082048 +1662015374784082944 +1662015374823083776 +1662015374868084736 +1662015374913085696 +1662015374958086656 +1662015375003087616 +1662015375045088512 +1662015375087089408 +1662015375129090304 +1662015375180091392 +1662015375225092352 +1662015375276093440 +1662015375315094272 +1662015375360095232 +1662015375402096128 +1662015375453097216 +1662015375498098176 +1662015375549099264 +1662015375591100160 +1662015375636101120 +1662015375678102016 +1662015375720102912 +1662015375765103872 +1662015375813104896 +1662015375858105856 +1662015375903106816 +1662015375948107776 +1662015375996108800 +1662015376038109696 +1662015376080110592 +1662015376119111424 +1662015376167112448 +1662015376209113344 +1662015376257114368 +1662015376305115392 +1662015376347116288 +1662015376392117248 +1662015376434118144 +1662015376479119104 +1662015376524120064 +1662015376569121024 +1662015376614121984 +1662015376656122880 +1662015376707123968 +1662015376752124928 +1662015376803126016 +1662015376848126976 +1662015376893127936 +1662015376938128896 +1662015376980129792 +1662015377028130816 +1662015377073131776 +1662015377115132672 +1662015377154133504 +1662015377196134400 +1662015377238135296 +1662015377286136320 +1662015377337137408 +1662015377379138304 +1662015377424139264 +1662015377466140160 +1662015377514141184 +1662015377556142080 +1662015377604143104 +1662015377649144064 +1662015377694145024 +1662015377739145984 +1662015377781146880 +1662015377823147776 +1662015377868148736 +1662015377907149568 +1662015377949150464 +1662015377991151360 +1662015378036152320 +1662015378081153280 +1662015378120154112 +1662015378165155072 +1662015378207155968 +1662015378249156864 +1662015378285157632 +1662015378327158528 +1662015378366159360 +1662015378408160256 +1662015378456161280 +1662015378495162112 +1662015378546163200 +1662015378591164160 +1662015378636165120 +1662015378684166144 +1662015378726167040 +1662015378768167936 +1662015378813168896 +1662015378855169792 +1662015378894170624 +1662015378936171520 +1662015378978172416 +1662015379023173376 +1662015379065174272 +1662015379107175168 +1662015379149176064 +1662015379194177024 +1662015379236177920 +1662015379278178816 +1662015379323179776 +1662015379365180672 +1662015379419181824 +1662015379461182720 +1662015379500183552 +1662015379542184448 +1662015379584185344 +1662015379629186304 +1662015379680187392 +1662015379722188288 +1662015379767189248 +1662015379812190208 +1662015379854191104 +1662015379896192000 +1662015379941192960 +1662015379989193984 +1662015380037195008 +1662015380082195968 +1662015380130196992 +1662015380175197952 +1662015380220198912 +1662015380265199872 +1662015380313200896 +1662015380355201792 +1662015380397202688 +1662015380439203584 +1662015380481204480 +1662015380526205440 +1662015380568206336 +1662015380616207360 +1662015380658208256 +1662015380706209280 +1662015380760210432 +1662015380805211392 +1662015380853212416 +1662015380895213312 +1662015380937214208 +1662015380982215168 +1662015381027216128 +1662015381078217216 +1662015381120218112 +1662015381162219008 +1662015381204219904 +1662015381246220800 +1662015381288221696 +1662015381333222656 +1662015381378223616 +1662015381423224576 +1662015381468225536 +1662015381513226496 +1662015381558227456 +1662015381600228352 +1662015381639229184 +1662015381681230080 +1662015381723230976 +1662015381768231936 +1662015381816232960 +1662015381861233920 +1662015381903234816 +1662015381945235712 +1662015381990236672 +1662015382038237696 +1662015382086238720 +1662015382134239744 +1662015382182240768 +1662015382230241792 +1662015382278242816 +1662015382323243776 +1662015382365244672 +1662015382407245568 +1662015382458246656 +1662015382500247552 +1662015382545248512 +1662015382581249280 +1662015382623250176 +1662015382662251008 +1662015382713252096 +1662015382755252992 +1662015382797253888 +1662015382839254784 +1662015382878255616 +1662015382923256576 +1662015382965257472 +1662015383007258368 +1662015383052259328 +1662015383097260288 +1662015383145261312 +1662015383193262336 +1662015383238263296 +1662015383277264128 +1662015383319265024 +1662015383364265984 +1662015383409266944 +1662015383454267904 +1662015383496268800 +1662015383541269760 +1662015383583270656 +1662015383631271680 +1662015383676272640 +1662015383718273536 +1662015383763274496 +1662015383808275456 +1662015383850276352 +1662015383892277248 +1662015383934278144 +1662015383985279232 +1662015384024280064 +1662015384066280960 +1662015384108281856 +1662015384153282816 +1662015384198283776 +1662015384246284800 +1662015384288285696 +1662015384336286720 +1662015384381287680 +1662015384423288576 +1662015384465289472 +1662015384507290368 +1662015384558291456 +1662015384603292416 +1662015384642293248 +1662015384687294208 +1662015384732295168 +1662015384789296384 +1662015384831297280 +1662015384879298304 +1662015384921299200 +1662015384963300096 +1662015385005300992 +1662015385047301888 +1662015385089302784 +1662015385131303680 +1662015385176304640 +1662015385218305536 +1662015385263306496 +1662015385305307392 +1662015385347308288 +1662015385392309248 +1662015385434310144 +1662015385476311040 +1662015385518311936 +1662015385563312896 +1662015385608313856 +1662015385653314816 +1662015385710316032 +1662015385755316992 +1662015385797317888 +1662015385839318784 +1662015385884319744 +1662015385929320704 +1662015385974321664 +1662015386022322688 +1662015386061323520 +1662015386103324416 +1662015386145325312 +1662015386187326208 +1662015386229327104 +1662015386274328064 +1662015386322329088 +1662015386370330112 +1662015386412331008 +1662015386457331968 +1662015386502332928 +1662015386547333888 +1662015386595334912 +1662015386637335808 +1662015386688336896 +1662015386733337856 +1662015386778338816 +1662015386820339712 +1662015386868340736 +1662015386916341760 +1662015386961342720 +1662015387003343616 +1662015387048344576 +1662015387093345536 +1662015387141346560 +1662015387186347520 +1662015387228348416 +1662015387282349568 +1662015387330350592 +1662015387366351360 +1662015387408352256 +1662015387447353088 +1662015387489353984 +1662015387534354944 +1662015387579355904 +1662015387627356928 +1662015387669357824 +1662015387714358784 +1662015387759359744 +1662015387804360704 +1662015387858361856 +1662015387900362752 +1662015387945363712 +1662015387987364608 +1662015388029365504 +1662015388071366400 +1662015388119367424 +1662015388164368384 +1662015388209369344 +1662015388251370240 +1662015388293371136 +1662015388332371968 +1662015388374372864 +1662015388419373824 +1662015388464374784 +1662015388506375680 +1662015388548376576 +1662015388593377536 +1662015388644378624 +1662015388689379584 +1662015388731380480 +1662015388776381440 +1662015388818382336 +1662015388860383232 +1662015388905384192 +1662015388944385024 +1662015388992386048 +1662015389040387072 +1662015389082387968 +1662015389124388864 +1662015389163389696 +1662015389205390592 +1662015389247391488 +1662015389295392512 +1662015389337393408 +1662015389382394368 +1662015389424395264 +1662015389466396160 +1662015389508397056 +1662015389556398080 +1662015389598398976 +1662015389643399936 +1662015389682400768 +1662015389724401664 +1662015389766402560 +1662015389814403584 +1662015389859404544 +1662015389904405504 +1662015389940406272 +1662015389979407104 +1662015390021408000 +1662015390072409088 +1662015390120410112 +1662015390162411008 +1662015390210412032 +1662015390255412992 +1662015390300413952 +1662015390342414848 +1662015390384415744 +1662015390429416704 +1662015390468417536 +1662015390510418432 +1662015390555419392 +1662015390597420288 +1662015390639421184 +1662015390684422144 +1662015390726423040 +1662015390771424000 +1662015390813424896 +1662015390855425792 +1662015390897426688 +1662015390936427520 +1662015390978428416 +1662015391020429312 +1662015391062430208 +1662015391104431104 +1662015391152432128 +1662015391194433024 +1662015391236433920 +1662015391278434816 +1662015391326435840 +1662015391371436800 +1662015391416437760 +1662015391461438720 +1662015391503439616 +1662015391545440512 +1662015391587441408 +1662015391632442368 +1662015391677443328 +1662015391722444288 +1662015391764445184 +1662015391806446080 +1662015391848446976 +1662015391890447872 +1662015391932448768 +1662015391974449664 +1662015392019450624 +1662015392070451712 +1662015392112452608 +1662015392160453632 +1662015392202454528 +1662015392247455488 +1662015392289456384 +1662015392334457344 +1662015392379458304 +1662015392424459264 +1662015392469460224 +1662015392520461312 +1662015392562462208 +1662015392607463168 +1662015392652464128 +1662015392694465024 +1662015392739465984 +1662015392784466944 +1662015392829467904 +1662015392877468928 +1662015392916469760 +1662015392955470592 +1662015392997471488 +1662015393054472704 +1662015393102473728 +1662015393147474688 +1662015393192475648 +1662015393240476672 +1662015393282477568 +1662015393324478464 +1662015393372479488 +1662015393423480576 +1662015393468481536 +1662015393510482432 +1662015393552483328 +1662015393597484288 +1662015393642485248 +1662015393690486272 +1662015393732487168 +1662015393771488000 +1662015393819489024 +1662015393864489984 +1662015393906490880 +1662015393948491776 +1662015393993492736 +1662015394038493696 +1662015394089494784 +1662015394131495680 +1662015394173496576 +1662015394218497536 +1662015394260498432 +1662015394302499328 +1662015394347500288 +1662015394392501248 +1662015394434502144 +1662015394479503104 +1662015394521504000 +1662015394566504960 +1662015394608505856 +1662015394653506816 +1662015394698507776 +1662015394746508800 +1662015394788509696 +1662015394833510656 +1662015394878511616 +1662015394923512576 +1662015394965513472 +1662015395010514432 +1662015395061515520 +1662015395097516288 +1662015395139517184 +1662015395181518080 +1662015395223518976 +1662015395274520064 +1662015395316520960 +1662015395367522048 +1662015395409522944 +1662015395454523904 +1662015395499524864 +1662015395550525952 +1662015395589526784 +1662015395631527680 +1662015395679528704 +1662015395724529664 +1662015395766530560 +1662015395814531584 +1662015395856532480 +1662015395898533376 +1662015395943534336 +1662015395991535360 +1662015396036536320 +1662015396078537216 +1662015396126538240 +1662015396168539136 +1662015396216540160 +1662015396264541184 +1662015396309542144 +1662015396357543168 +1662015396399544064 +1662015396447545088 +1662015396492546048 +1662015396540547072 +1662015396582547968 +1662015396627548928 +1662015396675549952 +1662015396720550912 +1662015396765551872 +1662015396807552768 +1662015396852553728 +1662015396894554624 +1662015396939555584 +1662015396987556608 +1662015397020557312 +1662015397068558336 +1662015397116559360 +1662015397161560320 +1662015397203561216 +1662015397248562176 +1662015397287563008 +1662015397332563968 +1662015397377564928 +1662015397416565760 +1662015397458566656 +1662015397503567616 +1662015397545568512 +1662015397584569344 +1662015397632570368 +1662015397677571328 +1662015397722572288 +1662015397767573248 +1662015397815574272 +1662015397860575232 +1662015397905576192 +1662015397953577216 +1662015397995578112 +1662015398040579072 +1662015398085580032 +1662015398130580992 +1662015398172581888 +1662015398217582848 +1662015398259583744 +1662015398301584640 +1662015398349585664 +1662015398391586560 +1662015398436587520 +1662015398481588480 +1662015398523589376 +1662015398568590336 +1662015398613591296 +1662015398655592192 +1662015398700593152 +1662015398742594048 +1662015398793595136 +1662015398835596032 +1662015398883597056 +1662015398928598016 +1662015398967598848 +1662015399009599744 +1662015399054600704 +1662015399102601728 +1662015399150602752 +1662015399198603776 +1662015399240604672 +1662015399282605568 +1662015399330606592 +1662015399375607552 +1662015399423608576 +1662015399465609472 +1662015399507610368 +1662015399552611328 +1662015399591612160 +1662015399636613120 +1662015399678614016 +1662015399723614976 +1662015399765615872 +1662015399819617024 +1662015399867618048 +1662015399921619200 +1662015399960620032 +1662015400005620992 +1662015400050621952 +1662015400098622976 +1662015400140623872 +1662015400182624768 +1662015400227625728 +1662015400272626688 +1662015400311627520 +1662015400353628416 +1662015400404629504 +1662015400446630400 +1662015400488631296 +1662015400530632192 +1662015400575633152 +1662015400617634048 +1662015400665635072 +1662015400710636032 +1662015400752636928 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track2.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track2.txt new file mode 100644 index 0000000000..c35350d63a --- /dev/null +++ b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track2.txt @@ -0,0 +1,2537 @@ +1662122091767260928 +1662122091809261824 +1662122091851262720 +1662122091893263616 +1662122091935264512 +1662122091980265472 +1662122092022266368 +1662122092064267264 +1662122092106268160 +1662122092148269056 +1662122092193270016 +1662122092232270848 +1662122092280271872 +1662122092322272768 +1662122092364273664 +1662122092412274688 +1662122092454275584 +1662122092493276416 +1662122092535277312 +1662122092580278272 +1662122092625279232 +1662122092667280128 +1662122092709281024 +1662122092751281920 +1662122092796282880 +1662122092847283968 +1662122092889284864 +1662122092931285760 +1662122092970286592 +1662122093015287552 +1662122093060288512 +1662122093105289472 +1662122093153290496 +1662122093201291520 +1662122093240292352 +1662122093282293248 +1662122093324294144 +1662122093366295040 +1662122093408295936 +1662122093453296896 +1662122093501297920 +1662122093543298816 +1662122093591299840 +1662122093633300736 +1662122093675301632 +1662122093723302656 +1662122093768303616 +1662122093810304512 +1662122093855305472 +1662122093894306304 +1662122093939307264 +1662122093981308160 +1662122094023309056 +1662122094065309952 +1662122094110310912 +1662122094146311680 +1662122094191312640 +1662122094227313408 +1662122094275314432 +1662122094317315328 +1662122094359316224 +1662122094395316992 +1662122094437317888 +1662122094482318848 +1662122094524319744 +1662122094566320640 +1662122094611321600 +1662122094653322496 +1662122094695323392 +1662122094740324352 +1662122094782325248 +1662122094824326144 +1662122094872327168 +1662122094917328128 +1662122094965329152 +1662122095007330048 +1662122095052331008 +1662122095094331904 +1662122095139332864 +1662122095181333760 +1662122095220334592 +1662122095265335552 +1662122095316336640 +1662122095358337536 +1662122095406338560 +1662122095454339584 +1662122095496340480 +1662122095541341440 +1662122095586342400 +1662122095625343232 +1662122095667344128 +1662122095709345024 +1662122095751345920 +1662122095793346816 +1662122095835347712 +1662122095874348544 +1662122095916349440 +1662122095958350336 +1662122096000351232 +1662122096045352192 +1662122096084353024 +1662122096120353792 +1662122096162354688 +1662122096204355584 +1662122096243356416 +1662122096279357184 +1662122096327358208 +1662122096375359232 +1662122096417360128 +1662122096453360896 +1662122096495361792 +1662122096540362752 +1662122096585363712 +1662122096627364608 +1662122096669365504 +1662122096717366528 +1662122096759367424 +1662122096801368320 +1662122096843369216 +1662122096885370112 +1662122096924370944 +1662122096966371840 +1662122097005372672 +1662122097047373568 +1662122097089374464 +1662122097134375424 +1662122097179376384 +1662122097221377280 +1662122097263378176 +1662122097305379072 +1662122097347379968 +1662122097395380992 +1662122097437381888 +1662122097479382784 +1662122097521383680 +1662122097563384576 +1662122097605385472 +1662122097656386560 +1662122097704387584 +1662122097743388416 +1662122097785389312 +1662122097836390400 +1662122097881391360 +1662122097923392256 +1662122097968393216 +1662122098010394112 +1662122098052395008 +1662122098094395904 +1662122098136396800 +1662122098178397696 +1662122098226398720 +1662122098271399680 +1662122098316400640 +1662122098358401536 +1662122098397402368 +1662122098439403264 +1662122098481404160 +1662122098529405184 +1662122098577406208 +1662122098628407296 +1662122098670408192 +1662122098712409088 +1662122098757410048 +1662122098796410880 +1662122098841411840 +1662122098883412736 +1662122098922413568 +1662122098970414592 +1662122099012415488 +1662122099054416384 +1662122099096417280 +1662122099141418240 +1662122099183419136 +1662122099222419968 +1662122099267420928 +1662122099315421952 +1662122099360422912 +1662122099405423872 +1662122099450424832 +1662122099498425856 +1662122099537426688 +1662122099585427712 +1662122099624428544 +1662122099669429504 +1662122099711430400 +1662122099753431296 +1662122099798432256 +1662122099843433216 +1662122099888434176 +1662122099933435136 +1662122099969435904 +1662122100014436864 +1662122100056437760 +1662122100101438720 +1662122100146439680 +1662122100197440768 +1662122100236441600 +1662122100281442560 +1662122100323443456 +1662122100365444352 +1662122100410445312 +1662122100449446144 +1662122100494447104 +1662122100536448000 +1662122100578448896 +1662122100617449728 +1662122100659450624 +1662122100701451520 +1662122100743452416 +1662122100785453312 +1662122100824454144 +1662122100866455040 +1662122100908455936 +1662122100950456832 +1662122100992457728 +1662122101037458688 +1662122101079459584 +1662122101124460544 +1662122101160461312 +1662122101205462272 +1662122101244463104 +1662122101298464256 +1662122101340465152 +1662122101379465984 +1662122101421466880 +1662122101466467840 +1662122101514468864 +1662122101556469760 +1662122101601470720 +1662122101649471744 +1662122101694472704 +1662122101733473536 +1662122101784474624 +1662122101826475520 +1662122101865476352 +1662122101904477184 +1662122101949478144 +1662122101997479168 +1662122102042480128 +1662122102090481152 +1662122102129481984 +1662122102171482880 +1662122102213483776 +1662122102255484672 +1662122102297485568 +1662122102342486528 +1662122102384487424 +1662122102423488256 +1662122102465489152 +1662122102507490048 +1662122102546490880 +1662122102588491776 +1662122102627492608 +1662122102663493376 +1662122102705494272 +1662122102747495168 +1662122102789496064 +1662122102834497024 +1662122102876497920 +1662122102918498816 +1662122102960499712 +1662122103005500672 +1662122103044501504 +1662122103089502464 +1662122103131503360 +1662122103176504320 +1662122103221505280 +1662122103263506176 +1662122103308507136 +1662122103350508032 +1662122103392508928 +1662122103437509888 +1662122103479510784 +1662122103515511552 +1662122103557512448 +1662122103593513216 +1662122103635514112 +1662122103680515072 +1662122103725516032 +1662122103767516928 +1662122103809517824 +1662122103845518592 +1662122103887519488 +1662122103932520448 +1662122103974521344 +1662122104019522304 +1662122104061523200 +1662122104106524160 +1662122104148525056 +1662122104184525824 +1662122104223526656 +1662122104268527616 +1662122104310528512 +1662122104355529472 +1662122104397530368 +1662122104439531264 +1662122104478532096 +1662122104520532992 +1662122104562533888 +1662122104604534784 +1662122104646535680 +1662122104688536576 +1662122104730537472 +1662122104772538368 +1662122104814539264 +1662122104859540224 +1662122104904541184 +1662122104949542144 +1662122104988542976 +1662122105027543808 +1662122105072544768 +1662122105114545664 +1662122105159546624 +1662122105201547520 +1662122105243548416 +1662122105285549312 +1662122105327550208 +1662122105366551040 +1662122105408551936 +1662122105450552832 +1662122105489553664 +1662122105531554560 +1662122105573555456 +1662122105615556352 +1662122105657557248 +1662122105699558144 +1662122105747559168 +1662122105789560064 +1662122105834561024 +1662122105882562048 +1662122105924562944 +1662122105969563904 +1662122106008564736 +1662122106053565696 +1662122106092566528 +1662122106134567424 +1662122106173568256 +1662122106215569152 +1662122106251569920 +1662122106290570752 +1662122106326571520 +1662122106374572544 +1662122106416573440 +1662122106461574400 +1662122106506575360 +1662122106548576256 +1662122106584577024 +1662122106626577920 +1662122106665578752 +1662122106707579648 +1662122106752580608 +1662122106794581504 +1662122106836582400 +1662122106881583360 +1662122106923584256 +1662122106965585152 +1662122107007586048 +1662122107055587072 +1662122107097587968 +1662122107136588800 +1662122107172589568 +1662122107214590464 +1662122107259591424 +1662122107307592448 +1662122107349593344 +1662122107394594304 +1662122107433595136 +1662122107472595968 +1662122107517596928 +1662122107556597760 +1662122107598598656 +1662122107643599616 +1662122107682600448 +1662122107724601344 +1662122107769602304 +1662122107814603264 +1662122107862604288 +1662122107904605184 +1662122107949606144 +1662122107991607040 +1662122108030607872 +1662122108075608832 +1662122108117609728 +1662122108159610624 +1662122108207611648 +1662122108249612544 +1662122108291613440 +1662122108339614464 +1662122108387615488 +1662122108429616384 +1662122108471617280 +1662122108516618240 +1662122108558619136 +1662122108600620032 +1662122108642620928 +1662122108687621888 +1662122108729622784 +1662122108774623744 +1662122108816624640 +1662122108861625600 +1662122108909626624 +1662122108951627520 +1662122108990628352 +1662122109035629312 +1662122109083630336 +1662122109125631232 +1662122109164632064 +1662122109206632960 +1662122109245633792 +1662122109287634688 +1662122109332635648 +1662122109368636416 +1662122109410637312 +1662122109452638208 +1662122109491639040 +1662122109539640064 +1662122109587641088 +1662122109635642112 +1662122109674642944 +1662122109716643840 +1662122109761644800 +1662122109803645696 +1662122109845646592 +1662122109887647488 +1662122109929648384 +1662122109968649216 +1662122110010650112 +1662122110055651072 +1662122110097651968 +1662122110136652800 +1662122110178653696 +1662122110220654592 +1662122110265655552 +1662122110307656448 +1662122110352657408 +1662122110394658304 +1662122110436659200 +1662122110481660160 +1662122110526661120 +1662122110571662080 +1662122110613662976 +1662122110661664000 +1662122110703664896 +1662122110748665856 +1662122110793666816 +1662122110835667712 +1662122110880668672 +1662122110919669504 +1662122110970670592 +1662122111012671488 +1662122111054672384 +1662122111093673216 +1662122111138674176 +1662122111186675200 +1662122111225676032 +1662122111267676928 +1662122111309677824 +1662122111351678720 +1662122111393679616 +1662122111435680512 +1662122111477681408 +1662122111522682368 +1662122111570683392 +1662122111615684352 +1662122111657685248 +1662122111702686208 +1662122111747687168 +1662122111789688064 +1662122111834689024 +1662122111876689920 +1662122111918690816 +1662122111963691776 +1662122112005692672 +1662122112047693568 +1662122112089694464 +1662122112134695424 +1662122112182696448 +1662122112224697344 +1662122112266698240 +1662122112308699136 +1662122112353700096 +1662122112395700992 +1662122112434701824 +1662122112476702720 +1662122112521703680 +1662122112572704768 +1662122112617705728 +1662122112656706560 +1662122112698707456 +1662122112746708480 +1662122112788709376 +1662122112833710336 +1662122112875711232 +1662122112914712064 +1662122112953712896 +1662122112998713856 +1662122113037714688 +1662122113079715584 +1662122113118716416 +1662122113154717184 +1662122113196718080 +1662122113235718912 +1662122113277719808 +1662122113319720704 +1662122113355721472 +1662122113400722432 +1662122113448723456 +1662122113487724288 +1662122113529725184 +1662122113571726080 +1662122113613726976 +1662122113655727872 +1662122113700728832 +1662122113742729728 +1662122113784730624 +1662122113826731520 +1662122113871732480 +1662122113913733376 +1662122113958734336 +1662122114006735360 +1662122114048736256 +1662122114090737152 +1662122114132738048 +1662122114177739008 +1662122114222739968 +1662122114264740864 +1662122114309741824 +1662122114354742784 +1662122114396743680 +1662122114438744576 +1662122114489745664 +1662122114534746624 +1662122114579747584 +1662122114627748608 +1662122114669749504 +1662122114708750336 +1662122114750751232 +1662122114792752128 +1662122114837753088 +1662122114882754048 +1662122114921754880 +1662122114966755840 +1662122115008756736 +1662122115059757824 +1662122115110758912 +1662122115149759744 +1662122115194760704 +1662122115236761600 +1662122115278762496 +1662122115320763392 +1662122115365764352 +1662122115404765184 +1662122115446766080 +1662122115491767040 +1662122115533767936 +1662122115575768832 +1662122115620769792 +1662122115662770688 +1662122115707771648 +1662122115749772544 +1662122115788773376 +1662122115830774272 +1662122115875775232 +1662122115917776128 +1662122115959777024 +1662122115998777856 +1662122116043778816 +1662122116088779776 +1662122116136780800 +1662122116175781632 +1662122116217782528 +1662122116265783552 +1662122116307784448 +1662122116352785408 +1662122116394786304 +1662122116430787072 +1662122116475788032 +1662122116517788928 +1662122116562789888 +1662122116604790784 +1662122116643791616 +1662122116685792512 +1662122116727793408 +1662122116769794304 +1662122116811795200 +1662122116856796160 +1662122116901797120 +1662122116943798016 +1662122116985798912 +1662122117033799936 +1662122117075800832 +1662122117114801664 +1662122117153802496 +1662122117192803328 +1662122117240804352 +1662122117282805248 +1662122117324806144 +1662122117363806976 +1662122117408807936 +1662122117450808832 +1662122117495809792 +1662122117540810752 +1662122117582811648 +1662122117627812608 +1662122117669813504 +1662122117711814400 +1662122117759815424 +1662122117798816256 +1662122117846817280 +1662122117888818176 +1662122117933819136 +1662122117978820096 +1662122118023821056 +1662122118068822016 +1662122118113822976 +1662122118161824000 +1662122118206824960 +1662122118248825856 +1662122118287826688 +1662122118332827648 +1662122118374828544 +1662122118416829440 +1662122118461830400 +1662122118503831296 +1662122118548832256 +1662122118593833216 +1662122118638834176 +1662122118680835072 +1662122118722835968 +1662122118764836864 +1662122118806837760 +1662122118848838656 +1662122118890839552 +1662122118935840512 +1662122118977841408 +1662122119019842304 +1662122119061843200 +1662122119100844032 +1662122119145844992 +1662122119187845888 +1662122119226846720 +1662122119271847680 +1662122119319848704 +1662122119364849664 +1662122119403850496 +1662122119442851328 +1662122119484852224 +1662122119526853120 +1662122119571854080 +1662122119613854976 +1662122119652855808 +1662122119697856768 +1662122119739857664 +1662122119778858496 +1662122119823859456 +1662122119874860544 +1662122119922861568 +1662122119964862464 +1662122120009863424 +1662122120054864384 +1662122120096865280 +1662122120138866176 +1662122120180867072 +1662122120222867968 +1662122120270868992 +1662122120315869952 +1662122120360870912 +1662122120405871872 +1662122120450872832 +1662122120486873600 +1662122120525874432 +1662122120567875328 +1662122120609876224 +1662122120648877056 +1662122120690877952 +1662122120732878848 +1662122120777879808 +1662122120819880704 +1662122120858881536 +1662122120903882496 +1662122120948883456 +1662122120987884288 +1662122121023885056 +1662122121068886016 +1662122121110886912 +1662122121152887808 +1662122121194888704 +1662122121239889664 +1662122121281890560 +1662122121320891392 +1662122121365892352 +1662122121407893248 +1662122121449894144 +1662122121491895040 +1662122121536896000 +1662122121581896960 +1662122121626897920 +1662122121668898816 +1662122121710899712 +1662122121752900608 +1662122121797901568 +1662122121836902400 +1662122121878903296 +1662122121923904256 +1662122121968905216 +1662122122007906048 +1662122122049906944 +1662122122091907840 +1662122122136908800 +1662122122178909696 +1662122122223910656 +1662122122265911552 +1662122122307912448 +1662122122349913344 +1662122122394914304 +1662122122436915200 +1662122122481916160 +1662122122520916992 +1662122122568918016 +1662122122616919040 +1662122122661920000 +1662122122703920896 +1662122122745921792 +1662122122790922752 +1662122122832923648 +1662122122874924544 +1662122122913925376 +1662122122955926272 +1662122123000927232 +1662122123042928128 +1662122123087929088 +1662122123132930048 +1662122123171930880 +1662122123210931712 +1662122123249932544 +1662122123288933376 +1662122123330934272 +1662122123372935168 +1662122123414936064 +1662122123456936960 +1662122123498937856 +1662122123540938752 +1662122123579939584 +1662122123621940480 +1662122123663941376 +1662122123708942336 +1662122123753943296 +1662122123795944192 +1662122123837945088 +1662122123879945984 +1662122123918946816 +1662122123960947712 +1662122124005948672 +1662122124047949568 +1662122124092950528 +1662122124134951424 +1662122124179952384 +1662122124224953344 +1662122124266954240 +1662122124311955200 +1662122124359956224 +1662122124398957056 +1662122124440957952 +1662122124482958848 +1662122124530959872 +1662122124572960768 +1662122124617961728 +1662122124659962624 +1662122124701963520 +1662122124743964416 +1662122124788965376 +1662122124833966336 +1662122124878967296 +1662122124923968256 +1662122124968969216 +1662122125013970176 +1662122125058971136 +1662122125097971968 +1662122125139972864 +1662122125181973760 +1662122125226974720 +1662122125271975680 +1662122125310976512 +1662122125361977600 +1662122125400978432 +1662122125445979392 +1662122125493980416 +1662122125535981312 +1662122125583982336 +1662122125625983232 +1662122125670984192 +1662122125709985024 +1662122125751985920 +1662122125793986816 +1662122125835987712 +1662122125874988544 +1662122125916989440 +1662122125961990400 +1662122126003991296 +1662122126045992192 +1662122126087993088 +1662122126129993984 +1662122126171994880 +1662122126219995904 +1662122126264996864 +1662122126303997696 +1662122126351998720 +1662122126393999616 +1662122126436000512 +1662122126478001408 +1662122126523002368 +1662122126565003264 +1662122126601004032 +1662122126640004864 +1662122126685005824 +1662122126727006720 +1662122126769007616 +1662122126808008448 +1662122126850009344 +1662122126895010304 +1662122126940011264 +1662122126985012224 +1662122127021012992 +1662122127063013888 +1662122127105014784 +1662122127144015616 +1662122127189016576 +1662122127231017472 +1662122127273018368 +1662122127315019264 +1662122127363020288 +1662122127408021248 +1662122127462022400 +1662122127507023360 +1662122127549024256 +1662122127594025216 +1662122127639026176 +1662122127681027072 +1662122127729028096 +1662122127783029248 +1662122127828030208 +1662122127867031040 +1662122127909031936 +1662122127954032896 +1662122127999033856 +1662122128044034816 +1662122128086035712 +1662122128125036544 +1662122128170037504 +1662122128212038400 +1662122128257039360 +1662122128302040320 +1662122128347041280 +1662122128389042176 +1662122128440043264 +1662122128479044096 +1662122128518044928 +1662122128557045760 +1662122128599046656 +1662122128644047616 +1662122128689048576 +1662122128737049600 +1662122128776050432 +1662122128824051456 +1662122128866052352 +1662122128908053248 +1662122128950054144 +1662122128992055040 +1662122129034055936 +1662122129073056768 +1662122129115057664 +1662122129160058624 +1662122129208059648 +1662122129247060480 +1662122129295061504 +1662122129340062464 +1662122129382063360 +1662122129427064320 +1662122129472065280 +1662122129517066240 +1662122129559067136 +1662122129601068032 +1662122129640068864 +1662122129679069696 +1662122129727070720 +1662122129766071552 +1662122129808072448 +1662122129844073216 +1662122129889074176 +1662122129934075136 +1662122129976076032 +1662122130021076992 +1662122130066077952 +1662122130114078976 +1662122130159079936 +1662122130198080768 +1662122130240081664 +1662122130282082560 +1662122130330083584 +1662122130369084416 +1662122130414085376 +1662122130456086272 +1662122130498087168 +1662122130540088064 +1662122130582088960 +1662122130624089856 +1662122130669090816 +1662122130711091712 +1662122130753092608 +1662122130798093568 +1662122130840094464 +1662122130885095424 +1662122130927096320 +1662122130969097216 +1662122131011098112 +1662122131056099072 +1662122131095099904 +1662122131137100800 +1662122131182101760 +1662122131227102720 +1662122131263103488 +1662122131305104384 +1662122131350105344 +1662122131395106304 +1662122131437107200 +1662122131482108160 +1662122131527109120 +1662122131566109952 +1662122131605110784 +1662122131647111680 +1662122131689112576 +1662122131737113600 +1662122131776114432 +1662122131821115392 +1662122131863116288 +1662122131905117184 +1662122131947118080 +1662122131989118976 +1662122132028119808 +1662122132073120768 +1662122132115121664 +1662122132154122496 +1662122132205123584 +1662122132247124480 +1662122132286125312 +1662122132325126144 +1662122132370127104 +1662122132409127936 +1662122132454128896 +1662122132502129920 +1662122132541130752 +1662122132583131648 +1662122132628132608 +1662122132670133504 +1662122132712134400 +1662122132754135296 +1662122132799136256 +1662122132838137088 +1662122132877137920 +1662122132919138816 +1662122132964139776 +1662122133006140672 +1662122133051141632 +1662122133093142528 +1662122133135143424 +1662122133180144384 +1662122133225145344 +1662122133267146240 +1662122133309147136 +1662122133351148032 +1662122133393148928 +1662122133438149888 +1662122133480150784 +1662122133525151744 +1662122133567152640 +1662122133609153536 +1662122133654154496 +1662122133696155392 +1662122133744156416 +1662122133786157312 +1662122133831158272 +1662122133876159232 +1662122133921160192 +1662122133966161152 +1662122134011162112 +1662122134059163136 +1662122134101164032 +1662122134143164928 +1662122134188165888 +1662122134233166848 +1662122134281167872 +1662122134326168832 +1662122134368169728 +1662122134410170624 +1662122134452171520 +1662122134500172544 +1662122134539173376 +1662122134584174336 +1662122134626175232 +1662122134668176128 +1662122134710177024 +1662122134755177984 +1662122134797178880 +1662122134839179776 +1662122134887180800 +1662122134932181760 +1662122134971182592 +1662122135013183488 +1662122135052184320 +1662122135094185216 +1662122135133186048 +1662122135175186944 +1662122135217187840 +1662122135262188800 +1662122135310189824 +1662122135355190784 +1662122135400191744 +1662122135442192640 +1662122135487193600 +1662122135526194432 +1662122135571195392 +1662122135613196288 +1662122135652197120 +1662122135697198080 +1662122135736198912 +1662122135781199872 +1662122135823200768 +1662122135868201728 +1662122135907202560 +1662122135952203520 +1662122135994204416 +1662122136039205376 +1662122136081206272 +1662122136123207168 +1662122136168208128 +1662122136207208960 +1662122136252209920 +1662122136297210880 +1662122136342211840 +1662122136381212672 +1662122136426213632 +1662122136471214592 +1662122136516215552 +1662122136561216512 +1662122136600217344 +1662122136642218240 +1662122136684219136 +1662122136726220032 +1662122136771220992 +1662122136813221888 +1662122136861222912 +1662122136903223808 +1662122136951224832 +1662122136993225728 +1662122137035226624 +1662122137083227648 +1662122137125228544 +1662122137167229440 +1662122137209230336 +1662122137254231296 +1662122137290232064 +1662122137335233024 +1662122137371233792 +1662122137416234752 +1662122137461235712 +1662122137503236608 +1662122137551237632 +1662122137596238592 +1662122137641239552 +1662122137683240448 +1662122137728241408 +1662122137770242304 +1662122137815243264 +1662122137857244160 +1662122137902245120 +1662122137950246144 +1662122137998247168 +1662122138037248000 +1662122138082248960 +1662122138127249920 +1662122138169250816 +1662122138214251776 +1662122138265252864 +1662122138307253760 +1662122138349254656 +1662122138391255552 +1662122138433256448 +1662122138478257408 +1662122138520258304 +1662122138565259264 +1662122138610260224 +1662122138652261120 +1662122138688261888 +1662122138730262784 +1662122138772263680 +1662122138817264640 +1662122138862265600 +1662122138901266432 +1662122138940267264 +1662122138991268352 +1662122139030269184 +1662122139072270080 +1662122139117271040 +1662122139159271936 +1662122139201272832 +1662122139240273664 +1662122139282274560 +1662122139327275520 +1662122139369276416 +1662122139411277312 +1662122139450278144 +1662122139492279040 +1662122139534279936 +1662122139579280896 +1662122139621281792 +1662122139660282624 +1662122139702283520 +1662122139747284480 +1662122139792285440 +1662122139837286400 +1662122139879287296 +1662122139921288192 +1662122139963289088 +1662122140002289920 +1662122140044290816 +1662122140089291776 +1662122140128292608 +1662122140170293504 +1662122140209294336 +1662122140251295232 +1662122140296296192 +1662122140338297088 +1662122140383298048 +1662122140428299008 +1662122140470299904 +1662122140512300800 +1662122140560301824 +1662122140611302912 +1662122140659303936 +1662122140704304896 +1662122140746305792 +1662122140791306752 +1662122140833307648 +1662122140872308480 +1662122140914309376 +1662122140959310336 +1662122141004311296 +1662122141049312256 +1662122141094313216 +1662122141136314112 +1662122141178315008 +1662122141223315968 +1662122141268316928 +1662122141313317888 +1662122141352318720 +1662122141394319616 +1662122141436320512 +1662122141478321408 +1662122141523322368 +1662122141565323264 +1662122141610324224 +1662122141658325248 +1662122141706326272 +1662122141742327040 +1662122141790328064 +1662122141832328960 +1662122141871329792 +1662122141916330752 +1662122141961331712 +1662122142006332672 +1662122142045333504 +1662122142087334400 +1662122142129335296 +1662122142174336256 +1662122142216337152 +1662122142261338112 +1662122142303339008 +1662122142351340032 +1662122142393340928 +1662122142435341824 +1662122142480342784 +1662122142522343680 +1662122142561344512 +1662122142603345408 +1662122142648346368 +1662122142693347328 +1662122142735348224 +1662122142783349248 +1662122142825350144 +1662122142867351040 +1662122142915352064 +1662122142960353024 +1662122143002353920 +1662122143041354752 +1662122143086355712 +1662122143131356672 +1662122143173357568 +1662122143215358464 +1662122143260359424 +1662122143299360256 +1662122143341361152 +1662122143383362048 +1662122143425362944 +1662122143467363840 +1662122143512364800 +1662122143563365888 +1662122143605366784 +1662122143644367616 +1662122143683368448 +1662122143725369344 +1662122143767370240 +1662122143812371200 +1662122143854372096 +1662122143893372928 +1662122143935373824 +1662122143980374784 +1662122144022375680 +1662122144064376576 +1662122144112377600 +1662122144154378496 +1662122144199379456 +1662122144247380480 +1662122144289381376 +1662122144331382272 +1662122144373383168 +1662122144418384128 +1662122144454384896 +1662122144499385856 +1662122144541386752 +1662122144583387648 +1662122144628388608 +1662122144664389376 +1662122144709390336 +1662122144754391296 +1662122144793392128 +1662122144838393088 +1662122144883394048 +1662122144925394944 +1662122144973395968 +1662122145021396992 +1662122145063397888 +1662122145105398784 +1662122145144399616 +1662122145189400576 +1662122145231401472 +1662122145270402304 +1662122145315403264 +1662122145360404224 +1662122145408405248 +1662122145459406336 +1662122145504407296 +1662122145546408192 +1662122145588409088 +1662122145633410048 +1662122145678411008 +1662122145720411904 +1662122145765412864 +1662122145813413888 +1662122145855414784 +1662122145903415808 +1662122145948416768 +1662122145987417600 +1662122146032418560 +1662122146074419456 +1662122146122420480 +1662122146167421440 +1662122146212422400 +1662122146257423360 +1662122146302424320 +1662122146344425216 +1662122146389426176 +1662122146434427136 +1662122146476428032 +1662122146521428992 +1662122146563429888 +1662122146605430784 +1662122146647431680 +1662122146689432576 +1662122146734433536 +1662122146779434496 +1662122146821435392 +1662122146863436288 +1662122146908437248 +1662122146950438144 +1662122146992439040 +1662122147034439936 +1662122147070440704 +1662122147112441600 +1662122147163442688 +1662122147205443584 +1662122147244444416 +1662122147289445376 +1662122147331446272 +1662122147373447168 +1662122147415448064 +1662122147454448896 +1662122147496449792 +1662122147541450752 +1662122147583451648 +1662122147625452544 +1662122147670453504 +1662122147712454400 +1662122147754455296 +1662122147796456192 +1662122147838457088 +1662122147886458112 +1662122147931459072 +1662122147973459968 +1662122148018460928 +1662122148063461888 +1662122148105462784 +1662122148150463744 +1662122148192464640 +1662122148240465664 +1662122148279466496 +1662122148321467392 +1662122148366468352 +1662122148408469248 +1662122148447470080 +1662122148492471040 +1662122148534471936 +1662122148576472832 +1662122148621473792 +1662122148663474688 +1662122148705475584 +1662122148747476480 +1662122148792477440 +1662122148837478400 +1662122148882479360 +1662122148930480384 +1662122148972481280 +1662122149014482176 +1662122149059483136 +1662122149104484096 +1662122149146484992 +1662122149191485952 +1662122149233486848 +1662122149281487872 +1662122149323488768 +1662122149365489664 +1662122149407490560 +1662122149449491456 +1662122149491492352 +1662122149536493312 +1662122149575494144 +1662122149617495040 +1662122149659495936 +1662122149704496896 +1662122149746497792 +1662122149788498688 +1662122149830499584 +1662122149872500480 +1662122149914501376 +1662122149956502272 +1662122150001503232 +1662122150043504128 +1662122150088505088 +1662122150127505920 +1662122150169506816 +1662122150208507648 +1662122150250508544 +1662122150292509440 +1662122150334510336 +1662122150379511296 +1662122150421512192 +1662122150463513088 +1662122150511514112 +1662122150553515008 +1662122150592515840 +1662122150634516736 +1662122150679517696 +1662122150721518592 +1662122150763519488 +1662122150805520384 +1662122150847521280 +1662122150895522304 +1662122150940523264 +1662122150988524288 +1662122151033525248 +1662122151078526208 +1662122151123527168 +1662122151165528064 +1662122151210529024 +1662122151252529920 +1662122151297530880 +1662122151342531840 +1662122151384532736 +1662122151423533568 +1662122151465534464 +1662122151513535488 +1662122151561536512 +1662122151603537408 +1662122151648538368 +1662122151690539264 +1662122151735540224 +1662122151777541120 +1662122151819542016 +1662122151858542848 +1662122151903543808 +1662122151942544640 +1662122151987545600 +1662122152035546624 +1662122152077547520 +1662122152119548416 +1662122152164549376 +1662122152209550336 +1662122152254551296 +1662122152293552128 +1662122152335553024 +1662122152374553856 +1662122152416554752 +1662122152455555584 +1662122152497556480 +1662122152548557568 +1662122152587558400 +1662122152632559360 +1662122152674560256 +1662122152725561344 +1662122152770562304 +1662122152815563264 +1662122152857564160 +1662122152902565120 +1662122152941565952 +1662122152986566912 +1662122153028567808 +1662122153073568768 +1662122153115569664 +1662122153157570560 +1662122153199571456 +1662122153244572416 +1662122153286573312 +1662122153331574272 +1662122153376575232 +1662122153418576128 +1662122153463577088 +1662122153505577984 +1662122153550578944 +1662122153586579712 +1662122153637580800 +1662122153679581696 +1662122153721582592 +1662122153760583424 +1662122153805584384 +1662122153853585408 +1662122153901586432 +1662122153943587328 +1662122153982588160 +1662122154021588992 +1662122154063589888 +1662122154111590912 +1662122154153591808 +1662122154198592768 +1662122154243593728 +1662122154285594624 +1662122154324595456 +1662122154369596416 +1662122154411597312 +1662122154447598080 +1662122154489598976 +1662122154534599936 +1662122154579600896 +1662122154624601856 +1662122154666602752 +1662122154708603648 +1662122154750604544 +1662122154795605504 +1662122154837606400 +1662122154879607296 +1662122154924608256 +1662122154972609280 +1662122155014610176 +1662122155056611072 +1662122155095611904 +1662122155137612800 +1662122155179613696 +1662122155221614592 +1662122155260615424 +1662122155305616384 +1662122155347617280 +1662122155389618176 +1662122155434619136 +1662122155479620096 +1662122155524621056 +1662122155569622016 +1662122155611622912 +1662122155650623744 +1662122155695624704 +1662122155737625600 +1662122155779626496 +1662122155824627456 +1662122155866628352 +1662122155914629376 +1662122155953630208 +1662122155995631104 +1662122156043632128 +1662122156088633088 +1662122156130633984 +1662122156172634880 +1662122156214635776 +1662122156259636736 +1662122156307637760 +1662122156349638656 +1662122156397639680 +1662122156436640512 +1662122156481641472 +1662122156535642624 +1662122156574643456 +1662122156619644416 +1662122156667645440 +1662122156709646336 +1662122156751647232 +1662122156799648256 +1662122156841649152 +1662122156883650048 +1662122156928651008 +1662122156973651968 +1662122157015652864 +1662122157057653760 +1662122157102654720 +1662122157144655616 +1662122157183656448 +1662122157231657472 +1662122157273658368 +1662122157315659264 +1662122157363660288 +1662122157408661248 +1662122157450662144 +1662122157498663168 +1662122157537664000 +1662122157576664832 +1662122157618665728 +1662122157663666688 +1662122157705667584 +1662122157747668480 +1662122157789669376 +1662122157837670400 +1662122157882671360 +1662122157924672256 +1662122157966673152 +1662122158014674176 +1662122158062675200 +1662122158101676032 +1662122158149677056 +1662122158191677952 +1662122158236678912 +1662122158275679744 +1662122158317680640 +1662122158353681408 +1662122158395682304 +1662122158440683264 +1662122158482684160 +1662122158524685056 +1662122158572686080 +1662122158617687040 +1662122158662688000 +1662122158704688896 +1662122158746689792 +1662122158791690752 +1662122158830691584 +1662122158872692480 +1662122158911693312 +1662122158953694208 +1662122158998695168 +1662122159043696128 +1662122159085697024 +1662122159127697920 +1662122159163698688 +1662122159205699584 +1662122159247700480 +1662122159292701440 +1662122159337702400 +1662122159382703360 +1662122159421704192 +1662122159463705088 +1662122159502705920 +1662122159550706944 +1662122159589707776 +1662122159634708736 +1662122159673709568 +1662122159727710720 +1662122159766711552 +1662122159808712448 +1662122159850713344 +1662122159895714304 +1662122159940715264 +1662122159982716160 +1662122160021716992 +1662122160063717888 +1662122160108718848 +1662122160153719808 +1662122160201720832 +1662122160240721664 +1662122160282722560 +1662122160324723456 +1662122160366724352 +1662122160408725248 +1662122160456726272 +1662122160501727232 +1662122160546728192 +1662122160588729088 +1662122160636730112 +1662122160684731136 +1662122160732732160 +1662122160774733056 +1662122160816733952 +1662122160861734912 +1662122160903735808 +1662122160942736640 +1662122160984737536 +1662122161026738432 +1662122161068739328 +1662122161113740288 +1662122161158741248 +1662122161203742208 +1662122161245743104 +1662122161287744000 +1662122161332744960 +1662122161377745920 +1662122161419746816 +1662122161461747712 +1662122161503748608 +1662122161545749504 +1662122161593750528 +1662122161635751424 +1662122161680752384 +1662122161722753280 +1662122161764754176 +1662122161806755072 +1662122161845755904 +1662122161884756736 +1662122161926757632 +1662122161974758656 +1662122162016759552 +1662122162052760320 +1662122162091761152 +1662122162133762048 +1662122162178763008 +1662122162223763968 +1662122162265764864 +1662122162313765888 +1662122162355766784 +1662122162397767680 +1662122162439768576 +1662122162484769536 +1662122162523770368 +1662122162565771264 +1662122162607772160 +1662122162652773120 +1662122162694774016 +1662122162733774848 +1662122162778775808 +1662122162823776768 +1662122162868777728 +1662122162910778624 +1662122162949779456 +1662122162991780352 +1662122163039781376 +1662122163084782336 +1662122163126783232 +1662122163168784128 +1662122163213785088 +1662122163258786048 +1662122163297786880 +1662122163339787776 +1662122163378788608 +1662122163420789504 +1662122163456790272 +1662122163504791296 +1662122163549792256 +1662122163591793152 +1662122163633794048 +1662122163675794944 +1662122163717795840 +1662122163762796800 +1662122163804797696 +1662122163849798656 +1662122163888799488 +1662122163930800384 +1662122163972801280 +1662122164011802112 +1662122164050802944 +1662122164092803840 +1662122164134804736 +1662122164176805632 +1662122164221806592 +1662122164263807488 +1662122164305808384 +1662122164347809280 +1662122164392810240 +1662122164431811072 +1662122164470811904 +1662122164512812800 +1662122164548813568 +1662122164593814528 +1662122164635815424 +1662122164677816320 +1662122164719817216 +1662122164764818176 +1662122164812819200 +1662122164857820160 +1662122164893820928 +1662122164938821888 +1662122164980822784 +1662122165025823744 +1662122165070824704 +1662122165112825600 +1662122165157826560 +1662122165202827520 +1662122165244828416 +1662122165283829248 +1662122165325830144 +1662122165367831040 +1662122165412832000 +1662122165454832896 +1662122165499833856 +1662122165544834816 +1662122165586835712 +1662122165628836608 +1662122165670837504 +1662122165715838464 +1662122165760839424 +1662122165805840384 +1662122165853841408 +1662122165895842304 +1662122165934843136 +1662122165979844096 +1662122166021844992 +1662122166063845888 +1662122166105846784 +1662122166147847680 +1662122166189848576 +1662122166231849472 +1662122166276850432 +1662122166321851392 +1662122166360852224 +1662122166405853184 +1662122166450854144 +1662122166492855040 +1662122166531855872 +1662122166570856704 +1662122166615857664 +1662122166657858560 +1662122166702859520 +1662122166744860416 +1662122166786861312 +1662122166831862272 +1662122166876863232 +1662122166912864000 +1662122166951864832 +1662122166993865728 +1662122167035866624 +1662122167077867520 +1662122167116868352 +1662122167161869312 +1662122167206870272 +1662122167248871168 +1662122167296872192 +1662122167344873216 +1662122167386874112 +1662122167428875008 +1662122167470875904 +1662122167515876864 +1662122167560877824 +1662122167599878656 +1662122167638879488 +1662122167680880384 +1662122167722881280 +1662122167767882240 +1662122167815883264 +1662122167857884160 +1662122167899885056 +1662122167944886016 +1662122167989886976 +1662122168034887936 +1662122168079888896 +1662122168121889792 +1662122168163890688 +1662122168211891712 +1662122168253892608 +1662122168298893568 +1662122168331894272 +1662122168373895168 +1662122168415896064 +1662122168460897024 +1662122168502897920 +1662122168544898816 +1662122168586899712 +1662122168631900672 +1662122168670901504 +1662122168721902592 +1662122168763903488 +1662122168808904448 +1662122168850905344 +1662122168892906240 +1662122168931907072 +1662122168970907904 +1662122169012908800 +1662122169057909760 +1662122169096910592 +1662122169138911488 +1662122169180912384 +1662122169219913216 +1662122169264914176 +1662122169306915072 +1662122169354916096 +1662122169393916928 +1662122169438917888 +1662122169483918848 +1662122169522919680 +1662122169567920640 +1662122169609921536 +1662122169657922560 +1662122169702923520 +1662122169744924416 +1662122169786925312 +1662122169828926208 +1662122169870927104 +1662122169912928000 +1662122169957928960 +1662122169999929856 +1662122170041930752 +1662122170089931776 +1662122170128932608 +1662122170170933504 +1662122170209934336 +1662122170254935296 +1662122170296936192 +1662122170341937152 +1662122170389938176 +1662122170434939136 +1662122170476940032 +1662122170521940992 +1662122170563941888 +1662122170611942912 +1662122170659943936 +1662122170707944960 +1662122170749945856 +1662122170794946816 +1662122170839947776 +1662122170881948672 +1662122170920949504 +1662122170965950464 +1662122171016951552 +1662122171061952512 +1662122171106953472 +1662122171148954368 +1662122171193955328 +1662122171235956224 +1662122171280957184 +1662122171322958080 +1662122171364958976 +1662122171406959872 +1662122171451960832 +1662122171493961728 +1662122171541962752 +1662122171583963648 +1662122171625964544 +1662122171667965440 +1662122171715966464 +1662122171763967488 +1662122171805968384 +1662122171847969280 +1662122171892970240 +1662122171940971264 +1662122171982972160 +1662122172024973056 +1662122172066973952 +1662122172111974912 +1662122172153975808 +1662122172195976704 +1662122172237977600 +1662122172279978496 +1662122172318979328 +1662122172357980160 +1662122172402981120 +1662122172444982016 +1662122172489982976 +1662122172531983872 +1662122172576984832 +1662122172618985728 +1662122172663986688 +1662122172705987584 +1662122172750988544 +1662122172795989504 +1662122172837990400 +1662122172882991360 +1662122172924992256 +1662122172966993152 +1662122173011994112 +1662122173053995008 +1662122173095995904 +1662122173134996736 +1662122173185997824 +1662122173227998720 +1662122173275999744 +1662122173318000640 +1662122173363001600 +1662122173405002496 +1662122173447003392 +1662122173492004352 +1662122173537005312 +1662122173582006272 +1662122173627007232 +1662122173672008192 +1662122173717009152 +1662122173759010048 +1662122173804011008 +1662122173849011968 +1662122173894012928 +1662122173939013888 +1662122173981014784 +1662122174023015680 +1662122174065016576 +1662122174107017472 +1662122174149018368 +1662122174194019328 +1662122174236020224 +1662122174284021248 +1662122174329022208 +1662122174371023104 +1662122174416024064 +1662122174461025024 +1662122174503025920 +1662122174545026816 +1662122174593027840 +1662122174638028800 +1662122174680029696 +1662122174722030592 +1662122174764031488 +1662122174800032256 +1662122174845033216 +1662122174887034112 +1662122174926034944 +1662122174968035840 +1662122175007036672 +1662122175049037568 +1662122175091038464 +1662122175136039424 +1662122175175040256 +1662122175220041216 +1662122175262042112 +1662122175307043072 +1662122175352044032 +1662122175394044928 +1662122175442045952 +1662122175484046848 +1662122175535047936 +1662122175577048832 +1662122175625049856 +1662122175667050752 +1662122175712051712 +1662122175754052608 +1662122175799053568 +1662122175841054464 +1662122175883055360 +1662122175925056256 +1662122175973057280 +1662122176015058176 +1662122176057059072 +1662122176102060032 +1662122176144060928 +1662122176189061888 +1662122176231062784 +1662122176273063680 +1662122176312064512 +1662122176354065408 +1662122176396066304 +1662122176432067072 +1662122176474067968 +1662122176516068864 +1662122176558069760 +1662122176600070656 +1662122176636071424 +1662122176681072384 +1662122176726073344 +1662122176768074240 +1662122176816075264 +1662122176858076160 +1662122176900077056 +1662122176948078080 +1662122176990078976 +1662122177032079872 +1662122177077080832 +1662122177119081728 +1662122177161082624 +1662122177203083520 +1662122177245084416 +1662122177287085312 +1662122177332086272 +1662122177374087168 +1662122177416088064 +1662122177461089024 +1662122177506089984 +1662122177554091008 +1662122177596091904 +1662122177635092736 +1662122177680093696 +1662122177725094656 +1662122177770095616 +1662122177815096576 +1662122177860097536 +1662122177905098496 +1662122177947099392 +1662122177986100224 +1662122178028101120 +1662122178070102016 +1662122178112102912 +1662122178154103808 +1662122178202104832 +1662122178241105664 +1662122178280106496 +1662122178325107456 +1662122178370108416 +1662122178415109376 +1662122178454110208 +1662122178502111232 +1662122178547112192 +1662122178589113088 +1662122178634114048 +1662122178679115008 +1662122178724115968 +1662122178766116864 +1662122178814117888 +1662122178859118848 +1662122178910119936 +1662122178955120896 +1662122179003121920 +1662122179051122944 +1662122179096123904 +1662122179138124800 +1662122179180125696 +1662122179228126720 +1662122179267127552 +1662122179312128512 +1662122179363129600 +1662122179405130496 +1662122179450131456 +1662122179498132480 +1662122179540133376 +1662122179579134208 +1662122179624135168 +1662122179666136064 +1662122179711137024 +1662122179753137920 +1662122179798138880 +1662122179840139776 +1662122179885140736 +1662122179930141696 +1662122179972142592 +1662122180014143488 +1662122180056144384 +1662122180098145280 +1662122180137146112 +1662122180176146944 +1662122180227148032 +1662122180269148928 +1662122180314149888 +1662122180356150784 +1662122180395151616 +1662122180437152512 +1662122180479153408 +1662122180521154304 +1662122180566155264 +1662122180608156160 +1662122180653157120 +1662122180695158016 +1662122180734158848 +1662122180776159744 +1662122180821160704 +1662122180863161600 +1662122180908162560 +1662122180956163584 +1662122181001164544 +1662122181049165568 +1662122181091166464 +1662122181133167360 +1662122181172168192 +1662122181217169152 +1662122181262170112 +1662122181310171136 +1662122181355172096 +1662122181400173056 +1662122181442173952 +1662122181484174848 +1662122181526175744 +1662122181571176704 +1662122181613177600 +1662122181652178432 +1662122181694179328 +1662122181736180224 +1662122181772180992 +1662122181817181952 +1662122181862182912 +1662122181907183872 +1662122181949184768 +1662122181994185728 +1662122182042186752 +1662122182081187584 +1662122182117188352 +1662122182159189248 +1662122182198190080 +1662122182243191040 +1662122182285191936 +1662122182327192832 +1662122182369193728 +1662122182411194624 +1662122182456195584 +1662122182498196480 +1662122182540197376 +1662122182582198272 +1662122182624199168 +1662122182666200064 +1662122182708200960 +1662122182750201856 +1662122182795202816 +1662122182837203712 +1662122182882204672 +1662122182927205632 +1662122182969206528 +1662122183011207424 +1662122183059208448 +1662122183098209280 +1662122183137210112 +1662122183182211072 +1662122183224211968 +1662122183269212928 +1662122183308213760 +1662122183353214720 +1662122183395215616 +1662122183437216512 +1662122183476217344 +1662122183515218176 +1662122183557219072 +1662122183599219968 +1662122183641220864 +1662122183689221888 +1662122183731222784 +1662122183776223744 +1662122183821224704 +1662122183863225600 +1662122183908226560 +1662122183947227392 +1662122183989228288 +1662122184034229248 +1662122184076230144 +1662122184121231104 +1662122184163232000 +1662122184202232832 +1662122184247233792 +1662122184292234752 +1662122184334235648 +1662122184376236544 +1662122184421237504 +1662122184463238400 +1662122184508239360 +1662122184553240320 +1662122184595241216 +1662122184637242112 +1662122184679243008 +1662122184721243904 +1662122184763244800 +1662122184808245760 +1662122184850246656 +1662122184892247552 +1662122184934248448 +1662122184976249344 +1662122185015250176 +1662122185057251072 +1662122185099251968 +1662122185144252928 +1662122185192253952 +1662122185234254848 +1662122185276255744 +1662122185321256704 +1662122185366257664 +1662122185411258624 +1662122185450259456 +1662122185492260352 +1662122185531261184 +1662122185579262208 +1662122185627263232 +1662122185672264192 +1662122185717265152 +1662122185759266048 +1662122185807267072 +1662122185849267968 +1662122185888268800 +1662122185930269696 +1662122185966270464 +1662122186011271424 +1662122186053272320 +1662122186095273216 +1662122186137274112 +1662122186173274880 +1662122186218275840 +1662122186260276736 +1662122186299277568 +1662122186341278464 +1662122186383279360 +1662122186428280320 +1662122186473281280 +1662122186515282176 +1662122186563283200 +1662122186614284288 +1662122186656285184 +1662122186701286144 +1662122186746287104 +1662122186788288000 +1662122186833288960 +1662122186878289920 +1662122186917290752 +1662122186962291712 +1662122187004292608 +1662122187049293568 +1662122187088294400 +1662122187130295296 +1662122187175296256 +1662122187220297216 +1662122187262298112 +1662122187301298944 +1662122187343299840 +1662122187382300672 +1662122187424301568 +1662122187463302400 +1662122187505303296 +1662122187544304128 +1662122187586305024 +1662122187631305984 +1662122187673306880 +1662122187715307776 +1662122187757308672 +1662122187802309632 +1662122187844310528 +1662122187889311488 +1662122187934312448 +1662122187979313408 +1662122188024314368 +1662122188063315200 +1662122188111316224 +1662122188153317120 +1662122188201318144 +1662122188243319040 +1662122188294320128 +1662122188336321024 +1662122188378321920 +1662122188423322880 +1662122188465323776 +1662122188504324608 +1662122188549325568 +1662122188591326464 +1662122188636327424 +1662122188681328384 +1662122188723329280 +1662122188768330240 +1662122188813331200 +1662122188858332160 +1662122188906333184 +1662122188951334144 +1662122188996335104 +1662122189041336064 +1662122189086337024 +1662122189128337920 +1662122189173338880 +1662122189221339904 +1662122189263340800 +1662122189305341696 +1662122189350342656 +1662122189395343616 +1662122189431344384 +1662122189476345344 +1662122189518346240 +1662122189560347136 +1662122189605348096 +1662122189647348992 +1662122189692349952 +1662122189737350912 +1662122189782351872 +1662122189827352832 +1662122189872353792 +1662122189917354752 +1662122189962355712 +1662122190007356672 +1662122190052357632 +1662122190097358592 +1662122190139359488 +1662122190181360384 +1662122190220361216 +1662122190265362176 +1662122190307363072 +1662122190352364032 +1662122190397364992 +1662122190436365824 +1662122190475366656 +1662122190520367616 +1662122190565368576 +1662122190613369600 +1662122190661370624 +1662122190700371456 +1662122190742372352 +1662122190787373312 +1662122190829374208 +1662122190874375168 +1662122190916376064 +1662122190964377088 +1662122191006377984 +1662122191048378880 +1662122191099379968 +1662122191141380864 +1662122191186381824 +1662122191228382720 +1662122191276383744 +1662122191318384640 +1662122191360385536 +1662122191405386496 +1662122191444387328 +1662122191489388288 +1662122191531389184 +1662122191570390016 +1662122191609390848 +1662122191651391744 +1662122191690392576 +1662122191732393472 +1662122191774394368 +1662122191813395200 +1662122191855396096 +1662122191897396992 +1662122191936397824 +1662122191978398720 +1662122192020399616 +1662122192062400512 +1662122192101401344 +1662122192143402240 +1662122192185403136 +1662122192227404032 +1662122192269404928 +1662122192311405824 +1662122192350406656 +1662122192395407616 +1662122192437408512 +1662122192476409344 +1662122192518410240 +1662122192563411200 +1662122192608412160 +1662122192650413056 +1662122192695414016 +1662122192740414976 +1662122192782415872 +1662122192824416768 +1662122192869417728 +1662122192914418688 +1662122192956419584 +1662122193001420544 +1662122193040421376 +1662122193082422272 +1662122193127423232 +1662122193166424064 +1662122193208424960 +1662122193247425792 +1662122193289426688 +1662122193331427584 +1662122193370428416 +1662122193415429376 +1662122193454430208 +1662122193499431168 +1662122193541432064 +1662122193589433088 +1662122193631433984 +1662122193676434944 +1662122193721435904 +1662122193763436800 +1662122193808437760 +1662122193850438656 +1662122193889439488 +1662122193934440448 +1662122193976441344 +1662122194018442240 +1662122194057443072 +1662122194093443840 +1662122194135444736 +1662122194186445824 +1662122194231446784 +1662122194270447616 +1662122194309448448 +1662122194348449280 +1662122194390450176 +1662122194432451072 +1662122194471451904 +1662122194513452800 +1662122194558453760 +1662122194603454720 +1662122194645455616 +1662122194690456576 +1662122194729457408 +1662122194777458432 +1662122194819459328 +1662122194864460288 +1662122194906461184 +1662122194954462208 +1662122194999463168 +1662122195044464128 +1662122195089465088 +1662122195131465984 +1662122195179467008 +1662122195224467968 +1662122195266468864 +1662122195308469760 +1662122195353470720 +1662122195395471616 +1662122195443472640 +1662122195488473600 +1662122195533474560 +1662122195572475392 +1662122195614476288 +1662122195656477184 +1662122195698478080 +1662122195740478976 +1662122195782479872 +1662122195821480704 +1662122195866481664 +1662122195908482560 +1662122195953483520 +1662122195992484352 +1662122196037485312 +1662122196082486272 +1662122196127487232 +1662122196169488128 +1662122196211489024 +1662122196253489920 +1662122196292490752 +1662122196334491648 +1662122196373492480 +1662122196415493376 +1662122196454494208 +1662122196496495104 +1662122196538496000 +1662122196580496896 +1662122196622497792 +1662122196667498752 +1662122196709499648 +1662122196748500480 +1662122196793501440 +1662122196838502400 +1662122196880503296 +1662122196922504192 +1662122196967505152 +1662122197015506176 +1662122197057507072 +1662122197099507968 +1662122197138508800 +1662122197180509696 +1662122197222510592 +1662122197264511488 +1662122197309512448 +1662122197351513344 +1662122197393514240 +1662122197441515264 +1662122197483516160 +1662122197528517120 +1662122197570518016 +1662122197621519104 +1662122197663520000 +1662122197705520896 +1662122197747521792 +1662122197789522688 +1662122197834523648 +1662122197879524608 +1662122197921525504 +1662122197963526400 +1662122198005527296 +1662122198044528128 +1662122198086529024 +1662122198131529984 +1662122198176530944 +1662122198218531840 +1662122198263532800 +1662122198302533632 +1662122198347534592 +1662122198395535616 +1662122198434536448 +1662122198482537472 +1662122198521538304 +1662122198563539200 +1662122198605540096 +1662122198644540928 +1662122198680541696 +1662122198722542592 +1662122198767543552 +1662122198806544384 +1662122198851545344 +1662122198890546176 +1662122198938547200 +1662122198986548224 +1662122199025549056 +1662122199064549888 +1662122199103550720 +1662122199145551616 +1662122199193552640 +1662122199241553664 +1662122199283554560 +1662122199331555584 +1662122199376556544 +1662122199415557376 +1662122199463558400 +1662122199508559360 +1662122199553560320 +1662122199601561344 +1662122199640562176 +1662122199682563072 +1662122199727564032 +1662122199769564928 +1662122199814565888 +1662122199862566912 +1662122199904567808 +1662122199943568640 +1662122199994569728 +1662122200033570560 +1662122200078571520 +1662122200120572416 +1662122200159573248 +1662122200204574208 +1662122200240574976 +1662122200285575936 +1662122200330576896 +1662122200369577728 +1662122200420578816 +1662122200459579648 +1662122200498580480 +1662122200540581376 +1662122200582582272 +1662122200621583104 +1662122200666584064 +1662122200708584960 +1662122200753585920 +1662122200795586816 +1662122200834587648 +1662122200876588544 +1662122200918589440 diff --git a/Examples/Monocular/mono_mimir.cc b/Examples/Monocular/mono_mimir.cc new file mode 100644 index 0000000000..8dd739c298 --- /dev/null +++ b/Examples/Monocular/mono_mimir.cc @@ -0,0 +1,230 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include +#include +#include +#include + +#include + +#include + +using namespace std; + +void LoadImages(const string &strImagePath, const string &strPathTimes, + vector &vstrImages, vector &vTimeStamps); + +int main(int argc, char **argv) +{ + if(argc < 5) + { + cerr << endl << "Usage: ./mono_Mimir path_to_vocabulary path_to_settings path_to_sequence_folder_1 path_to_times_file_1 (path_to_image_folder_2 path_to_times_file_2 ... path_to_image_folder_N path_to_times_file_N) (trajectory_file_name)" << endl; + cerr << endl << "Example: ./Examples/Monocular/mono_mimir /home/olaya/dev/ORB_SLAM3/Vocabulary/ORBvoc.txt /home/olaya/dev/ORB_SLAM3/Examples/Monocular/MIMIR.yaml /home/olaya/Datasets/MIMIR/SeaFloor/track0/auv0/rgb/cam2/data /home/olaya/Datasets/MIMIR/SeaFloor/track0/auv0/ORB_timestamps.txt seafloor_cam2_track0.txt" << endl; + return 1; + } + + const int num_seq = (argc-3)/2; + cout << "num_seq = " << num_seq << endl; + bool bFileName= (((argc-3) % 2) == 1); + string file_name; + if (bFileName) + { + file_name = string(argv[argc-1]); + cout << "file name: " << file_name << endl; + } + + // Load all sequences: + int seq; + vector< vector > vstrImageFilenames; + vector< vector > vTimestampsCam; + vector nImages; + + vstrImageFilenames.resize(num_seq); + vTimestampsCam.resize(num_seq); + nImages.resize(num_seq); + + int tot_images = 0; + for (seq = 0; seq vTimesTrack; + vTimesTrack.resize(tot_images); + + cout << endl << "-------" << endl; + cout.precision(17); + + + int fps = 20; + float dT = 1.f/fps; + // Create SLAM system. It initializes all system threads and gets ready to process frames. + // ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR, false); FIX?? + ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR, true, 0, string(argv[3])); + float imageScale = SLAM.GetImageScale(); + + double t_resize = 0.f; + double t_track = 0.f; + + for (seq = 0; seq >(t_End_Resize - t_Start_Resize).count(); + SLAM.InsertResizeTime(t_resize); +#endif + } + + #ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); + #else + std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now(); + #endif + + // Pass the image to the SLAM system + // cout << "tframe = " << tframe << endl; + SLAM.TrackMonocular(im,tframe); // TODO change to monocular_inertial + + #ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); + #else + std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now(); + #endif + +#ifdef REGISTER_TIMES + t_track = t_resize + std::chrono::duration_cast >(t2 - t1).count(); + SLAM.InsertTrackTime(t_track); +#endif + + double ttrack= std::chrono::duration_cast >(t2 - t1).count(); + + vTimesTrack[ni]=ttrack; + + // Wait to load the next frame + double T=0; + if(ni0) + T = tframe-vTimestampsCam[seq][ni-1]; + + //std::cout << "T: " << T << std::endl; + //std::cout << "ttrack: " << ttrack << std::endl; + + if(ttrack &vstrImages, vector &vTimeStamps) +{ + ifstream fTimes; + fTimes.open(strPathTimes.c_str()); + vTimeStamps.reserve(5000); + vstrImages.reserve(5000); + while(!fTimes.eof()) + { + string s; + getline(fTimes,s); + if(!s.empty()) + { + stringstream ss; + ss << s; + vstrImages.push_back(strImagePath + "/" + ss.str() + ".png"); + double t; + ss >> t; + vTimeStamps.push_back(t*1e-9); + + } + } +} diff --git a/Examples/Stereo/MIMIR.yaml b/Examples/Stereo/MIMIR.yaml new file mode 100644 index 0000000000..547bcdccc7 --- /dev/null +++ b/Examples/Stereo/MIMIR.yaml @@ -0,0 +1,96 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# System config +#-------------------------------------------------------------------------------------------- + +# When the variables are commented, the system doesn't load a previous session or not store the current one + +# If the LoadFile doesn't exist, the system give a message and create a new Atlas from scratch +#System.LoadAtlasFromFile: "Session_MH01_MH02_MH03_Stereo60_Pseudo" + +# The store file is created from the current session, if a file with the same name exists it is deleted +#System.SaveAtlasToFile: "Session_MH01_MH02_MH03_Stereo60_Pseudo" + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- +File.version: "1.0" + +Camera.type: "PinHole" + +# Camera calibration and distortion parameters (OpenCV) +Camera1.fx: 252.07470703125 +Camera1.fy: 252.07470703125 +Camera1.cx: 360.0 +Camera1.cy: 270.0 + +Camera1.k1: 0.0 +Camera1.k2: 0.0 +Camera1.p1: 0.0 +Camera1.p2: 0.0 + +Camera2.fx: 252.07470703125 +Camera2.fy: 252.07470703125 +Camera2.cx: 360.0 +Camera2.cy: 270.0 + +Camera2.k1: 0.0 +Camera2.k2: 0.0 +Camera2.p1: 0.0 +Camera2.p2: 0.0 + +Camera.width: 720 +Camera.height: 540 + +# Camera frames per second +Camera.fps: 30 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +Stereo.ThDepth: 60.0 +Stereo.T_c1_c2: !!opencv-matrix + rows: 4 + cols: 4 + dt: f + data: [1,0,0,0, + 0,1,0,0.12, + 0,0,1,0, + 0,0,0,1] + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1200 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1.0 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize: 2.0 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3.0 +Viewer.ViewpointX: 0.0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500.0 +Viewer.imageViewScale: 1.0 + diff --git a/Examples/Stereo/MIMIR_TimeStamps/OceanFloor_track0_dark.txt b/Examples/Stereo/MIMIR_TimeStamps/OceanFloor_track0_dark.txt new file mode 100644 index 0000000000..e14794a331 --- /dev/null +++ b/Examples/Stereo/MIMIR_TimeStamps/OceanFloor_track0_dark.txt @@ -0,0 +1,2405 @@ +1662138209585822464 +1662138209624823296 +1662138209666824192 +1662138209705825024 +1662138209747825920 +1662138209789826816 +1662138209831827712 +1662138209873828608 +1662138209918829568 +1662138209972830720 +1662138210017831680 +1662138210065832704 +1662138210110833664 +1662138210155834624 +1662138210197835520 +1662138210242836480 +1662138210287837440 +1662138210329838336 +1662138210374839296 +1662138210416840192 +1662138210467841280 +1662138210515842304 +1662138210563843328 +1662138210605844224 +1662138210647845120 +1662138210698846208 +1662138210740847104 +1662138210782848000 +1662138210824848896 +1662138210869849856 +1662138210914850816 +1662138210959851776 +1662138211001852672 +1662138211046853632 +1662138211088854528 +1662138211130855424 +1662138211181856512 +1662138211223857408 +1662138211262858240 +1662138211304859136 +1662138211349860096 +1662138211391860992 +1662138211436861952 +1662138211475862784 +1662138211517863680 +1662138211562864640 +1662138211607865600 +1662138211652866560 +1662138211697867520 +1662138211745868544 +1662138211787869440 +1662138211829870336 +1662138211874871296 +1662138211925872384 +1662138211967873280 +1662138212012874240 +1662138212060875264 +1662138212102876160 +1662138212141876992 +1662138212180877824 +1662138212222878720 +1662138212270879744 +1662138212318880768 +1662138212363881728 +1662138212411882752 +1662138212465883904 +1662138212507884800 +1662138212552885760 +1662138212597886720 +1662138212639887616 +1662138212684888576 +1662138212732889600 +1662138212771890432 +1662138212813891328 +1662138212855892224 +1662138212897893120 +1662138212939894016 +1662138212981894912 +1662138213026895872 +1662138213068896768 +1662138213116897792 +1662138213161898752 +1662138213206899712 +1662138213248900608 +1662138213290901504 +1662138213332902400 +1662138213374903296 +1662138213416904192 +1662138213461905152 +1662138213509906176 +1662138213551907072 +1662138213599908096 +1662138213641908992 +1662138213695910144 +1662138213737911040 +1662138213788912128 +1662138213833913088 +1662138213881914112 +1662138213929915136 +1662138213971916032 +1662138214019917056 +1662138214061917952 +1662138214109918976 +1662138214157920000 +1662138214208921088 +1662138214250921984 +1662138214298923008 +1662138214337923840 +1662138214382924800 +1662138214430925824 +1662138214478926848 +1662138214520927744 +1662138214562928640 +1662138214604929536 +1662138214649930496 +1662138214691931392 +1662138214733932288 +1662138214775933184 +1662138214820934144 +1662138214859934976 +1662138214904935936 +1662138214955937024 +1662138214997937920 +1662138215042938880 +1662138215084939776 +1662138215132940800 +1662138215171941632 +1662138215210942464 +1662138215255943424 +1662138215300944384 +1662138215342945280 +1662138215387946240 +1662138215429947136 +1662138215468947968 +1662138215513948928 +1662138215561949952 +1662138215606950912 +1662138215648951808 +1662138215690952704 +1662138215738953728 +1662138215780954624 +1662138215828955648 +1662138215870956544 +1662138215909957376 +1662138215957958400 +1662138215999959296 +1662138216041960192 +1662138216083961088 +1662138216122961920 +1662138216164962816 +1662138216212963840 +1662138216257964800 +1662138216299965696 +1662138216341966592 +1662138216383967488 +1662138216431968512 +1662138216470969344 +1662138216512970240 +1662138216554971136 +1662138216596972032 +1662138216641972992 +1662138216689974016 +1662138216737975040 +1662138216782976000 +1662138216824976896 +1662138216866977792 +1662138216905978624 +1662138216947979520 +1662138216992980480 +1662138217034981376 +1662138217085982464 +1662138217133983488 +1662138217175984384 +1662138217214985216 +1662138217259986176 +1662138217301987072 +1662138217349988096 +1662138217391988992 +1662138217433989888 +1662138217475990784 +1662138217517991680 +1662138217559992576 +1662138217607993600 +1662138217652994560 +1662138217700995584 +1662138217742996480 +1662138217787997440 +1662138217829998336 +1662138217871999232 +1662138217914000128 +1662138217956001024 +1662138217998001920 +1662138218040002816 +1662138218085003776 +1662138218130004736 +1662138218175005696 +1662138218217006592 +1662138218256007424 +1662138218298008320 +1662138218343009280 +1662138218385010176 +1662138218427011072 +1662138218469011968 +1662138218517012992 +1662138218559013888 +1662138218601014784 +1662138218646015744 +1662138218694016768 +1662138218739017728 +1662138218781018624 +1662138218823019520 +1662138218865020416 +1662138218907021312 +1662138218949022208 +1662138218997023232 +1662138219036024064 +1662138219081025024 +1662138219123025920 +1662138219162026752 +1662138219207027712 +1662138219249028608 +1662138219294029568 +1662138219339030528 +1662138219381031424 +1662138219423032320 +1662138219474033408 +1662138219519034368 +1662138219567035392 +1662138219612036352 +1662138219660037376 +1662138219708038400 +1662138219756039424 +1662138219798040320 +1662138219846041344 +1662138219888042240 +1662138219933043200 +1662138219987044352 +1662138220035045376 +1662138220080046336 +1662138220128047360 +1662138220173048320 +1662138220218049280 +1662138220263050240 +1662138220305051136 +1662138220350052096 +1662138220395053056 +1662138220434053888 +1662138220479054848 +1662138220524055808 +1662138220569056768 +1662138220611057664 +1662138220650058496 +1662138220692059392 +1662138220734060288 +1662138220779061248 +1662138220824062208 +1662138220869063168 +1662138220917064192 +1662138220962065152 +1662138221007066112 +1662138221049067008 +1662138221091067904 +1662138221133068800 +1662138221178069760 +1662138221220070656 +1662138221265071616 +1662138221307072512 +1662138221349073408 +1662138221403074560 +1662138221445075456 +1662138221493076480 +1662138221535077376 +1662138221580078336 +1662138221628079360 +1662138221670080256 +1662138221712081152 +1662138221757082112 +1662138221799083008 +1662138221838083840 +1662138221880084736 +1662138221922085632 +1662138221961086464 +1662138222009087488 +1662138222051088384 +1662138222102089472 +1662138222150090496 +1662138222195091456 +1662138222240092416 +1662138222288093440 +1662138222336094464 +1662138222381095424 +1662138222429096448 +1662138222471097344 +1662138222513098240 +1662138222558099200 +1662138222600100096 +1662138222648101120 +1662138222687101952 +1662138222732102912 +1662138222777103872 +1662138222822104832 +1662138222870105856 +1662138222912106752 +1662138222960107776 +1662138223002108672 +1662138223044109568 +1662138223086110464 +1662138223131111424 +1662138223173112320 +1662138223221113344 +1662138223266114304 +1662138223311115264 +1662138223359116288 +1662138223401117184 +1662138223437117952 +1662138223479118848 +1662138223527119872 +1662138223569120768 +1662138223611121664 +1662138223656122624 +1662138223701123584 +1662138223749124608 +1662138223791125504 +1662138223839126528 +1662138223881127424 +1662138223926128384 +1662138223968129280 +1662138224019130368 +1662138224058131200 +1662138224112132352 +1662138224160133376 +1662138224208134400 +1662138224247135232 +1662138224289136128 +1662138224334137088 +1662138224376137984 +1662138224418138880 +1662138224463139840 +1662138224511140864 +1662138224553141760 +1662138224598142720 +1662138224643143680 +1662138224688144640 +1662138224733145600 +1662138224784146688 +1662138224826147584 +1662138224868148480 +1662138224910149376 +1662138224952150272 +1662138224994151168 +1662138225039152128 +1662138225084153088 +1662138225132154112 +1662138225174155008 +1662138225219155968 +1662138225267156992 +1662138225315158016 +1662138225360158976 +1662138225405159936 +1662138225450160896 +1662138225501161984 +1662138225546162944 +1662138225588163840 +1662138225633164800 +1662138225678165760 +1662138225723166720 +1662138225765167616 +1662138225810168576 +1662138225858169600 +1662138225900170496 +1662138225948171520 +1662138225993172480 +1662138226035173376 +1662138226077174272 +1662138226122175232 +1662138226167176192 +1662138226212177152 +1662138226254178048 +1662138226302179072 +1662138226344179968 +1662138226392180992 +1662138226431181824 +1662138226473182720 +1662138226521183744 +1662138226566184704 +1662138226608185600 +1662138226650186496 +1662138226689187328 +1662138226743188480 +1662138226794189568 +1662138226839190528 +1662138226881191424 +1662138226923192320 +1662138226971193344 +1662138227013194240 +1662138227058195200 +1662138227103196160 +1662138227148197120 +1662138227193198080 +1662138227241199104 +1662138227286200064 +1662138227337201152 +1662138227391202304 +1662138227433203200 +1662138227475204096 +1662138227517204992 +1662138227559205888 +1662138227604206848 +1662138227652207872 +1662138227694208768 +1662138227739209728 +1662138227784210688 +1662138227826211584 +1662138227868212480 +1662138227910213376 +1662138227955214336 +1662138227997215232 +1662138228039216128 +1662138228084217088 +1662138228126217984 +1662138228171218944 +1662138228225220096 +1662138228267220992 +1662138228318222080 +1662138228363223040 +1662138228405223936 +1662138228456225024 +1662138228504226048 +1662138228549227008 +1662138228594227968 +1662138228642228992 +1662138228684229888 +1662138228729230848 +1662138228783232000 +1662138228828232960 +1662138228870233856 +1662138228918234880 +1662138228966235904 +1662138229008236800 +1662138229056237824 +1662138229095238656 +1662138229143239680 +1662138229185240576 +1662138229227241472 +1662138229269242368 +1662138229317243392 +1662138229359244288 +1662138229401245184 +1662138229449246208 +1662138229503247360 +1662138229545248256 +1662138229590249216 +1662138229632250112 +1662138229674251008 +1662138229716251904 +1662138229764252928 +1662138229806253824 +1662138229851254784 +1662138229893255680 +1662138229941256704 +1662138229986257664 +1662138230028258560 +1662138230073259520 +1662138230127260672 +1662138230169261568 +1662138230217262592 +1662138230262263552 +1662138230304264448 +1662138230349265408 +1662138230394266368 +1662138230436267264 +1662138230481268224 +1662138230526269184 +1662138230574270208 +1662138230613271040 +1662138230658272000 +1662138230706273024 +1662138230748273920 +1662138230790274816 +1662138230835275776 +1662138230877276672 +1662138230919277568 +1662138230961278464 +1662138231006279424 +1662138231048280320 +1662138231099281408 +1662138231141282304 +1662138231186283264 +1662138231228284160 +1662138231279285248 +1662138231324286208 +1662138231372287232 +1662138231414288128 +1662138231468289280 +1662138231510290176 +1662138231552291072 +1662138231594291968 +1662138231633292800 +1662138231675293696 +1662138231714294528 +1662138231759295488 +1662138231810296576 +1662138231852297472 +1662138231894298368 +1662138231942299392 +1662138231984300288 +1662138232023301120 +1662138232068302080 +1662138232113303040 +1662138232155303936 +1662138232203304960 +1662138232248305920 +1662138232290306816 +1662138232338307840 +1662138232386308864 +1662138232428309760 +1662138232467310592 +1662138232515311616 +1662138232557312512 +1662138232614313728 +1662138232656314624 +1662138232695315456 +1662138232737316352 +1662138232782317312 +1662138232833318400 +1662138232875319296 +1662138232917320192 +1662138232959321088 +1662138233001321984 +1662138233046322944 +1662138233088323840 +1662138233136324864 +1662138233187325952 +1662138233232326912 +1662138233280327936 +1662138233322328832 +1662138233364329728 +1662138233409330688 +1662138233451331584 +1662138233493332480 +1662138233535333376 +1662138233580334336 +1662138233625335296 +1662138233667336192 +1662138233715337216 +1662138233757338112 +1662138233805339136 +1662138233856340224 +1662138233895341056 +1662138233940342016 +1662138233979342848 +1662138234021343744 +1662138234066344704 +1662138234108345600 +1662138234153346560 +1662138234192347392 +1662138234237348352 +1662138234282349312 +1662138234324350208 +1662138234366351104 +1662138234408352000 +1662138234453352960 +1662138234504354048 +1662138234549355008 +1662138234591355904 +1662138234645357056 +1662138234690358016 +1662138234735358976 +1662138234780359936 +1662138234828360960 +1662138234870361856 +1662138234912362752 +1662138234957363712 +1662138235002364672 +1662138235050365696 +1662138235095366656 +1662138235143367680 +1662138235194368768 +1662138235236369664 +1662138235275370496 +1662138235317371392 +1662138235359372288 +1662138235407373312 +1662138235452374272 +1662138235497375232 +1662138235545376256 +1662138235596377344 +1662138235644378368 +1662138235686379264 +1662138235728380160 +1662138235773381120 +1662138235812381952 +1662138235854382848 +1662138235905383936 +1662138235947384832 +1662138235989385728 +1662138236037386752 +1662138236079387648 +1662138236121388544 +1662138236163389440 +1662138236211390464 +1662138236256391424 +1662138236298392320 +1662138236340393216 +1662138236388394240 +1662138236430395136 +1662138236475396096 +1662138236520397056 +1662138236565398016 +1662138236607398912 +1662138236652399872 +1662138236706401024 +1662138236748401920 +1662138236796402944 +1662138236844403968 +1662138236886404864 +1662138236931405824 +1662138236976406784 +1662138237018407680 +1662138237066408704 +1662138237108409600 +1662138237150410496 +1662138237201411584 +1662138237246412544 +1662138237288413440 +1662138237336414464 +1662138237378415360 +1662138237423416320 +1662138237471417344 +1662138237513418240 +1662138237555419136 +1662138237597420032 +1662138237642420992 +1662138237687421952 +1662138237729422848 +1662138237771423744 +1662138237813424640 +1662138237852425472 +1662138237894426368 +1662138237939427328 +1662138237981428224 +1662138238023429120 +1662138238065430016 +1662138238110430976 +1662138238152431872 +1662138238197432832 +1662138238248433920 +1662138238299435008 +1662138238350436096 +1662138238392436992 +1662138238434437888 +1662138238476438784 +1662138238515439616 +1662138238563440640 +1662138238608441600 +1662138238653442560 +1662138238695443456 +1662138238737444352 +1662138238779445248 +1662138238821446144 +1662138238863447040 +1662138238905447936 +1662138238956449024 +1662138239001449984 +1662138239049451008 +1662138239091451904 +1662138239130452736 +1662138239169453568 +1662138239211454464 +1662138239259455488 +1662138239304456448 +1662138239349457408 +1662138239400458496 +1662138239451459584 +1662138239499460608 +1662138239541461504 +1662138239586462464 +1662138239640463616 +1662138239682464512 +1662138239733465600 +1662138239778466560 +1662138239823467520 +1662138239865468416 +1662138239910469376 +1662138239961470464 +1662138240006471424 +1662138240048472320 +1662138240096473344 +1662138240141474304 +1662138240183475200 +1662138240225476096 +1662138240270477056 +1662138240315478016 +1662138240357478912 +1662138240402479872 +1662138240447480832 +1662138240492481792 +1662138240534482688 +1662138240576483584 +1662138240618484480 +1662138240663485440 +1662138240717486592 +1662138240762487552 +1662138240810488576 +1662138240849489408 +1662138240897490432 +1662138240945491456 +1662138240987492352 +1662138241032493312 +1662138241077494272 +1662138241122495232 +1662138241167496192 +1662138241209497088 +1662138241257498112 +1662138241299499008 +1662138241344499968 +1662138241389500928 +1662138241434501888 +1662138241479502848 +1662138241527503872 +1662138241569504768 +1662138241608505600 +1662138241650506496 +1662138241695507456 +1662138241743508480 +1662138241785509376 +1662138241830510336 +1662138241878511360 +1662138241923512320 +1662138241974513408 +1662138242019514368 +1662138242061515264 +1662138242106516224 +1662138242151517184 +1662138242193518080 +1662138242235518976 +1662138242277519872 +1662138242319520768 +1662138242361521664 +1662138242406522624 +1662138242454523648 +1662138242499524608 +1662138242538525440 +1662138242580526336 +1662138242622527232 +1662138242667528192 +1662138242712529152 +1662138242754530048 +1662138242796530944 +1662138242844531968 +1662138242889532928 +1662138242931533824 +1662138242982534912 +1662138243030535936 +1662138243072536832 +1662138243114537728 +1662138243159538688 +1662138243204539648 +1662138243249540608 +1662138243294541568 +1662138243336542464 +1662138243381543424 +1662138243423544320 +1662138243465545216 +1662138243510546176 +1662138243552547072 +1662138243594547968 +1662138243639548928 +1662138243681549824 +1662138243723550720 +1662138243765551616 +1662138243810552576 +1662138243861553664 +1662138243900554496 +1662138243948555520 +1662138243996556544 +1662138244044557568 +1662138244086558464 +1662138244131559424 +1662138244173560320 +1662138244218561280 +1662138244260562176 +1662138244308563200 +1662138244350564096 +1662138244392564992 +1662138244431565824 +1662138244473566720 +1662138244515567616 +1662138244557568512 +1662138244599569408 +1662138244641570304 +1662138244689571328 +1662138244737572352 +1662138244782573312 +1662138244824574208 +1662138244866575104 +1662138244914576128 +1662138244965577216 +1662138245010578176 +1662138245058579200 +1662138245106580224 +1662138245151581184 +1662138245196582144 +1662138245244583168 +1662138245292584192 +1662138245337585152 +1662138245391586304 +1662138245442587392 +1662138245487588352 +1662138245535589376 +1662138245577590272 +1662138245619591168 +1662138245667592192 +1662138245706593024 +1662138245754594048 +1662138245796594944 +1662138245847596032 +1662138245895597056 +1662138245937597952 +1662138245982598912 +1662138246027599872 +1662138246078600960 +1662138246123601920 +1662138246174603008 +1662138246216603904 +1662138246258604800 +1662138246300605696 +1662138246345606656 +1662138246387607552 +1662138246435608576 +1662138246480609536 +1662138246522610432 +1662138246567611392 +1662138246609612288 +1662138246654613248 +1662138246699614208 +1662138246744615168 +1662138246786616064 +1662138246825616896 +1662138246876617984 +1662138246918618880 +1662138246960619776 +1662138247011620864 +1662138247053621760 +1662138247104622848 +1662138247149623808 +1662138247191624704 +1662138247233625600 +1662138247284626688 +1662138247329627648 +1662138247371628544 +1662138247419629568 +1662138247461630464 +1662138247509631488 +1662138247554632448 +1662138247599633408 +1662138247650634496 +1662138247692635392 +1662138247740636416 +1662138247782637312 +1662138247833638400 +1662138247875639296 +1662138247917640192 +1662138247959641088 +1662138248007642112 +1662138248049643008 +1662138248097644032 +1662138248139644928 +1662138248181645824 +1662138248229646848 +1662138248268647680 +1662138248313648640 +1662138248355649536 +1662138248400650496 +1662138248442651392 +1662138248487652352 +1662138248532653312 +1662138248571654144 +1662138248616655104 +1662138248655655936 +1662138248697656832 +1662138248739657728 +1662138248784658688 +1662138248832659712 +1662138248874660608 +1662138248919661568 +1662138248967662592 +1662138249015663616 +1662138249057664512 +1662138249105665536 +1662138249150666496 +1662138249198667520 +1662138249240668416 +1662138249282669312 +1662138249324670208 +1662138249366671104 +1662138249411672064 +1662138249456673024 +1662138249501673984 +1662138249546674944 +1662138249594675968 +1662138249636676864 +1662138249678677760 +1662138249726678784 +1662138249768679680 +1662138249810680576 +1662138249855681536 +1662138249897682432 +1662138249942683392 +1662138249990684416 +1662138250032685312 +1662138250080686336 +1662138250122687232 +1662138250170688256 +1662138250215689216 +1662138250257690112 +1662138250305691136 +1662138250347692032 +1662138250398693120 +1662138250440694016 +1662138250485694976 +1662138250527695872 +1662138250569696768 +1662138250614697728 +1662138250662698752 +1662138250707699712 +1662138250752700672 +1662138250800701696 +1662138250845702656 +1662138250887703552 +1662138250938704640 +1662138250980705536 +1662138251022706432 +1662138251067707392 +1662138251112708352 +1662138251154709248 +1662138251196710144 +1662138251238711040 +1662138251280711936 +1662138251322712832 +1662138251364713728 +1662138251409714688 +1662138251451715584 +1662138251493716480 +1662138251541717504 +1662138251583718400 +1662138251628719360 +1662138251676720384 +1662138251715721216 +1662138251757722112 +1662138251808723200 +1662138251853724160 +1662138251898725120 +1662138251937725952 +1662138251985726976 +1662138252027727872 +1662138252072728832 +1662138252114729728 +1662138252156730624 +1662138252198731520 +1662138252246732544 +1662138252285733376 +1662138252327734272 +1662138252372735232 +1662138252420736256 +1662138252459737088 +1662138252501737984 +1662138252546738944 +1662138252591739904 +1662138252633740800 +1662138252690742016 +1662138252735742976 +1662138252783744000 +1662138252831745024 +1662138252873745920 +1662138252915746816 +1662138252957747712 +1662138252996748544 +1662138253041749504 +1662138253083750400 +1662138253125751296 +1662138253167752192 +1662138253215753216 +1662138253263754240 +1662138253314755328 +1662138253353756160 +1662138253398757120 +1662138253443758080 +1662138253494759168 +1662138253536760064 +1662138253581761024 +1662138253629762048 +1662138253683763200 +1662138253725764096 +1662138253770765056 +1662138253818766080 +1662138253857766912 +1662138253899767808 +1662138253953768960 +1662138254001769984 +1662138254043770880 +1662138254088771840 +1662138254136772864 +1662138254181773824 +1662138254223774720 +1662138254265775616 +1662138254310776576 +1662138254361777664 +1662138254406778624 +1662138254451779584 +1662138254496780544 +1662138254532781312 +1662138254577782272 +1662138254622783232 +1662138254670784256 +1662138254709785088 +1662138254751785984 +1662138254799787008 +1662138254841787904 +1662138254883788800 +1662138254931789824 +1662138254979790848 +1662138255024791808 +1662138255069792768 +1662138255111793664 +1662138255153794560 +1662138255195795456 +1662138255237796352 +1662138255282797312 +1662138255333798400 +1662138255378799360 +1662138255423800320 +1662138255462801152 +1662138255507802112 +1662138255549803008 +1662138255588803840 +1662138255633804800 +1662138255675805696 +1662138255717806592 +1662138255759807488 +1662138255801808384 +1662138255846809344 +1662138255894810368 +1662138255936811264 +1662138255981812224 +1662138256023813120 +1662138256065814016 +1662138256113815040 +1662138256161816064 +1662138256206817024 +1662138256242817792 +1662138256281818624 +1662138256329819648 +1662138256371820544 +1662138256419821568 +1662138256464822528 +1662138256506823424 +1662138256554824448 +1662138256596825344 +1662138256638826240 +1662138256683827200 +1662138256725828096 +1662138256770829056 +1662138256812829952 +1662138256860830976 +1662138256911832064 +1662138256956833024 +1662138257001833984 +1662138257052835072 +1662138257094835968 +1662138257139836928 +1662138257184837888 +1662138257235838976 +1662138257277839872 +1662138257328840960 +1662138257370841856 +1662138257412842752 +1662138257454843648 +1662138257496844544 +1662138257544845568 +1662138257586846464 +1662138257628847360 +1662138257670848256 +1662138257724849408 +1662138257769850368 +1662138257811851264 +1662138257853852160 +1662138257895853056 +1662138257937853952 +1662138257979854848 +1662138258021855744 +1662138258069856768 +1662138258117857792 +1662138258156858624 +1662138258201859584 +1662138258246860544 +1662138258294861568 +1662138258342862592 +1662138258387863552 +1662138258429864448 +1662138258471865344 +1662138258516866304 +1662138258567867392 +1662138258609868288 +1662138258654869248 +1662138258696870144 +1662138258741871104 +1662138258786872064 +1662138258825872896 +1662138258867873792 +1662138258912874752 +1662138258957875712 +1662138259005876736 +1662138259047877632 +1662138259095878656 +1662138259149879808 +1662138259200880896 +1662138259242881792 +1662138259287882752 +1662138259335883776 +1662138259386884864 +1662138259428885760 +1662138259470886656 +1662138259512887552 +1662138259560888576 +1662138259602889472 +1662138259647890432 +1662138259689891328 +1662138259734892288 +1662138259776893184 +1662138259824894208 +1662138259866895104 +1662138259911896064 +1662138259956897024 +1662138259998897920 +1662138260040898816 +1662138260088899840 +1662138260133900800 +1662138260175901696 +1662138260226902784 +1662138260268903680 +1662138260316904704 +1662138260364905728 +1662138260406906624 +1662138260448907520 +1662138260490908416 +1662138260529909248 +1662138260574910208 +1662138260616911104 +1662138260667912192 +1662138260721913344 +1662138260769914368 +1662138260814915328 +1662138260856916224 +1662138260898917120 +1662138260937917952 +1662138260985918976 +1662138261036920064 +1662138261081921024 +1662138261120921856 +1662138261165922816 +1662138261207923712 +1662138261252924672 +1662138261300925696 +1662138261342926592 +1662138261384927488 +1662138261441928704 +1662138261483929600 +1662138261528930560 +1662138261573931520 +1662138261618932480 +1662138261666933504 +1662138261708934400 +1662138261753935360 +1662138261801936384 +1662138261849937408 +1662138261900938496 +1662138261945939456 +1662138261987940352 +1662138262026941184 +1662138262074942208 +1662138262116943104 +1662138262164944128 +1662138262209945088 +1662138262254946048 +1662138262296946944 +1662138262350948096 +1662138262395949056 +1662138262437949952 +1662138262482950912 +1662138262533952000 +1662138262575952896 +1662138262617953792 +1662138262668954880 +1662138262716955904 +1662138262767956992 +1662138262815958016 +1662138262857958912 +1662138262905959936 +1662138262950960896 +1662138262992961792 +1662138263043962880 +1662138263088963840 +1662138263130964736 +1662138263178965760 +1662138263220966656 +1662138263265967616 +1662138263304968448 +1662138263355969536 +1662138263400970496 +1662138263451971584 +1662138263493972480 +1662138263544973568 +1662138263592974592 +1662138263634975488 +1662138263673976320 +1662138263718977280 +1662138263763978240 +1662138263811979264 +1662138263859980288 +1662138263901981184 +1662138263949982208 +1662138263991983104 +1662138264036984064 +1662138264087985152 +1662138264129986048 +1662138264174987008 +1662138264219987968 +1662138264258988800 +1662138264303989760 +1662138264354990848 +1662138264399991808 +1662138264444992768 +1662138264483993600 +1662138264525994496 +1662138264573995520 +1662138264618996480 +1662138264660997376 +1662138264702998272 +1662138264762999552 +1662138264808000512 +1662138264850001408 +1662138264898002432 +1662138264943003392 +1662138264985004288 +1662138265030005248 +1662138265072006144 +1662138265114007040 +1662138265159008000 +1662138265207009024 +1662138265249009920 +1662138265300011008 +1662138265348012032 +1662138265390012928 +1662138265432013824 +1662138265477014784 +1662138265522015744 +1662138265564016640 +1662138265606017536 +1662138265651018496 +1662138265696019456 +1662138265744020480 +1662138265786021376 +1662138265831022336 +1662138265873023232 +1662138265918024192 +1662138265966025216 +1662138266008026112 +1662138266050027008 +1662138266095027968 +1662138266146029056 +1662138266188029952 +1662138266239031040 +1662138266284032000 +1662138266332033024 +1662138266371033856 +1662138266413034752 +1662138266455035648 +1662138266497036544 +1662138266542037504 +1662138266587038464 +1662138266629039360 +1662138266674040320 +1662138266725041408 +1662138266770042368 +1662138266821043456 +1662138266863044352 +1662138266908045312 +1662138266950046208 +1662138266992047104 +1662138267037048064 +1662138267079048960 +1662138267121049856 +1662138267166050816 +1662138267208051712 +1662138267253052672 +1662138267298053632 +1662138267343054592 +1662138267391055616 +1662138267433056512 +1662138267475057408 +1662138267520058368 +1662138267568059392 +1662138267610060288 +1662138267649061120 +1662138267694062080 +1662138267739063040 +1662138267778063872 +1662138267820064768 +1662138267862065664 +1662138267907066624 +1662138267952067584 +1662138267994068480 +1662138268039069440 +1662138268078070272 +1662138268117071104 +1662138268165072128 +1662138268210073088 +1662138268264074240 +1662138268306075136 +1662138268348076032 +1662138268387076864 +1662138268429077760 +1662138268471078656 +1662138268519079680 +1662138268564080640 +1662138268606081536 +1662138268657082624 +1662138268696083456 +1662138268744084480 +1662138268792085504 +1662138268831086336 +1662138268879087360 +1662138268924088320 +1662138268972089344 +1662138269017090304 +1662138269068091392 +1662138269107092224 +1662138269152093184 +1662138269194094080 +1662138269236094976 +1662138269290096128 +1662138269335097088 +1662138269377097984 +1662138269419098880 +1662138269464099840 +1662138269506100736 +1662138269548101632 +1662138269590102528 +1662138269632103424 +1662138269680104448 +1662138269731105536 +1662138269776106496 +1662138269818107392 +1662138269863108352 +1662138269905109248 +1662138269956110336 +1662138269998111232 +1662138270040112128 +1662138270085113088 +1662138270130114048 +1662138270172114944 +1662138270217115904 +1662138270262116864 +1662138270304117760 +1662138270352118784 +1662138270394119680 +1662138270442120704 +1662138270484121600 +1662138270529122560 +1662138270571123456 +1662138270613124352 +1662138270661125376 +1662138270703126272 +1662138270745127168 +1662138270790128128 +1662138270841129216 +1662138270886130176 +1662138270928131072 +1662138270973132032 +1662138271015132928 +1662138271063133952 +1662138271108134912 +1662138271156135936 +1662138271201136896 +1662138271243137792 +1662138271294138880 +1662138271336139776 +1662138271384140800 +1662138271426141696 +1662138271477142784 +1662138271519143680 +1662138271558144512 +1662138271600145408 +1662138271645146368 +1662138271690147328 +1662138271729148160 +1662138271777149184 +1662138271819150080 +1662138271864151040 +1662138271912152064 +1662138271954152960 +1662138271996153856 +1662138272038154752 +1662138272080155648 +1662138272125156608 +1662138272173157632 +1662138272215158528 +1662138272260159488 +1662138272305160448 +1662138272347161344 +1662138272389162240 +1662138272434163200 +1662138272485164288 +1662138272530165248 +1662138272572166144 +1662138272614167040 +1662138272659168000 +1662138272716169216 +1662138272758170112 +1662138272803171072 +1662138272848172032 +1662138272893172992 +1662138272935173888 +1662138272983174912 +1662138273028175872 +1662138273070176768 +1662138273118177792 +1662138273172178944 +1662138273217179904 +1662138273265180928 +1662138273313181952 +1662138273358182912 +1662138273406183936 +1662138273448184832 +1662138273490185728 +1662138273538186752 +1662138273583187712 +1662138273634188800 +1662138273676189696 +1662138273721190656 +1662138273766191616 +1662138273808192512 +1662138273850193408 +1662138273892194304 +1662138273931195136 +1662138273970195968 +1662138274012196864 +1662138274057197824 +1662138274099198720 +1662138274141199616 +1662138274183200512 +1662138274231201536 +1662138274279202560 +1662138274324203520 +1662138274372204544 +1662138274414205440 +1662138274459206400 +1662138274501207296 +1662138274549208320 +1662138274591209216 +1662138274633210112 +1662138274681211136 +1662138274729212160 +1662138274771213056 +1662138274813213952 +1662138274855214848 +1662138274897215744 +1662138274939216640 +1662138274981217536 +1662138275026218496 +1662138275071219456 +1662138275113220352 +1662138275155221248 +1662138275197222144 +1662138275242223104 +1662138275287224064 +1662138275332225024 +1662138275380226048 +1662138275425227008 +1662138275473228032 +1662138275518228992 +1662138275563229952 +1662138275602230784 +1662138275647231744 +1662138275689232640 +1662138275734233600 +1662138275776234496 +1662138275821235456 +1662138275863236352 +1662138275905237248 +1662138275953238272 +1662138275998239232 +1662138276040240128 +1662138276085241088 +1662138276133242112 +1662138276178243072 +1662138276220243968 +1662138276265244928 +1662138276307245824 +1662138276355246848 +1662138276394247680 +1662138276445248768 +1662138276487249664 +1662138276529250560 +1662138276577251584 +1662138276622252544 +1662138276673253632 +1662138276718254592 +1662138276760255488 +1662138276802256384 +1662138276850257408 +1662138276892258304 +1662138276940259328 +1662138276982260224 +1662138277030261248 +1662138277072262144 +1662138277120263168 +1662138277165264128 +1662138277210265088 +1662138277252265984 +1662138277303267072 +1662138277342267904 +1662138277384268800 +1662138277423269632 +1662138277465270528 +1662138277507271424 +1662138277555272448 +1662138277600273408 +1662138277645274368 +1662138277696275456 +1662138277741276416 +1662138277783277312 +1662138277825278208 +1662138277864279040 +1662138277906279936 +1662138277951280896 +1662138277999281920 +1662138278044282880 +1662138278086283776 +1662138278125284608 +1662138278179285760 +1662138278224286720 +1662138278266287616 +1662138278308288512 +1662138278350289408 +1662138278398290432 +1662138278443291392 +1662138278485292288 +1662138278524293120 +1662138278566294016 +1662138278608294912 +1662138278662296064 +1662138278710297088 +1662138278752297984 +1662138278800299008 +1662138278845299968 +1662138278887300864 +1662138278929301760 +1662138278971302656 +1662138279016303616 +1662138279058304512 +1662138279100305408 +1662138279151306496 +1662138279196307456 +1662138279244308480 +1662138279295309568 +1662138279343310592 +1662138279385311488 +1662138279430312448 +1662138279475313408 +1662138279526314496 +1662138279571315456 +1662138279634316800 +1662138279673317632 +1662138279721318656 +1662138279766319616 +1662138279820320768 +1662138279862321664 +1662138279907322624 +1662138279952323584 +1662138279994324480 +1662138280039325440 +1662138280081326336 +1662138280126327296 +1662138280174328320 +1662138280222329344 +1662138280264330240 +1662138280306331136 +1662138280348332032 +1662138280390332928 +1662138280438333952 +1662138280483334912 +1662138280525335808 +1662138280567336704 +1662138280615337728 +1662138280663338752 +1662138280705339648 +1662138280747340544 +1662138280792341504 +1662138280834342400 +1662138280879343360 +1662138280921344256 +1662138280966345216 +1662138281011346176 +1662138281056347136 +1662138281104348160 +1662138281152349184 +1662138281194350080 +1662138281242351104 +1662138281287352064 +1662138281338353152 +1662138281380354048 +1662138281419354880 +1662138281461355776 +1662138281503356672 +1662138281557357824 +1662138281599358720 +1662138281644359680 +1662138281689360640 +1662138281731361536 +1662138281782362624 +1662138281824363520 +1662138281878364672 +1662138281926365696 +1662138281971366656 +1662138282022367744 +1662138282064368640 +1662138282106369536 +1662138282148370432 +1662138282190371328 +1662138282232372224 +1662138282271373056 +1662138282313373952 +1662138282352374784 +1662138282397375744 +1662138282442376704 +1662138282484377600 +1662138282532378624 +1662138282574379520 +1662138282619380480 +1662138282661381376 +1662138282703382272 +1662138282745383168 +1662138282787384064 +1662138282829384960 +1662138282889386240 +1662138282934387200 +1662138282976388096 +1662138283024389120 +1662138283066390016 +1662138283108390912 +1662138283153391872 +1662138283195392768 +1662138283237393664 +1662138283279394560 +1662138283330395648 +1662138283375396608 +1662138283426397696 +1662138283477398784 +1662138283519399680 +1662138283561400576 +1662138283603401472 +1662138283645402368 +1662138283687403264 +1662138283729404160 +1662138283768404992 +1662138283810405888 +1662138283855406848 +1662138283900407808 +1662138283942408704 +1662138283987409664 +1662138284032410624 +1662138284077411584 +1662138284122412544 +1662138284167413504 +1662138284212414464 +1662138284254415360 +1662138284302416384 +1662138284350417408 +1662138284404418560 +1662138284446419456 +1662138284488420352 +1662138284536421376 +1662138284584422400 +1662138284626423296 +1662138284668424192 +1662138284728425472 +1662138284770426368 +1662138284812427264 +1662138284854428160 +1662138284896429056 +1662138284941430016 +1662138284992431104 +1662138285037432064 +1662138285082433024 +1662138285130434048 +1662138285178435072 +1662138285229436160 +1662138285271437056 +1662138285319438080 +1662138285370439168 +1662138285418440192 +1662138285460441088 +1662138285502441984 +1662138285550443008 +1662138285601444096 +1662138285655445248 +1662138285694446080 +1662138285742447104 +1662138285784448000 +1662138285826448896 +1662138285880450048 +1662138285928451072 +1662138285970451968 +1662138286012452864 +1662138286057453824 +1662138286108454912 +1662138286165456128 +1662138286207457024 +1662138286249457920 +1662138286297458944 +1662138286342459904 +1662138286390460928 +1662138286435461888 +1662138286480462848 +1662138286519463680 +1662138286564464640 +1662138286609465600 +1662138286660466688 +1662138286711467776 +1662138286756468736 +1662138286804469760 +1662138286852470784 +1662138286891471616 +1662138286933472512 +1662138286975473408 +1662138287020474368 +1662138287071475456 +1662138287113476352 +1662138287152477184 +1662138287197478144 +1662138287239479040 +1662138287281479936 +1662138287320480768 +1662138287362481664 +1662138287416482816 +1662138287458483712 +1662138287500484608 +1662138287545485568 +1662138287587486464 +1662138287629487360 +1662138287677488384 +1662138287719489280 +1662138287761490176 +1662138287806491136 +1662138287851492096 +1662138287893492992 +1662138287938493952 +1662138287983494912 +1662138288025495808 +1662138288067496704 +1662138288118497792 +1662138288157498624 +1662138288199499520 +1662138288238500352 +1662138288283501312 +1662138288325502208 +1662138288373503232 +1662138288418504192 +1662138288460505088 +1662138288502505984 +1662138288547506944 +1662138288592507904 +1662138288634508800 +1662138288676509696 +1662138288718510592 +1662138288763511552 +1662138288814512640 +1662138288856513536 +1662138288898514432 +1662138288940515328 +1662138288985516288 +1662138289027517184 +1662138289075518208 +1662138289117519104 +1662138289159520000 +1662138289201520896 +1662138289246521856 +1662138289291522816 +1662138289336523776 +1662138289384524800 +1662138289435525888 +1662138289480526848 +1662138289528527872 +1662138289576528896 +1662138289621529856 +1662138289663530752 +1662138289711531776 +1662138289759532800 +1662138289810533888 +1662138289852534784 +1662138289897535744 +1662138289942536704 +1662138289981537536 +1662138290026538496 +1662138290068539392 +1662138290122540544 +1662138290167541504 +1662138290215542528 +1662138290260543488 +1662138290302544384 +1662138290350545408 +1662138290392546304 +1662138290446547456 +1662138290494548480 +1662138290539549440 +1662138290584550400 +1662138290626551296 +1662138290674552320 +1662138290725553408 +1662138290767554304 +1662138290815555328 +1662138290857556224 +1662138290899557120 +1662138290944558080 +1662138290995559168 +1662138291037560064 +1662138291082561024 +1662138291124561920 +1662138291166562816 +1662138291208563712 +1662138291253564672 +1662138291304565760 +1662138291352566784 +1662138291394567680 +1662138291439568640 +1662138291484569600 +1662138291532570624 +1662138291574571520 +1662138291622572544 +1662138291667573504 +1662138291712574464 +1662138291760575488 +1662138291802576384 +1662138291844577280 +1662138291889578240 +1662138291931579136 +1662138291979580160 +1662138292021581056 +1662138292063581952 +1662138292105582848 +1662138292147583744 +1662138292198584832 +1662138292243585792 +1662138292288586752 +1662138292333587712 +1662138292378588672 +1662138292429589760 +1662138292471590656 +1662138292510591488 +1662138292552592384 +1662138292597593344 +1662138292645594368 +1662138292687595264 +1662138292726596096 +1662138292768596992 +1662138292813597952 +1662138292861598976 +1662138292903599872 +1662138292948600832 +1662138292990601728 +1662138293032602624 +1662138293077603584 +1662138293125604608 +1662138293170605568 +1662138293218606592 +1662138293266607616 +1662138293311608576 +1662138293359609600 +1662138293404610560 +1662138293446611456 +1662138293488612352 +1662138293533613312 +1662138293581614336 +1662138293623615232 +1662138293665616128 +1662138293710617088 +1662138293755618048 +1662138293800619008 +1662138293845619968 +1662138293887620864 +1662138293929621760 +1662138293989623040 +1662138294037624064 +1662138294085625088 +1662138294127625984 +1662138294172626944 +1662138294214627840 +1662138294265628928 +1662138294307629824 +1662138294349630720 +1662138294394631680 +1662138294436632576 +1662138294481633536 +1662138294526634496 +1662138294574635520 +1662138294619636480 +1662138294661637376 +1662138294706638336 +1662138294751639296 +1662138294796640256 +1662138294841641216 +1662138294886642176 +1662138294931643136 +1662138294973644032 +1662138295018644992 +1662138295063645952 +1662138295105646848 +1662138295153647872 +1662138295195648768 +1662138295246649856 +1662138295288650752 +1662138295339651840 +1662138295384652800 +1662138295426653696 +1662138295480654848 +1662138295531655936 +1662138295573656832 +1662138295618657792 +1662138295663658752 +1662138295708659712 +1662138295765660928 +1662138295810661888 +1662138295852662784 +1662138295897663744 +1662138295936664576 +1662138295975665408 +1662138296026666496 +1662138296068667392 +1662138296110668288 +1662138296155669248 +1662138296200670208 +1662138296242671104 +1662138296284672000 +1662138296329672960 +1662138296380674048 +1662138296419674880 +1662138296470675968 +1662138296512676864 +1662138296554677760 +1662138296602678784 +1662138296644679680 +1662138296686680576 +1662138296737681664 +1662138296779682560 +1662138296821683456 +1662138296872684544 +1662138296917685504 +1662138296959686400 +1662138297016687616 +1662138297061688576 +1662138297109689600 +1662138297154690560 +1662138297193691392 +1662138297235692288 +1662138297289693440 +1662138297337694464 +1662138297382695424 +1662138297424696320 +1662138297466697216 +1662138297508698112 +1662138297559699200 +1662138297601700096 +1662138297646701056 +1662138297697702144 +1662138297742703104 +1662138297784704000 +1662138297823704832 +1662138297862705664 +1662138297901706496 +1662138297952707584 +1662138298000708608 +1662138298045709568 +1662138298090710528 +1662138298141711616 +1662138298183712512 +1662138298225713408 +1662138298270714368 +1662138298315715328 +1662138298360716288 +1662138298405717248 +1662138298447718144 +1662138298492719104 +1662138298534720000 +1662138298576720896 +1662138298618721792 +1662138298660722688 +1662138298702723584 +1662138298744724480 +1662138298798725632 +1662138298840726528 +1662138298888727552 +1662138298936728576 +1662138298981729536 +1662138299023730432 +1662138299065731328 +1662138299107732224 +1662138299155733248 +1662138299197734144 +1662138299239735040 +1662138299287736064 +1662138299329736960 +1662138299374737920 +1662138299428739072 +1662138299479740160 +1662138299527741184 +1662138299578742272 +1662138299620743168 +1662138299662744064 +1662138299707745024 +1662138299749745920 +1662138299803747072 +1662138299848748032 +1662138299902749184 +1662138299944750080 +1662138299986750976 +1662138300028751872 +1662138300073752832 +1662138300118753792 +1662138300160754688 +1662138300199755520 +1662138300241756416 +1662138300286757376 +1662138300331758336 +1662138300373759232 +1662138300421760256 +1662138300463761152 +1662138300505762048 +1662138300559763200 +1662138300601764096 +1662138300643764992 +1662138300691766016 +1662138300730766848 +1662138300781767936 +1662138300823768832 +1662138300865769728 +1662138300904770560 +1662138300949771520 +1662138300997772544 +1662138301039773440 +1662138301087774464 +1662138301129775360 +1662138301174776320 +1662138301222777344 +1662138301264778240 +1662138301306779136 +1662138301351780096 +1662138301399781120 +1662138301441782016 +1662138301489783040 +1662138301531783936 +1662138301573784832 +1662138301621785856 +1662138301666786816 +1662138301708787712 +1662138301753788672 +1662138301795789568 +1662138301837790464 +1662138301879791360 +1662138301927792384 +1662138301978793472 +1662138302023794432 +1662138302065795328 +1662138302116796416 +1662138302167797504 +1662138302215798528 +1662138302266799616 +1662138302308800512 +1662138302356801536 +1662138302398802432 +1662138302446803456 +1662138302488804352 +1662138302533805312 +1662138302587806464 +1662138302629807360 +1662138302671808256 +1662138302713809152 +1662138302758810112 +1662138302803811072 +1662138302851812096 +1662138302896813056 +1662138302938813952 +1662138302983814912 +1662138303025815808 +1662138303073816832 +1662138303118817792 +1662138303163818752 +1662138303208819712 +1662138303256820736 +1662138303298821632 +1662138303340822528 +1662138303391823616 +1662138303439824640 +1662138303487825664 +1662138303532826624 +1662138303577827584 +1662138303625828608 +1662138303667829504 +1662138303709830400 +1662138303754831360 +1662138303799832320 +1662138303844833280 +1662138303886834176 +1662138303937835264 +1662138303982836224 +1662138304024837120 +1662138304066838016 +1662138304114839040 +1662138304171840256 +1662138304213841152 +1662138304264842240 +1662138304309843200 +1662138304357844224 +1662138304405845248 +1662138304450846208 +1662138304492847104 +1662138304540848128 +1662138304585849088 +1662138304627849984 +1662138304675851008 +1662138304720851968 +1662138304765852928 +1662138304813853952 +1662138304855854848 +1662138304903855872 +1662138304948856832 +1662138304999857920 +1662138305047858944 +1662138305089859840 +1662138305140860928 +1662138305194862080 +1662138305239863040 +1662138305278863872 +1662138305326864896 +1662138305374865920 +1662138305419866880 +1662138305461867776 +1662138305509868800 +1662138305557869824 +1662138305599870720 +1662138305647871744 +1662138305689872640 +1662138305734873600 +1662138305776874496 +1662138305830875648 +1662138305878876672 +1662138305929877760 +1662138305974878720 +1662138306019879680 +1662138306073880832 +1662138306115881728 +1662138306160882688 +1662138306202883584 +1662138306250884608 +1662138306292885504 +1662138306334886400 +1662138306376887296 +1662138306421888256 +1662138306463889152 +1662138306505890048 +1662138306565891328 +1662138306610892288 +1662138306652893184 +1662138306694894080 +1662138306742895104 +1662138306787896064 +1662138306838897152 +1662138306880898048 +1662138306925899008 +1662138306970899968 +1662138307021901056 +1662138307060901888 +1662138307105902848 +1662138307147903744 +1662138307192904704 +1662138307237905664 +1662138307288906752 +1662138307327907584 +1662138307375908608 +1662138307420909568 +1662138307468910592 +1662138307516911616 +1662138307561912576 +1662138307612913664 +1662138307654914560 +1662138307705915648 +1662138307753916672 +1662138307801917696 +1662138307852918784 +1662138307900919808 +1662138307948920832 +1662138307990921728 +1662138308032922624 +1662138308080923648 +1662138308125924608 +1662138308176925696 +1662138308221926656 +1662138308266927616 +1662138308308928512 +1662138308356929536 +1662138308401930496 +1662138308446931456 +1662138308494932480 +1662138308545933568 +1662138308584934400 +1662138308623935232 +1662138308668936192 +1662138308713937152 +1662138308758938112 +1662138308800939008 +1662138308845939968 +1662138308887940864 +1662138308929941760 +1662138308980942848 +1662138309022943744 +1662138309064944640 +1662138309109945600 +1662138309157946624 +1662138309205947648 +1662138309256948736 +1662138309301949696 +1662138309352950784 +1662138309397951744 +1662138309442952704 +1662138309493953792 +1662138309535954688 +1662138309583955712 +1662138309634956800 +1662138309676957696 +1662138309718958592 +1662138309763959552 +1662138309805960448 +1662138309859961600 +1662138309907962624 +1662138309949963520 +1662138310006964736 +1662138310048965632 +1662138310090966528 +1662138310138967552 +1662138310183968512 +1662138310225969408 +1662138310282970624 +1662138310321971456 +1662138310363972352 +1662138310411973376 +1662138310456974336 +1662138310501975296 +1662138310552976384 +1662138310594977280 +1662138310639978240 +1662138310684979200 +1662138310729980160 +1662138310771981056 +1662138310819982080 +1662138310861982976 +1662138310909984000 +1662138310960985088 +1662138311011986176 +1662138311065987328 +1662138311110988288 +1662138311152989184 +1662138311194990080 +1662138311239991040 +1662138311284992000 +1662138311332993024 +1662138311380994048 +1662138311428995072 +1662138311479996160 +1662138311530997248 +1662138311578998272 +1662138311623999232 +1662138311675000320 +1662138311717001216 +1662138311759002112 +1662138311804003072 +1662138311855004160 +1662138311906005248 +1662138311951006208 +1662138311993007104 +1662138312044008192 +1662138312089009152 +1662138312134010112 +1662138312179011072 +1662138312224012032 +1662138312266012928 +1662138312314013952 +1662138312362014976 +1662138312407015936 +1662138312449016832 +1662138312497017856 +1662138312536018688 +1662138312593019904 +1662138312638020864 +1662138312686021888 +1662138312731022848 +1662138312782023936 +1662138312830024960 +1662138312878025984 +1662138312920026880 +1662138312962027776 +1662138313010028800 +1662138313064029952 +1662138313112030976 +1662138313163032064 +1662138313208033024 +1662138313253033984 +1662138313301035008 +1662138313343035904 +1662138313388036864 +1662138313427037696 +1662138313472038656 +1662138313517039616 +1662138313565040640 +1662138313610041600 +1662138313658042624 +1662138313703043584 +1662138313748044544 +1662138313787045376 +1662138313841046528 +1662138313886047488 +1662138313931048448 +1662138313976049408 +1662138314021050368 +1662138314063051264 +1662138314111052288 +1662138314156053248 +1662138314201054208 +1662138314258055424 +1662138314303056384 +1662138314345057280 +1662138314387058176 +1662138314432059136 +1662138314474060032 +1662138314516060928 +1662138314564061952 +1662138314612062976 +1662138314657063936 +1662138314696064768 +1662138314738065664 +1662138314783066624 +1662138314783066624 +1662138314828067584 +1662138314873068544 +1662138314915069440 +1662138314957070336 +1662138314999071232 +1662138315041072128 +1662138315080072960 +1662138315128073984 +1662138315176075008 +1662138315224076032 +1662138315269076992 +1662138315317078016 +1662138315362078976 +1662138315410080000 +1662138315461081088 +1662138315509082112 +1662138315551083008 +1662138315599084032 +1662138315641084928 +1662138315683085824 +1662138315728086784 +1662138315770087680 +1662138315815088640 +1662138315854089472 +1662138315905090560 +1662138315947091456 +1662138315992092416 +1662138316037093376 +1662138316082094336 +1662138316133095424 +1662138316178096384 +1662138316223097344 +1662138316265098240 +1662138316310099200 +1662138316358100224 +1662138316397101056 +1662138316442102016 +1662138316493103104 +1662138316538104064 +1662138316583105024 +1662138316625105920 +1662138316676107008 +1662138316727108096 +1662138316772109056 +1662138316814109952 +1662138316859110912 +1662138316901111808 +1662138316946112768 +1662138316994113792 +1662138317036114688 +1662138317081115648 +1662138317123116544 +1662138317165117440 diff --git a/Examples/Stereo/MIMIR_TimeStamps/OceanFloor_track0_light.txt b/Examples/Stereo/MIMIR_TimeStamps/OceanFloor_track0_light.txt new file mode 100644 index 0000000000..cca6f70bc4 --- /dev/null +++ b/Examples/Stereo/MIMIR_TimeStamps/OceanFloor_track0_light.txt @@ -0,0 +1,2421 @@ +1662135911410189568 +1662135911452190464 +1662135911491191296 +1662135911539192320 +1662135911584193280 +1662135911638194432 +1662135911683195392 +1662135911731196416 +1662135911776197376 +1662135911824198400 +1662135911866199296 +1662135911908200192 +1662135911953201152 +1662135912001202176 +1662135912052203264 +1662135912094204160 +1662135912136205056 +1662135912181206016 +1662135912232207104 +1662135912280208128 +1662135912322209024 +1662135912370210048 +1662135912412210944 +1662135912454211840 +1662135912496212736 +1662135912538213632 +1662135912583214592 +1662135912625215488 +1662135912667216384 +1662135912712217344 +1662135912754218240 +1662135912796219136 +1662135912844220160 +1662135912889221120 +1662135912928221952 +1662135912970222848 +1662135913015223808 +1662135913057224704 +1662135913108225792 +1662135913159226880 +1662135913210227968 +1662135913249228800 +1662135913306230016 +1662135913351230976 +1662135913396231936 +1662135913441232896 +1662135913492233984 +1662135913540235008 +1662135913585235968 +1662135913639237120 +1662135913681238016 +1662135913729239040 +1662135913774240000 +1662135913825241088 +1662135913867241984 +1662135913909242880 +1662135913951243776 +1662135913993244672 +1662135914041245696 +1662135914086246656 +1662135914131247616 +1662135914173248512 +1662135914218249472 +1662135914260250368 +1662135914302251264 +1662135914350252288 +1662135914392253184 +1662135914437254144 +1662135914491255296 +1662135914530256128 +1662135914569256960 +1662135914611257856 +1662135914653258752 +1662135914698259712 +1662135914740260608 +1662135914782261504 +1662135914824262400 +1662135914866263296 +1662135914908264192 +1662135914953265152 +1662135914998266112 +1662135915046267136 +1662135915091268096 +1662135915136269056 +1662135915181270016 +1662135915223270912 +1662135915277272064 +1662135915325273088 +1662135915364273920 +1662135915415275008 +1662135915457275904 +1662135915499276800 +1662135915544277760 +1662135915586278656 +1662135915628279552 +1662135915676280576 +1662135915718281472 +1662135915772282624 +1662135915811283456 +1662135915853284352 +1662135915907285504 +1662135915949286400 +1662135915994287360 +1662135916039288320 +1662135916093289472 +1662135916135290368 +1662135916177291264 +1662135916222292224 +1662135916267293184 +1662135916309294080 +1662135916351294976 +1662135916393295872 +1662135916438296832 +1662135916486297856 +1662135916531298816 +1662135916573299712 +1662135916621300736 +1662135916669301760 +1662135916714302720 +1662135916759303680 +1662135916807304704 +1662135916849305600 +1662135916891306496 +1662135916933307392 +1662135916984308480 +1662135917035309568 +1662135917080310528 +1662135917125311488 +1662135917167312384 +1662135917212313344 +1662135917257314304 +1662135917311315456 +1662135917356316416 +1662135917395317248 +1662135917437318144 +1662135917482319104 +1662135917524320000 +1662135917569320960 +1662135917623322112 +1662135917668323072 +1662135917716324096 +1662135917758324992 +1662135917800325888 +1662135917839326720 +1662135917887327744 +1662135917929328640 +1662135917971329536 +1662135918013330432 +1662135918052331264 +1662135918094332160 +1662135918136333056 +1662135918178333952 +1662135918220334848 +1662135918262335744 +1662135918307336704 +1662135918361337856 +1662135918406338816 +1662135918448339712 +1662135918508340992 +1662135918550341888 +1662135918592342784 +1662135918643343872 +1662135918685344768 +1662135918733345792 +1662135918775346688 +1662135918817347584 +1662135918856348416 +1662135918898349312 +1662135918946350336 +1662135918994351360 +1662135919036352256 +1662135919078353152 +1662135919120354048 +1662135919159354880 +1662135919201355776 +1662135919246356736 +1662135919294357760 +1662135919342358784 +1662135919387359744 +1662135919429360640 +1662135919474361600 +1662135919513362432 +1662135919555363328 +1662135919597364224 +1662135919645365248 +1662135919690366208 +1662135919732367104 +1662135919774368000 +1662135919816368896 +1662135919861369856 +1662135919906370816 +1662135919951371776 +1662135920005372928 +1662135920047373824 +1662135920095374848 +1662135920140375808 +1662135920185376768 +1662135920230377728 +1662135920272378624 +1662135920314379520 +1662135920356380416 +1662135920398381312 +1662135920440382208 +1662135920488383232 +1662135920536384256 +1662135920578385152 +1662135920617385984 +1662135920659386880 +1662135920704387840 +1662135920749388800 +1662135920797389824 +1662135920851390976 +1662135920896391936 +1662135920941392896 +1662135920983393792 +1662135921025394688 +1662135921070395648 +1662135921115396608 +1662135921154397440 +1662135921196398336 +1662135921250399488 +1662135921292400384 +1662135921358401792 +1662135921406402816 +1662135921448403712 +1662135921496404736 +1662135921544405760 +1662135921595406848 +1662135921640407808 +1662135921685408768 +1662135921724409600 +1662135921775410688 +1662135921823411712 +1662135921865412608 +1662135921907413504 +1662135921952414464 +1662135921997415424 +1662135922039416320 +1662135922081417216 +1662135922123418112 +1662135922165419008 +1662135922207419904 +1662135922249420800 +1662135922300421888 +1662135922345422848 +1662135922390423808 +1662135922435424768 +1662135922480425728 +1662135922522426624 +1662135922567427584 +1662135922609428480 +1662135922654429440 +1662135922705430528 +1662135922750431488 +1662135922792432384 +1662135922840433408 +1662135922897434624 +1662135922942435584 +1662135922987436544 +1662135923029437440 +1662135923071438336 +1662135923113439232 +1662135923155440128 +1662135923203441152 +1662135923245442048 +1662135923284442880 +1662135923326443776 +1662135923365444608 +1662135923407445504 +1662135923449446400 +1662135923491447296 +1662135923533448192 +1662135923578449152 +1662135923620450048 +1662135923674451200 +1662135923716452096 +1662135923758452992 +1662135923800453888 +1662135923848454912 +1662135923890455808 +1662135923932456704 +1662135923983457792 +1662135924025458688 +1662135924079459840 +1662135924121460736 +1662135924163461632 +1662135924208462592 +1662135924268463872 +1662135924310464768 +1662135924355465728 +1662135924394466560 +1662135924436467456 +1662135924481468416 +1662135924532469504 +1662135924577470464 +1662135924616471296 +1662135924667472384 +1662135924709473280 +1662135924751474176 +1662135924793475072 +1662135924835475968 +1662135924883476992 +1662135924925477888 +1662135924973478912 +1662135925015479808 +1662135925057480704 +1662135925099481600 +1662135925147482624 +1662135925186483456 +1662135925228484352 +1662135925273485312 +1662135925315486208 +1662135925360487168 +1662135925408488192 +1662135925453489152 +1662135925495490048 +1662135925540491008 +1662135925582491904 +1662135925624492800 +1662135925663493632 +1662135925708494592 +1662135925750495488 +1662135925798496512 +1662135925846497536 +1662135925888498432 +1662135925930499328 +1662135925987500544 +1662135926035501568 +1662135926077502464 +1662135926122503424 +1662135926164504320 +1662135926209505280 +1662135926263506432 +1662135926311507456 +1662135926353508352 +1662135926401509376 +1662135926449510400 +1662135926488511232 +1662135926530512128 +1662135926578513152 +1662135926620514048 +1662135926665515008 +1662135926707515904 +1662135926749516800 +1662135926791517696 +1662135926833518592 +1662135926875519488 +1662135926914520320 +1662135926959521280 +1662135927001522176 +1662135927055523328 +1662135927097524224 +1662135927148525312 +1662135927199526400 +1662135927238527232 +1662135927280528128 +1662135927322529024 +1662135927367529984 +1662135927406530816 +1662135927445531648 +1662135927487532544 +1662135927538533632 +1662135927580534528 +1662135927622535424 +1662135927664536320 +1662135927709537280 +1662135927760538368 +1662135927802539264 +1662135927850540288 +1662135927892541184 +1662135927937542144 +1662135927988543232 +1662135928030544128 +1662135928075545088 +1662135928120546048 +1662135928162546944 +1662135928207547904 +1662135928255548928 +1662135928303549952 +1662135928345550848 +1662135928393551872 +1662135928435552768 +1662135928477553664 +1662135928519554560 +1662135928561555456 +1662135928603556352 +1662135928645557248 +1662135928687558144 +1662135928729559040 +1662135928774560000 +1662135928822561024 +1662135928864561920 +1662135928912562944 +1662135928954563840 +1662135929002564864 +1662135929041565696 +1662135929083566592 +1662135929125567488 +1662135929167568384 +1662135929212569344 +1662135929257570304 +1662135929299571200 +1662135929341572096 +1662135929386573056 +1662135929428573952 +1662135929467574784 +1662135929512575744 +1662135929566576896 +1662135929608577792 +1662135929659578880 +1662135929707579904 +1662135929749580800 +1662135929800581888 +1662135929842582784 +1662135929884583680 +1662135929926584576 +1662135929968585472 +1662135930010586368 +1662135930061587456 +1662135930103588352 +1662135930154589440 +1662135930199590400 +1662135930241591296 +1662135930283592192 +1662135930328593152 +1662135930367593984 +1662135930415595008 +1662135930460595968 +1662135930511597056 +1662135930553597952 +1662135930598598912 +1662135930640599808 +1662135930685600768 +1662135930730601728 +1662135930778602752 +1662135930820603648 +1662135930865604608 +1662135930907605504 +1662135930952606464 +1662135930997607424 +1662135931039608320 +1662135931081609216 +1662135931135610368 +1662135931180611328 +1662135931222612224 +1662135931270613248 +1662135931321614336 +1662135931372615424 +1662135931420616448 +1662135931465617408 +1662135931507618304 +1662135931549619200 +1662135931591620096 +1662135931639621120 +1662135931684622080 +1662135931726622976 +1662135931774624000 +1662135931819624960 +1662135931870626048 +1662135931912626944 +1662135931960627968 +1662135932002628864 +1662135932065630208 +1662135932107631104 +1662135932149632000 +1662135932209633280 +1662135932254634240 +1662135932299635200 +1662135932350636288 +1662135932392637184 +1662135932434638080 +1662135932482639104 +1662135932524640000 +1662135932566640896 +1662135932608641792 +1662135932650642688 +1662135932695643648 +1662135932743644672 +1662135932785645568 +1662135932830646528 +1662135932875647488 +1662135932917648384 +1662135932959649280 +1662135933004650240 +1662135933049651200 +1662135933091652096 +1662135933133652992 +1662135933178653952 +1662135933223654912 +1662135933268655872 +1662135933310656768 +1662135933358657792 +1662135933403658752 +1662135933454659840 +1662135933499660800 +1662135933541661696 +1662135933589662720 +1662135933631663616 +1662135933679664640 +1662135933718665472 +1662135933757666304 +1662135933802667264 +1662135933853668352 +1662135933898669312 +1662135933940670208 +1662135933979671040 +1662135934024672000 +1662135934066672896 +1662135934111673856 +1662135934156674816 +1662135934210675968 +1662135934255676928 +1662135934297677824 +1662135934345678848 +1662135934387679744 +1662135934429680640 +1662135934468681472 +1662135934513682432 +1662135934555683328 +1662135934600684288 +1662135934642685184 +1662135934684686080 +1662135934729687040 +1662135934771687936 +1662135934816688896 +1662135934858689792 +1662135934900690688 +1662135934942691584 +1662135934990692608 +1662135935032693504 +1662135935077694464 +1662135935119695360 +1662135935158696192 +1662135935209697280 +1662135935251698176 +1662135935293699072 +1662135935344700160 +1662135935389701120 +1662135935431702016 +1662135935482703104 +1662135935524704000 +1662135935572705024 +1662135935620706048 +1662135935668707072 +1662135935713708032 +1662135935758708992 +1662135935803709952 +1662135935845710848 +1662135935887711744 +1662135935932712704 +1662135935974713600 +1662135936019714560 +1662135936067715584 +1662135936106716416 +1662135936154717440 +1662135936196718336 +1662135936235719168 +1662135936277720064 +1662135936325721088 +1662135936367721984 +1662135936415723008 +1662135936457723904 +1662135936499724800 +1662135936544725760 +1662135936592726784 +1662135936631727616 +1662135936679728640 +1662135936727729664 +1662135936772730624 +1662135936814731520 +1662135936856732416 +1662135936907733504 +1662135936949734400 +1662135936997735424 +1662135937045736448 +1662135937093737472 +1662135937135738368 +1662135937180739328 +1662135937222740224 +1662135937267741184 +1662135937306742016 +1662135937351742976 +1662135937396743936 +1662135937435744768 +1662135937477745664 +1662135937522746624 +1662135937567747584 +1662135937609748480 +1662135937660749568 +1662135937705750528 +1662135937756751616 +1662135937804752640 +1662135937846753536 +1662135937903754752 +1662135937942755584 +1662135937984756480 +1662135938032757504 +1662135938071758336 +1662135938119759360 +1662135938161760256 +1662135938212761344 +1662135938254762240 +1662135938308763392 +1662135938350764288 +1662135938395765248 +1662135938452766464 +1662135938500767488 +1662135938539768320 +1662135938584769280 +1662135938629770240 +1662135938671771136 +1662135938716772096 +1662135938764773120 +1662135938815774208 +1662135938863775232 +1662135938905776128 +1662135938953777152 +1662135939001778176 +1662135939043779072 +1662135939094780160 +1662135939142781184 +1662135939187782144 +1662135939235783168 +1662135939274784000 +1662135939322785024 +1662135939367785984 +1662135939409786880 +1662135939460787968 +1662135939502788864 +1662135939541789696 +1662135939592790784 +1662135939637791744 +1662135939688792832 +1662135939736793856 +1662135939778794752 +1662135939820795648 +1662135939865796608 +1662135939919797760 +1662135939961798656 +1662135940006799616 +1662135940045800448 +1662135940093801472 +1662135940135802368 +1662135940180803328 +1662135940228804352 +1662135940282805504 +1662135940327806464 +1662135940372807424 +1662135940426808576 +1662135940468809472 +1662135940510810368 +1662135940552811264 +1662135940603812352 +1662135940642813184 +1662135940681814016 +1662135940723814912 +1662135940765815808 +1662135940807816704 +1662135940849817600 +1662135940888818432 +1662135940930819328 +1662135940978820352 +1662135941023821312 +1662135941065822208 +1662135941107823104 +1662135941149824000 +1662135941188824832 +1662135941233825792 +1662135941281826816 +1662135941323827712 +1662135941365828608 +1662135941413829632 +1662135941455830528 +1662135941500831488 +1662135941542832384 +1662135941581833216 +1662135941623834112 +1662135941665835008 +1662135941707835904 +1662135941746836736 +1662135941791837696 +1662135941833838592 +1662135941878839552 +1662135941929840640 +1662135941977841664 +1662135942025842688 +1662135942061843456 +1662135942103844352 +1662135942145845248 +1662135942199846400 +1662135942247847424 +1662135942292848384 +1662135942334849280 +1662135942388850432 +1662135942433851392 +1662135942478852352 +1662135942520853248 +1662135942562854144 +1662135942613855232 +1662135942658856192 +1662135942700857088 +1662135942751858176 +1662135942793859072 +1662135942835859968 +1662135942883860992 +1662135942925861888 +1662135942967862784 +1662135943006863616 +1662135943048864512 +1662135943093865472 +1662135943138866432 +1662135943186867456 +1662135943234868480 +1662135943276869376 +1662135943321870336 +1662135943369871360 +1662135943408872192 +1662135943456873216 +1662135943501874176 +1662135943543875072 +1662135943582875904 +1662135943627876864 +1662135943669877760 +1662135943720878848 +1662135943762879744 +1662135943804880640 +1662135943849881600 +1662135943894882560 +1662135943945883648 +1662135943996884736 +1662135944038885632 +1662135944083886592 +1662135944134887680 +1662135944182888704 +1662135944224889600 +1662135944275890688 +1662135944317891584 +1662135944362892544 +1662135944410893568 +1662135944452894464 +1662135944497895424 +1662135944551896576 +1662135944593897472 +1662135944635898368 +1662135944680899328 +1662135944731900416 +1662135944776901376 +1662135944824902400 +1662135944878903552 +1662135944923904512 +1662135944965905408 +1662135945010906368 +1662135945058907392 +1662135945100908288 +1662135945142909184 +1662135945190910208 +1662135945235911168 +1662135945289912320 +1662135945331913216 +1662135945376914176 +1662135945421915136 +1662135945466916096 +1662135945508916992 +1662135945550917888 +1662135945595918848 +1662135945634919680 +1662135945679920640 +1662135945727921664 +1662135945775922688 +1662135945817923584 +1662135945862924544 +1662135945904925440 +1662135945949926400 +1662135945991927296 +1662135946036928256 +1662135946081929216 +1662135946123930112 +1662135946165931008 +1662135946216932096 +1662135946261933056 +1662135946306934016 +1662135946351934976 +1662135946393935872 +1662135946438936832 +1662135946477937664 +1662135946519938560 +1662135946564939520 +1662135946609940480 +1662135946651941376 +1662135946690942208 +1662135946735943168 +1662135946783944192 +1662135946825945088 +1662135946867945984 +1662135946918947072 +1662135946963948032 +1662135947005948928 +1662135947047949824 +1662135947095950848 +1662135947134951680 +1662135947188952832 +1662135947236953856 +1662135947278954752 +1662135947320955648 +1662135947368956672 +1662135947410957568 +1662135947452958464 +1662135947494959360 +1662135947539960320 +1662135947578961152 +1662135947623962112 +1662135947665963008 +1662135947716964096 +1662135947758964992 +1662135947800965888 +1662135947842966784 +1662135947890967808 +1662135947941968896 +1662135947989969920 +1662135948031970816 +1662135948079971840 +1662135948121972736 +1662135948163973632 +1662135948211974656 +1662135948253975552 +1662135948292976384 +1662135948337977344 +1662135948382978304 +1662135948430979328 +1662135948472980224 +1662135948514981120 +1662135948553981952 +1662135948595982848 +1662135948637983744 +1662135948685984768 +1662135948730985728 +1662135948772986624 +1662135948814987520 +1662135948856988416 +1662135948895989248 +1662135948937990144 +1662135948982991104 +1662135949033992192 +1662135949078993152 +1662135949120994048 +1662135949174995200 +1662135949216996096 +1662135949261997056 +1662135949306998016 +1662135949348998912 +1662135949393999872 +1662135949439000832 +1662135949481001728 +1662135949529002752 +1662135949568003584 +1662135949616004608 +1662135949667005696 +1662135949709006592 +1662135949754007552 +1662135949796008448 +1662135949838009344 +1662135949886010368 +1662135949928011264 +1662135949970012160 +1662135950012013056 +1662135950057014016 +1662135950099014912 +1662135950144015872 +1662135950186016768 +1662135950240017920 +1662135950285018880 +1662135950327019776 +1662135950375020800 +1662135950417021696 +1662135950468022784 +1662135950510023680 +1662135950558024704 +1662135950600025600 +1662135950642026496 +1662135950690027520 +1662135950735028480 +1662135950777029376 +1662135950822030336 +1662135950870031360 +1662135950918032384 +1662135950960033280 +1662135951002034176 +1662135951047035136 +1662135951089036032 +1662135951146037248 +1662135951188038144 +1662135951230039040 +1662135951272039936 +1662135951317040896 +1662135951368041984 +1662135951413042944 +1662135951455043840 +1662135951494044672 +1662135951545045760 +1662135951587046656 +1662135951632047616 +1662135951674048512 +1662135951722049536 +1662135951770050560 +1662135951815051520 +1662135951860052480 +1662135951902053376 +1662135951944054272 +1662135951986055168 +1662135952028056064 +1662135952067056896 +1662135952112057856 +1662135952154058752 +1662135952196059648 +1662135952238060544 +1662135952280061440 +1662135952337062656 +1662135952379063552 +1662135952424064512 +1662135952466065408 +1662135952517066496 +1662135952559067392 +1662135952616068608 +1662135952661069568 +1662135952709070592 +1662135952763071744 +1662135952808072704 +1662135952850073600 +1662135952895074560 +1662135952937075456 +1662135952982076416 +1662135953033077504 +1662135953075078400 +1662135953117079296 +1662135953159080192 +1662135953201081088 +1662135953243081984 +1662135953291083008 +1662135953333083904 +1662135953384084992 +1662135953426085888 +1662135953471086848 +1662135953513087744 +1662135953555088640 +1662135953603089664 +1662135953651090688 +1662135953693091584 +1662135953741092608 +1662135953786093568 +1662135953828094464 +1662135953870095360 +1662135953912096256 +1662135953957097216 +1662135953999098112 +1662135954044099072 +1662135954092100096 +1662135954134100992 +1662135954176101888 +1662135954218102784 +1662135954260103680 +1662135954308104704 +1662135954353105664 +1662135954392106496 +1662135954431107328 +1662135954479108352 +1662135954518109184 +1662135954566110208 +1662135954611111168 +1662135954656112128 +1662135954704113152 +1662135954746114048 +1662135954791115008 +1662135954833115904 +1662135954878116864 +1662135954923117824 +1662135954965118720 +1662135955016119808 +1662135955058120704 +1662135955097121536 +1662135955136122368 +1662135955178123264 +1662135955217124096 +1662135955259124992 +1662135955304125952 +1662135955346126848 +1662135955391127808 +1662135955436128768 +1662135955487129856 +1662135955526130688 +1662135955568131584 +1662135955610132480 +1662135955655133440 +1662135955697134336 +1662135955739135232 +1662135955781136128 +1662135955826137088 +1662135955868137984 +1662135955913138944 +1662135955964140032 +1662135956009140992 +1662135956057142016 +1662135956105143040 +1662135956153144064 +1662135956195144960 +1662135956240145920 +1662135956288146944 +1662135956336147968 +1662135956381148928 +1662135956426149888 +1662135956468150784 +1662135956513151744 +1662135956555152640 +1662135956600153600 +1662135956648154624 +1662135956690155520 +1662135956732156416 +1662135956774157312 +1662135956828158464 +1662135956876159488 +1662135956921160448 +1662135956963161344 +1662135957008162304 +1662135957056163328 +1662135957104164352 +1662135957146165248 +1662135957188166144 +1662135957230167040 +1662135957266167808 +1662135957308168704 +1662135957350169600 +1662135957392170496 +1662135957437171456 +1662135957479172352 +1662135957521173248 +1662135957566174208 +1662135957608175104 +1662135957650176000 +1662135957695176960 +1662135957734177792 +1662135957785178880 +1662135957827179776 +1662135957869180672 +1662135957911181568 +1662135957956182528 +1662135958001183488 +1662135958046184448 +1662135958088185344 +1662135958130186240 +1662135958175187200 +1662135958226188288 +1662135958268189184 +1662135958310190080 +1662135958352190976 +1662135958394191872 +1662135958445192960 +1662135958487193856 +1662135958529194752 +1662135958565195520 +1662135958610196480 +1662135958652197376 +1662135958694198272 +1662135958739199232 +1662135958781200128 +1662135958826201088 +1662135958868201984 +1662135958910202880 +1662135958952203776 +1662135958994204672 +1662135959039205632 +1662135959084206592 +1662135959129207552 +1662135959174208512 +1662135959216209408 +1662135959261210368 +1662135959306211328 +1662135959351212288 +1662135959396213248 +1662135959438214144 +1662135959483215104 +1662135959531216128 +1662135959573217024 +1662135959615217920 +1662135959654218752 +1662135959696219648 +1662135959738220544 +1662135959780221440 +1662135959825222400 +1662135959870223360 +1662135959909224192 +1662135959951225088 +1662135959999226112 +1662135960041227008 +1662135960083227904 +1662135960125228800 +1662135960167229696 +1662135960218230784 +1662135960260231680 +1662135960299232512 +1662135960347233536 +1662135960392234496 +1662135960440235520 +1662135960485236480 +1662135960539237632 +1662135960584238592 +1662135960635239680 +1662135960680240640 +1662135960725241600 +1662135960776242688 +1662135960818243584 +1662135960863244544 +1662135960908245504 +1662135960950246400 +1662135961001247488 +1662135961043248384 +1662135961085249280 +1662135961127250176 +1662135961178251264 +1662135961220252160 +1662135961265253120 +1662135961307254016 +1662135961352254976 +1662135961400256000 +1662135961448257024 +1662135961490257920 +1662135961535258880 +1662135961580259840 +1662135961619260672 +1662135961658261504 +1662135961700262400 +1662135961742263296 +1662135961784264192 +1662135961826265088 +1662135961868265984 +1662135961907266816 +1662135961949267712 +1662135961991268608 +1662135962039269632 +1662135962081270528 +1662135962123271424 +1662135962165272320 +1662135962210273280 +1662135962252274176 +1662135962303275264 +1662135962345276160 +1662135962387277056 +1662135962432278016 +1662135962477278976 +1662135962528280064 +1662135962570280960 +1662135962615281920 +1662135962657282816 +1662135962699283712 +1662135962741284608 +1662135962792285696 +1662135962837286656 +1662135962882287616 +1662135962924288512 +1662135962972289536 +1662135963014290432 +1662135963065291520 +1662135963113292544 +1662135963164293632 +1662135963212294656 +1662135963254295552 +1662135963299296512 +1662135963341297408 +1662135963386298368 +1662135963425299200 +1662135963467300096 +1662135963512301056 +1662135963554301952 +1662135963596302848 +1662135963644303872 +1662135963686304768 +1662135963728305664 +1662135963773306624 +1662135963815307520 +1662135963857308416 +1662135963902309376 +1662135963947310336 +1662135963995311360 +1662135964040312320 +1662135964088313344 +1662135964139314432 +1662135964181315328 +1662135964223316224 +1662135964271317248 +1662135964313318144 +1662135964358319104 +1662135964406320128 +1662135964445320960 +1662135964487321856 +1662135964532322816 +1662135964574323712 +1662135964619324672 +1662135964667325696 +1662135964709326592 +1662135964754327552 +1662135964796328448 +1662135964835329280 +1662135964883330304 +1662135964928331264 +1662135964970332160 +1662135965012333056 +1662135965057334016 +1662135965108335104 +1662135965144335872 +1662135965186336768 +1662135965234337792 +1662135965276338688 +1662135965327339776 +1662135965369340672 +1662135965414341632 +1662135965459342592 +1662135965507343616 +1662135965549344512 +1662135965591345408 +1662135965633346304 +1662135965678347264 +1662135965720348160 +1662135965765349120 +1662135965810350080 +1662135965852350976 +1662135965894351872 +1662135965933352704 +1662135965972353536 +1662135966017354496 +1662135966065355520 +1662135966107356416 +1662135966152357376 +1662135966191358208 +1662135966239359232 +1662135966284360192 +1662135966329361152 +1662135966371362048 +1662135966419363072 +1662135966464364032 +1662135966512365056 +1662135966551365888 +1662135966596366848 +1662135966638367744 +1662135966680368640 +1662135966719369472 +1662135966761370368 +1662135966803371264 +1662135966848372224 +1662135966890373120 +1662135966932374016 +1662135966974374912 +1662135967025376000 +1662135967067376896 +1662135967115377920 +1662135967160378880 +1662135967202379776 +1662135967250380800 +1662135967295381760 +1662135967340382720 +1662135967382383616 +1662135967424384512 +1662135967466385408 +1662135967505386240 +1662135967550387200 +1662135967592388096 +1662135967646389248 +1662135967685390080 +1662135967733391104 +1662135967775392000 +1662135967817392896 +1662135967874394112 +1662135967919395072 +1662135967961395968 +1662135968012397056 +1662135968054397952 +1662135968096398848 +1662135968141399808 +1662135968186400768 +1662135968225401600 +1662135968264402432 +1662135968312403456 +1662135968360404480 +1662135968402405376 +1662135968447406336 +1662135968492407296 +1662135968534408192 +1662135968582409216 +1662135968624410112 +1662135968666411008 +1662135968708411904 +1662135968747412736 +1662135968789413632 +1662135968834414592 +1662135968879415552 +1662135968921416448 +1662135968963417344 +1662135969008418304 +1662135969050419200 +1662135969092420096 +1662135969137421056 +1662135969182422016 +1662135969227422976 +1662135969269423872 +1662135969311424768 +1662135969356425728 +1662135969404426752 +1662135969452427776 +1662135969497428736 +1662135969548429824 +1662135969596430848 +1662135969641431808 +1662135969695432960 +1662135969740433920 +1662135969779434752 +1662135969821435648 +1662135969863436544 +1662135969908437504 +1662135969953438464 +1662135970004439552 +1662135970043440384 +1662135970088441344 +1662135970130442240 +1662135970178443264 +1662135970223444224 +1662135970265445120 +1662135970307446016 +1662135970358447104 +1662135970400448000 +1662135970445448960 +1662135970487449856 +1662135970526450688 +1662135970565451520 +1662135970607452416 +1662135970649453312 +1662135970691454208 +1662135970736455168 +1662135970781456128 +1662135970829457152 +1662135970871458048 +1662135970913458944 +1662135970958459904 +1662135971006460928 +1662135971063462144 +1662135971105463040 +1662135971150464000 +1662135971198465024 +1662135971240465920 +1662135971285466880 +1662135971336467968 +1662135971381468928 +1662135971426469888 +1662135971468470784 +1662135971510471680 +1662135971552472576 +1662135971600473600 +1662135971642474496 +1662135971690475520 +1662135971741476608 +1662135971786477568 +1662135971831478528 +1662135971876479488 +1662135971918480384 +1662135971960481280 +1662135972014482432 +1662135972068483584 +1662135972116484608 +1662135972164485632 +1662135972209486592 +1662135972254487552 +1662135972296488448 +1662135972344489472 +1662135972395490560 +1662135972443491584 +1662135972488492544 +1662135972533493504 +1662135972575494400 +1662135972620495360 +1662135972662496256 +1662135972704497152 +1662135972749498112 +1662135972797499136 +1662135972842500096 +1662135972887501056 +1662135972926501888 +1662135972974502912 +1662135973016503808 +1662135973070504960 +1662135973115505920 +1662135973160506880 +1662135973205507840 +1662135973262509056 +1662135973304509952 +1662135973346510848 +1662135973391511808 +1662135973433512704 +1662135973472513536 +1662135973514514432 +1662135973556515328 +1662135973598516224 +1662135973649517312 +1662135973700518400 +1662135973748519424 +1662135973793520384 +1662135973835521280 +1662135973883522304 +1662135973928523264 +1662135973976524288 +1662135974018525184 +1662135974060526080 +1662135974108527104 +1662135974150528000 +1662135974192528896 +1662135974237529856 +1662135974282530816 +1662135974324531712 +1662135974369532672 +1662135974411533568 +1662135974456534528 +1662135974501535488 +1662135974543536384 +1662135974585537280 +1662135974627538176 +1662135974681539328 +1662135974729540352 +1662135974771541248 +1662135974813542144 +1662135974858543104 +1662135974906544128 +1662135974945544960 +1662135974987545856 +1662135975035546880 +1662135975083547904 +1662135975134548992 +1662135975176549888 +1662135975218550784 +1662135975263551744 +1662135975311552768 +1662135975359553792 +1662135975401554688 +1662135975452555776 +1662135975494556672 +1662135975542557696 +1662135975587558656 +1662135975632559616 +1662135975677560576 +1662135975725561600 +1662135975767562496 +1662135975818563584 +1662135975866564608 +1662135975908565504 +1662135975950566400 +1662135975995567360 +1662135976040568320 +1662135976085569280 +1662135976127570176 +1662135976169571072 +1662135976211571968 +1662135976256572928 +1662135976295573760 +1662135976340574720 +1662135976385575680 +1662135976430576640 +1662135976472577536 +1662135976520578560 +1662135976559579392 +1662135976607580416 +1662135976649581312 +1662135976697582336 +1662135976745583360 +1662135976787584256 +1662135976829585152 +1662135976871586048 +1662135976913586944 +1662135976955587840 +1662135977006588928 +1662135977048589824 +1662135977093590784 +1662135977138591744 +1662135977183592704 +1662135977228593664 +1662135977276594688 +1662135977318595584 +1662135977360596480 +1662135977405597440 +1662135977453598464 +1662135977495599360 +1662135977540600320 +1662135977582601216 +1662135977624602112 +1662135977681603328 +1662135977723604224 +1662135977765605120 +1662135977810606080 +1662135977858607104 +1662135977900608000 +1662135977945608960 +1662135977996610048 +1662135978041611008 +1662135978086611968 +1662135978131612928 +1662135978173613824 +1662135978212614656 +1662135978257615616 +1662135978299616512 +1662135978341617408 +1662135978383618304 +1662135978425619200 +1662135978470620160 +1662135978509620992 +1662135978563622144 +1662135978608623104 +1662135978650624000 +1662135978698625024 +1662135978737625856 +1662135978785626880 +1662135978824627712 +1662135978869628672 +1662135978911629568 +1662135978956630528 +1662135978998631424 +1662135979043632384 +1662135979091633408 +1662135979133634304 +1662135979175635200 +1662135979220636160 +1662135979262637056 +1662135979304637952 +1662135979346638848 +1662135979388639744 +1662135979439640832 +1662135979484641792 +1662135979529642752 +1662135979571643648 +1662135979613644544 +1662135979658645504 +1662135979700646400 +1662135979742647296 +1662135979784648192 +1662135979829649152 +1662135979877650176 +1662135979919651072 +1662135979964652032 +1662135980009652992 +1662135980054653952 +1662135980105655040 +1662135980147655936 +1662135980189656832 +1662135980234657792 +1662135980276658688 +1662135980318659584 +1662135980363660544 +1662135980408661504 +1662135980465662720 +1662135980507663616 +1662135980549664512 +1662135980606665728 +1662135980651666688 +1662135980696667648 +1662135980738668544 +1662135980780669440 +1662135980822670336 +1662135980867671296 +1662135980909672192 +1662135980954673152 +1662135980996674048 +1662135981041675008 +1662135981083675904 +1662135981131676928 +1662135981179677952 +1662135981221678848 +1662135981293680384 +1662135981335681280 +1662135981383682304 +1662135981425683200 +1662135981470684160 +1662135981515685120 +1662135981560686080 +1662135981608687104 +1662135981659688192 +1662135981701689088 +1662135981740689920 +1662135981782690816 +1662135981824691712 +1662135981869692672 +1662135981920693760 +1662135981965694720 +1662135982016695808 +1662135982058696704 +1662135982100697600 +1662135982142698496 +1662135982184699392 +1662135982226700288 +1662135982271701248 +1662135982319702272 +1662135982361703168 +1662135982400704000 +1662135982442704896 +1662135982490705920 +1662135982541707008 +1662135982583707904 +1662135982625708800 +1662135982667709696 +1662135982715710720 +1662135982757711616 +1662135982796712448 +1662135982841713408 +1662135982883714304 +1662135982922715136 +1662135982967716096 +1662135983009716992 +1662135983048717824 +1662135983093718784 +1662135983135719680 +1662135983183720704 +1662135983228721664 +1662135983270722560 +1662135983321723648 +1662135983366724608 +1662135983408725504 +1662135983456726528 +1662135983501727488 +1662135983549728512 +1662135983594729472 +1662135983642730496 +1662135983687731456 +1662135983729732352 +1662135983771733248 +1662135983819734272 +1662135983864735232 +1662135983909736192 +1662135983954737152 +1662135983999738112 +1662135984041739008 +1662135984083739904 +1662135984125740800 +1662135984179741952 +1662135984224742912 +1662135984269743872 +1662135984317744896 +1662135984362745856 +1662135984404746752 +1662135984446747648 +1662135984491748608 +1662135984533749504 +1662135984572750336 +1662135984614751232 +1662135984656752128 +1662135984701753088 +1662135984743753984 +1662135984782754816 +1662135984833755904 +1662135984884756992 +1662135984929757952 +1662135984980759040 +1662135985031760128 +1662135985076761088 +1662135985115761920 +1662135985166763008 +1662135985217764096 +1662135985265765120 +1662135985304765952 +1662135985346766848 +1662135985388767744 +1662135985427768576 +1662135985469769472 +1662135985508770304 +1662135985547771136 +1662135985589772032 +1662135985634772992 +1662135985676773888 +1662135985721774848 +1662135985769775872 +1662135985817776896 +1662135985865777920 +1662135985907778816 +1662135985955779840 +1662135986003780864 +1662135986051781888 +1662135986096782848 +1662135986141783808 +1662135986186784768 +1662135986234785792 +1662135986279786752 +1662135986321787648 +1662135986363788544 +1662135986414789632 +1662135986462790656 +1662135986501791488 +1662135986546792448 +1662135986591793408 +1662135986636794368 +1662135986687795456 +1662135986729796352 +1662135986780797440 +1662135986828798464 +1662135986876799488 +1662135986918800384 +1662135986963801344 +1662135987014802432 +1662135987059803392 +1662135987107804416 +1662135987152805376 +1662135987197806336 +1662135987245807360 +1662135987290808320 +1662135987332809216 +1662135987374810112 +1662135987416811008 +1662135987461811968 +1662135987500812800 +1662135987542813696 +1662135987584814592 +1662135987632815616 +1662135987674816512 +1662135987716817408 +1662135987758818304 +1662135987803819264 +1662135987845820160 +1662135987890821120 +1662135987935822080 +1662135987980823040 +1662135988022823936 +1662135988067824896 +1662135988112825856 +1662135988154826752 +1662135988196827648 +1662135988235828480 +1662135988277829376 +1662135988319830272 +1662135988361831168 +1662135988406832128 +1662135988448833024 +1662135988493833984 +1662135988535834880 +1662135988583835904 +1662135988625836800 +1662135988670837760 +1662135988715838720 +1662135988760839680 +1662135988799840512 +1662135988838841344 +1662135988880842240 +1662135988919843072 +1662135988961843968 +1662135989003844864 +1662135989042845696 +1662135989084846592 +1662135989129847552 +1662135989171848448 +1662135989210849280 +1662135989258850304 +1662135989300851200 +1662135989342852096 +1662135989384852992 +1662135989429853952 +1662135989468854784 +1662135989510855680 +1662135989552856576 +1662135989594857472 +1662135989639858432 +1662135989681859328 +1662135989723860224 +1662135989765861120 +1662135989807862016 +1662135989852862976 +1662135989897863936 +1662135989942864896 +1662135989984865792 +1662135990029866752 +1662135990065867520 +1662135990113868544 +1662135990161869568 +1662135990203870464 +1662135990245871360 +1662135990287872256 +1662135990329873152 +1662135990374874112 +1662135990422875136 +1662135990464876032 +1662135990509876992 +1662135990551877888 +1662135990605879040 +1662135990650880000 +1662135990695880960 +1662135990743881984 +1662135990785882880 +1662135990836883968 +1662135990884884992 +1662135990935886080 +1662135990980887040 +1662135991025888000 +1662135991067888896 +1662135991109889792 +1662135991151890688 +1662135991199891712 +1662135991238892544 +1662135991283893504 +1662135991328894464 +1662135991370895360 +1662135991415896320 +1662135991457897216 +1662135991502898176 +1662135991544899072 +1662135991586899968 +1662135991628900864 +1662135991670901760 +1662135991712902656 +1662135991760903680 +1662135991802904576 +1662135991844905472 +1662135991889906432 +1662135991931907328 +1662135991979908352 +1662135992021909248 +1662135992075910400 +1662135992114911232 +1662135992156912128 +1662135992195912960 +1662135992240913920 +1662135992282914816 +1662135992330915840 +1662135992378916864 +1662135992417917696 +1662135992462918656 +1662135992510919680 +1662135992552920576 +1662135992603921664 +1662135992645922560 +1662135992687923456 +1662135992729924352 +1662135992771925248 +1662135992813926144 +1662135992855927040 +1662135992909928192 +1662135992951929088 +1662135992990929920 +1662135993032930816 +1662135993083931904 +1662135993128932864 +1662135993182934016 +1662135993224934912 +1662135993281936128 +1662135993329937152 +1662135993371938048 +1662135993413938944 +1662135993458939904 +1662135993503940864 +1662135993545941760 +1662135993590942720 +1662135993632943616 +1662135993677944576 +1662135993722945536 +1662135993761946368 +1662135993806947328 +1662135993851948288 +1662135993893949184 +1662135993935950080 +1662135993980951040 +1662135994025952000 +1662135994070952960 +1662135994112953856 +1662135994157954816 +1662135994202955776 +1662135994253956864 +1662135994298957824 +1662135994340958720 +1662135994382959616 +1662135994427960576 +1662135994469961472 +1662135994514962432 +1662135994565963520 +1662135994610964480 +1662135994655965440 +1662135994694966272 +1662135994739967232 +1662135994781968128 +1662135994838969344 +1662135994883970304 +1662135994931971328 +1662135994976972288 +1662135995018973184 +1662135995060974080 +1662135995111975168 +1662135995156976128 +1662135995201977088 +1662135995243977984 +1662135995291979008 +1662135995333979904 +1662135995381980928 +1662135995429981952 +1662135995480983040 +1662135995525984000 +1662135995573985024 +1662135995615985920 +1662135995672987136 +1662135995717988096 +1662135995777989376 +1662135995822990336 +1662135995864991232 +1662135995918992384 +1662135995960993280 +1662135995999994112 +1662135996044995072 +1662135996086995968 +1662135996128996864 +1662135996179997952 +1662135996224998912 +1662135996266999808 +1662135996315000832 +1662135996357001728 +1662135996402002688 +1662135996444003584 +1662135996489004544 +1662135996528005376 +1662135996579006464 +1662135996621007360 +1662135996666008320 +1662135996705009152 +1662135996747010048 +1662135996789010944 +1662135996837011968 +1662135996888013056 +1662135996939014144 +1662135996990015232 +1662135997038016256 +1662135997086017280 +1662135997128018176 +1662135997176019200 +1662135997218020096 +1662135997260020992 +1662135997305021952 +1662135997350022912 +1662135997398023936 +1662135997437024768 +1662135997479025664 +1662135997521026560 +1662135997572027648 +1662135997620028672 +1662135997659029504 +1662135997710030592 +1662135997752031488 +1662135997794032384 +1662135997836033280 +1662135997878034176 +1662135997920035072 +1662135997965036032 +1662135998007036928 +1662135998052037888 +1662135998097038848 +1662135998139039744 +1662135998184040704 +1662135998226041600 +1662135998271042560 +1662135998316043520 +1662135998361044480 +1662135998412045568 +1662135998457046528 +1662135998499047424 +1662135998550048512 +1662135998595049472 +1662135998640050432 +1662135998682051328 +1662135998727052288 +1662135998772053248 +1662135998820054272 +1662135998865055232 +1662135998907056128 +1662135998949057024 +1662135998997058048 +1662135999039058944 +1662135999081059840 +1662135999123060736 +1662135999168061696 +1662135999216062720 +1662135999264063744 +1662135999309064704 +1662135999360065792 +1662135999402066688 +1662135999447067648 +1662135999489068544 +1662135999528069376 +1662135999579070464 +1662135999630071552 +1662135999678072576 +1662135999720073472 +1662135999759074304 +1662135999804075264 +1662135999846076160 +1662135999894077184 +1662135999939078144 +1662135999981079040 +1662136000029080064 +1662136000077081088 +1662136000125082112 +1662136000173083136 +1662136000215084032 +1662136000257084928 +1662136000299085824 +1662136000341086720 +1662136000383087616 +1662136000425088512 +1662136000473089536 +1662136000518090496 +1662136000557091328 +1662136000605092352 +1662136000650093312 +1662136000701094400 +1662136000740095232 +1662136000782096128 +1662136000827097088 +1662136000869097984 +1662136000911098880 +1662136000953099776 +1662136000992100608 +1662136001034101504 +1662136001088102656 +1662136001130103552 +1662136001172104448 +1662136001217105408 +1662136001256106240 +1662136001307107328 +1662136001352108288 +1662136001400109312 +1662136001442110208 +1662136001490111232 +1662136001535112192 +1662136001580113152 +1662136001622114048 +1662136001670115072 +1662136001709115904 +1662136001751116800 +1662136001796117760 +1662136001841118720 +1662136001895119872 +1662136001946120960 +1662136001991121920 +1662136002042123008 +1662136002084123904 +1662136002132124928 +1662136002180125952 +1662136002222126848 +1662136002267127808 +1662136002306128640 +1662136002348129536 +1662136002396130560 +1662136002441131520 +1662136002495132672 +1662136002540133632 +1662136002585134592 +1662136002633135616 +1662136002678136576 +1662136002723137536 +1662136002768138496 +1662136002813139456 +1662136002852140288 +1662136002894141184 +1662136002939142144 +1662136002990143232 +1662136003041144320 +1662136003083145216 +1662136003128146176 +1662136003179147264 +1662136003239148544 +1662136003284149504 +1662136003323150336 +1662136003371151360 +1662136003416152320 +1662136003458153216 +1662136003503154176 +1662136003545155072 +1662136003590156032 +1662136003638157056 +1662136003680157952 +1662136003722158848 +1662136003761159680 +1662136003803160576 +1662136003848161536 +1662136003899162624 +1662136003941163520 +1662136003992164608 +1662136004034165504 +1662136004088166656 +1662136004139167744 +1662136004184168704 +1662136004229169664 +1662136004268170496 +1662136004313171456 +1662136004352172288 +1662136004400173312 +1662136004439174144 +1662136004484175104 +1662136004529176064 +1662136004571176960 +1662136004619177984 +1662136004658178816 +1662136004703179776 +1662136004748180736 +1662136004793181696 +1662136004835182592 +1662136004880183552 +1662136004928184576 +1662136004985185792 +1662136005030186752 +1662136005072187648 +1662136005120188672 +1662136005168189696 +1662136005213190656 +1662136005255191552 +1662136005297192448 +1662136005339193344 +1662136005381194240 +1662136005426195200 +1662136005465196032 +1662136005507196928 +1662136005552197888 +1662136005594198784 +1662136005639199744 +1662136005681200640 +1662136005729201664 +1662136005774202624 +1662136005816203520 +1662136005861204480 +1662136005903205376 +1662136005945206272 +1662136005984207104 +1662136006029208064 +1662136006080209152 +1662136006131210240 +1662136006185211392 +1662136006230212352 +1662136006272213248 +1662136006317214208 +1662136006359215104 +1662136006401216000 +1662136006452217088 +1662136006494217984 +1662136006539218944 +1662136006581219840 +1662136006632220928 +1662136006668221696 +1662136006713222656 +1662136006755223552 +1662136006800224512 +1662136006845225472 +1662136006887226368 +1662136006929227264 +1662136006971228160 +1662136007016229120 +1662136007067230208 +1662136007118231296 +1662136007160232192 +1662136007202233088 +1662136007244233984 +1662136007286234880 +1662136007328235776 +1662136007373236736 +1662136007421237760 +1662136007466238720 +1662136007517239808 +1662136007562240768 +1662136007604241664 +1662136007652242688 +1662136007697243648 +1662136007739244544 +1662136007781245440 +1662136007826246400 +1662136007868247296 +1662136007910248192 +1662136007952249088 +1662136008000250112 +1662136008042251008 +1662136008084251904 +1662136008126252800 +1662136008174253824 +1662136008216254720 +1662136008261255680 +1662136008303256576 +1662136008342257408 +1662136008384258304 +1662136008426259200 +1662136008468260096 +1662136008513261056 +1662136008561262080 +1662136008603262976 +1662136008648263936 +1662136008696264960 +1662136008741265920 +1662136008783266816 +1662136008831267840 +1662136008873268736 +1662136008918269696 +1662136008960270592 +1662136008999271424 +1662136009041272320 +1662136009089273344 +1662136009140274432 +1662136009182275328 +1662136009224276224 +1662136009266277120 +1662136009311278080 +1662136009356279040 +1662136009395279872 +1662136009440280832 +1662136009482281728 +1662136009527282688 +1662136009578283776 +1662136009617284608 +1662136009662285568 +1662136009704286464 +1662136009752287488 +1662136009797288448 +1662136009842289408 +1662136009884290304 +1662136009926291200 +1662136009974292224 +1662136010016293120 +1662136010061294080 +1662136010109295104 +1662136010154296064 +1662136010196296960 +1662136010235297792 +1662136010280298752 +1662136010322299648 +1662136010364300544 +1662136010409301504 +1662136010451302400 +1662136010499303424 +1662136010547304448 +1662136010592305408 +1662136010637306368 +1662136010676307200 +1662136010718308096 +1662136010760308992 +1662136010808310016 +1662136010850310912 +1662136010892311808 +1662136010934312704 +1662136010982313728 +1662136011027314688 +1662136011072315648 +1662136011114316544 +1662136011159317504 +1662136011201318400 +1662136011243319296 +1662136011285320192 +1662136011327321088 +1662136011372322048 +1662136011420323072 +1662136011462323968 +1662136011507324928 +1662136011549325824 +1662136011591326720 +1662136011633327616 +1662136011687328768 +1662136011732329728 +1662136011780330752 +1662136011822331648 +1662136011870332672 +1662136011918333696 +1662136011960334592 +1662136012002335488 +1662136012047336448 +1662136012092337408 +1662136012134338304 +1662136012176339200 +1662136012218340096 +1662136012260340992 +1662136012302341888 +1662136012350342912 +1662136012395343872 +1662136012437344768 +1662136012482345728 +1662136012527346688 +1662136012575347712 +1662136012614348544 +1662136012656349440 +1662136012701350400 +1662136012740351232 +1662136012782352128 +1662136012824353024 +1662136012866353920 +1662136012914354944 +1662136012959355904 +1662136013004356864 +1662136013046357760 +1662136013091358720 +1662136013136359680 +1662136013178360576 +1662136013223361536 +1662136013262362368 +1662136013307363328 +1662136013352364288 +1662136013394365184 +1662136013436366080 +1662136013481367040 +1662136013523367936 +1662136013565368832 +1662136013607369728 +1662136013652370688 +1662136013694371584 +1662136013736372480 +1662136013790373632 +1662136013832374528 +1662136013874375424 +1662136013916376320 +1662136013961377280 +1662136014006378240 +1662136014051379200 +1662136014096380160 +1662136014144381184 +1662136014189382144 +1662136014231383040 +1662136014276384000 +1662136014321384960 +1662136014369385984 +1662136014411386880 +1662136014453387776 +1662136014501388800 +1662136014543389696 +1662136014591390720 +1662136014630391552 +1662136014672392448 +1662136014717393408 +1662136014765394432 +1662136014807395328 +1662136014858396416 +1662136014903397376 +1662136014948398336 +1662136014996399360 +1662136015041400320 +1662136015086401280 +1662136015128402176 +1662136015170403072 +1662136015218404096 +1662136015263405056 +1662136015305405952 +1662136015347406848 +1662136015404408064 +1662136015449409024 +1662136015500410112 +1662136015545411072 +1662136015584411904 +1662136015629412864 +1662136015671413760 +1662136015716414720 +1662136015761415680 +1662136015806416640 +1662136015848417536 +1662136015893418496 +1662136015938419456 +1662136015986420480 +1662136016028421376 +1662136016076422400 +1662136016121423360 +1662136016163424256 +1662136016208425216 +1662136016253426176 +1662136016295427072 +1662136016340428032 +1662136016382428928 +1662136016427429888 +1662136016484431104 +1662136016529432064 +1662136016574433024 +1662136016625434112 +1662136016667435008 +1662136016715436032 +1662136016760436992 +1662136016808438016 +1662136016850438912 +1662136016892439808 +1662136016937440768 +1662136016985441792 +1662136017027442688 +1662136017075443712 +1662136017129444864 +1662136017174445824 +1662136017222446848 +1662136017264447744 +1662136017309448704 +1662136017351449600 +1662136017402450688 +1662136017441451520 +1662136017486452480 +1662136017534453504 +1662136017579454464 +1662136017624455424 +1662136017663456256 +1662136017708457216 +1662136017750458112 +1662136017792459008 +1662136017843460096 +1662136017882460928 +1662136017924461824 +1662136017966462720 +1662136018011463680 +1662136018056464640 +1662136018107465728 +1662136018152466688 +1662136018200467712 +1662136018248468736 +1662136018290469632 +1662136018332470528 +1662136018377471488 +1662136018425472512 +1662136018467473408 +1662136018509474304 +1662136018557475328 +1662136018605476352 +1662136018647477248 +1662136018689478144 +1662136018737479168 +1662136018791480320 +1662136018833481216 +1662136018878482176 +1662136018920483072 +1662136018962483968 +1662136019010484992 +1662136019052485888 +1662136019097486848 +1662136019136487680 +1662136019190488832 +1662136019232489728 diff --git a/Examples/Stereo/MIMIR_TimeStamps/OceanFloor_track1_light.txt b/Examples/Stereo/MIMIR_TimeStamps/OceanFloor_track1_light.txt new file mode 100644 index 0000000000..fc436ed12e --- /dev/null +++ b/Examples/Stereo/MIMIR_TimeStamps/OceanFloor_track1_light.txt @@ -0,0 +1,6263 @@ +1662129779504666880 +1662129779546667776 +1662129779588668672 +1662129779630669568 +1662129779675670528 +1662129779717671424 +1662129779762672384 +1662129779804673280 +1662129779849674240 +1662129779894675200 +1662129779936676096 +1662129779984677120 +1662129780026678016 +1662129780068678912 +1662129780110679808 +1662129780152680704 +1662129780194681600 +1662129780236682496 +1662129780278683392 +1662129780326684416 +1662129780368685312 +1662129780413686272 +1662129780455687168 +1662129780506688256 +1662129780548689152 +1662129780596690176 +1662129780641691136 +1662129780683692032 +1662129780728692992 +1662129780773693952 +1662129780815694848 +1662129780857695744 +1662129780911696896 +1662129780956697856 +1662129781001698816 +1662129781052699904 +1662129781097700864 +1662129781139701760 +1662129781181702656 +1662129781223703552 +1662129781268704512 +1662129781310705408 +1662129781358706432 +1662129781400707328 +1662129781442708224 +1662129781490709248 +1662129781532710144 +1662129781574711040 +1662129781616711936 +1662129781661712896 +1662129781703713792 +1662129781751714816 +1662129781796715776 +1662129781838716672 +1662129781883717632 +1662129781922718464 +1662129781970719488 +1662129782012720384 +1662129782054721280 +1662129782099722240 +1662129782141723136 +1662129782192724224 +1662129782234725120 +1662129782279726080 +1662129782324727040 +1662129782378728192 +1662129782423729152 +1662129782471730176 +1662129782513731072 +1662129782558732032 +1662129782600732928 +1662129782642733824 +1662129782687734784 +1662129782729735680 +1662129782777736704 +1662129782834737920 +1662129782876738816 +1662129782918739712 +1662129782966740736 +1662129783008741632 +1662129783053742592 +1662129783101743616 +1662129783143744512 +1662129783188745472 +1662129783233746432 +1662129783275747328 +1662129783323748352 +1662129783371749376 +1662129783410750208 +1662129783452751104 +1662129783497752064 +1662129783539752960 +1662129783584753920 +1662129783626754816 +1662129783668755712 +1662129783713756672 +1662129783761757696 +1662129783803758592 +1662129783845759488 +1662129783887760384 +1662129783932761344 +1662129783977762304 +1662129784019763200 +1662129784064764160 +1662129784106765056 +1662129784154766080 +1662129784199767040 +1662129784241767936 +1662129784292769024 +1662129784334769920 +1662129784382770944 +1662129784430771968 +1662129784472772864 +1662129784514773760 +1662129784562774784 +1662129784613775872 +1662129784655776768 +1662129784706777856 +1662129784751778816 +1662129784793779712 +1662129784838780672 +1662129784883781632 +1662129784931782656 +1662129784976783616 +1662129785018784512 +1662129785063785472 +1662129785111786496 +1662129785162787584 +1662129785210788608 +1662129785255789568 +1662129785300790528 +1662129785342791424 +1662129785387792384 +1662129785432793344 +1662129785483794432 +1662129785528795392 +1662129785576796416 +1662129785621797376 +1662129785666798336 +1662129785717799424 +1662129785762800384 +1662129785810801408 +1662129785852802304 +1662129785894803200 +1662129785936804096 +1662129785978804992 +1662129786026806016 +1662129786068806912 +1662129786113807872 +1662129786161808896 +1662129786209809920 +1662129786251810816 +1662129786296811776 +1662129786341812736 +1662129786386813696 +1662129786437814784 +1662129786485815808 +1662129786530816768 +1662129786584817920 +1662129786629818880 +1662129786671819776 +1662129786719820800 +1662129786761821696 +1662129786803822592 +1662129786845823488 +1662129786890824448 +1662129786929825280 +1662129786977826304 +1662129787025827328 +1662129787070828288 +1662129787115829248 +1662129787157830144 +1662129787205831168 +1662129787250832128 +1662129787295833088 +1662129787340834048 +1662129787388835072 +1662129787436836096 +1662129787481837056 +1662129787529838080 +1662129787574839040 +1662129787619840000 +1662129787658840832 +1662129787703841792 +1662129787748842752 +1662129787793843712 +1662129787841844736 +1662129787886845696 +1662129787931846656 +1662129787976847616 +1662129788021848576 +1662129788069849600 +1662129788111850496 +1662129788159851520 +1662129788201852416 +1662129788243853312 +1662129788288854272 +1662129788342855424 +1662129788390856448 +1662129788432857344 +1662129788480858368 +1662129788522859264 +1662129788567860224 +1662129788615861248 +1662129788660862208 +1662129788705863168 +1662129788747864064 +1662129788786864896 +1662129788831865856 +1662129788885867008 +1662129788933868032 +1662129788972868864 +1662129789020869888 +1662129789068870912 +1662129789110871808 +1662129789152872704 +1662129789197873664 +1662129789239874560 +1662129789287875584 +1662129789335876608 +1662129789377877504 +1662129789425878528 +1662129789467879424 +1662129789512880384 +1662129789563881472 +1662129789605882368 +1662129789647883264 +1662129789692884224 +1662129789737885184 +1662129789779886080 +1662129789821886976 +1662129789863887872 +1662129789908888832 +1662129789956889856 +1662129790001890816 +1662129790046891776 +1662129790085892608 +1662129790130893568 +1662129790175894528 +1662129790217895424 +1662129790259896320 +1662129790304897280 +1662129790352898304 +1662129790397899264 +1662129790442900224 +1662129790484901120 +1662129790526902016 +1662129790568902912 +1662129790610903808 +1662129790649904640 +1662129790691905536 +1662129790733906432 +1662129790775907328 +1662129790820908288 +1662129790862909184 +1662129790910910208 +1662129790949911040 +1662129790994912000 +1662129791033912832 +1662129791075913728 +1662129791120914688 +1662129791162915584 +1662129791207916544 +1662129791252917504 +1662129791294918400 +1662129791336919296 +1662129791378920192 +1662129791420921088 +1662129791465922048 +1662129791504922880 +1662129791549923840 +1662129791594924800 +1662129791636925696 +1662129791678926592 +1662129791720927488 +1662129791762928384 +1662129791804929280 +1662129791843930112 +1662129791888931072 +1662129791936932096 +1662129791981933056 +1662129792029934080 +1662129792077935104 +1662129792119936000 +1662129792155936768 +1662129792197937664 +1662129792245938688 +1662129792287939584 +1662129792338940672 +1662129792380941568 +1662129792425942528 +1662129792470943488 +1662129792512944384 +1662129792557945344 +1662129792599946240 +1662129792644947200 +1662129792683948032 +1662129792728948992 +1662129792773949952 +1662129792821950976 +1662129792866951936 +1662129792908952832 +1662129792959953920 +1662129793004954880 +1662129793049955840 +1662129793088956672 +1662129793133957632 +1662129793181958656 +1662129793223959552 +1662129793265960448 +1662129793313961472 +1662129793358962432 +1662129793409963520 +1662129793451964416 +1662129793496965376 +1662129793544966400 +1662129793586967296 +1662129793628968192 +1662129793670969088 +1662129793712969984 +1662129793754970880 +1662129793796971776 +1662129793841972736 +1662129793895973888 +1662129793937974784 +1662129793979975680 +1662129794027976704 +1662129794075977728 +1662129794117978624 +1662129794162979584 +1662129794207980544 +1662129794249981440 +1662129794291982336 +1662129794333983232 +1662129794375984128 +1662129794417985024 +1662129794459985920 +1662129794513987072 +1662129794555987968 +1662129794597988864 +1662129794639989760 +1662129794684990720 +1662129794732991744 +1662129794777992704 +1662129794822993664 +1662129794873994752 +1662129794915995648 +1662129794957996544 +1662129795002997504 +1662129795044998400 +1662129795083999232 +1662129795135000320 +1662129795177001216 +1662129795225002240 +1662129795267003136 +1662129795315004160 +1662129795366005248 +1662129795408006144 +1662129795456007168 +1662129795501008128 +1662129795543009024 +1662129795585009920 +1662129795624010752 +1662129795672011776 +1662129795717012736 +1662129795762013696 +1662129795804014592 +1662129795855015680 +1662129795903016704 +1662129795957017856 +1662129796008018944 +1662129796050019840 +1662129796098020864 +1662129796146021888 +1662129796191022848 +1662129796239023872 +1662129796284024832 +1662129796335025920 +1662129796380026880 +1662129796428027904 +1662129796470028800 +1662129796512029696 +1662129796557030656 +1662129796599031552 +1662129796641032448 +1662129796683033344 +1662129796725034240 +1662129796767035136 +1662129796812036096 +1662129796851036928 +1662129796896037888 +1662129796941038848 +1662129796992039936 +1662129797034040832 +1662129797076041728 +1662129797118042624 +1662129797163043584 +1662129797208044544 +1662129797253045504 +1662129797295046400 +1662129797337047296 +1662129797388048384 +1662129797430049280 +1662129797475050240 +1662129797526051328 +1662129797580052480 +1662129797628053504 +1662129797679054592 +1662129797718055424 +1662129797766056448 +1662129797814057472 +1662129797862058496 +1662129797907059456 +1662129797949060352 +1662129797991061248 +1662129798033062144 +1662129798075063040 +1662129798117063936 +1662129798162064896 +1662129798204065792 +1662129798246066688 +1662129798288067584 +1662129798333068544 +1662129798372069376 +1662129798420070400 +1662129798462071296 +1662129798504072192 +1662129798561073408 +1662129798609074432 +1662129798651075328 +1662129798690076160 +1662129798735077120 +1662129798777078016 +1662129798819078912 +1662129798870080000 +1662129798921081088 +1662129798966082048 +1662129799008082944 +1662129799053083904 +1662129799098084864 +1662129799140085760 +1662129799182086656 +1662129799230087680 +1662129799284088832 +1662129799329089792 +1662129799371090688 +1662129799428091904 +1662129799473092864 +1662129799515093760 +1662129799560094720 +1662129799605095680 +1662129799650096640 +1662129799692097536 +1662129799734098432 +1662129799776099328 +1662129799818100224 +1662129799863101184 +1662129799911102208 +1662129799956103168 +1662129800004104192 +1662129800046105088 +1662129800088105984 +1662129800133106944 +1662129800175107840 +1662129800223108864 +1662129800268109824 +1662129800319110912 +1662129800358111744 +1662129800400112640 +1662129800442113536 +1662129800493114624 +1662129800541115648 +1662129800589116672 +1662129800631117568 +1662129800676118528 +1662129800718119424 +1662129800772120576 +1662129800820121600 +1662129800862122496 +1662129800910123520 +1662129800955124480 +1662129801000125440 +1662129801048126464 +1662129801090127360 +1662129801150128640 +1662129801192129536 +1662129801234130432 +1662129801276131328 +1662129801321132288 +1662129801363133184 +1662129801405134080 +1662129801447134976 +1662129801495136000 +1662129801543137024 +1662129801588137984 +1662129801636139008 +1662129801681139968 +1662129801723140864 +1662129801765141760 +1662129801807142656 +1662129801855143680 +1662129801900144640 +1662129801948145664 +1662129801993146624 +1662129802044147712 +1662129802083148544 +1662129802131149568 +1662129802176150528 +1662129802224151552 +1662129802272152576 +1662129802311153408 +1662129802353154304 +1662129802398155264 +1662129802443156224 +1662129802488157184 +1662129802533158144 +1662129802584159232 +1662129802635160320 +1662129802677161216 +1662129802728162304 +1662129802773163264 +1662129802818164224 +1662129802860165120 +1662129802911166208 +1662129802950167040 +1662129802992167936 +1662129803040168960 +1662129803085169920 +1662129803136171008 +1662129803178171904 +1662129803220172800 +1662129803274173952 +1662129803316174848 +1662129803364175872 +1662129803415176960 +1662129803460177920 +1662129803499178752 +1662129803547179776 +1662129803592180736 +1662129803634181632 +1662129803676182528 +1662129803721183488 +1662129803760184320 +1662129803814185472 +1662129803856186368 +1662129803898187264 +1662129803943188224 +1662129803997189376 +1662129804039190272 +1662129804084191232 +1662129804126192128 +1662129804171193088 +1662129804216194048 +1662129804258194944 +1662129804312196096 +1662129804354196992 +1662129804402198016 +1662129804444198912 +1662129804495200000 +1662129804540200960 +1662129804582201856 +1662129804636203008 +1662129804678203904 +1662129804726204928 +1662129804768205824 +1662129804813206784 +1662129804855207680 +1662129804900208640 +1662129804951209728 +1662129804996210688 +1662129805041211648 +1662129805089212672 +1662129805140213760 +1662129805182214656 +1662129805227215616 +1662129805272216576 +1662129805314217472 +1662129805356218368 +1662129805398219264 +1662129805449220352 +1662129805494221312 +1662129805533222144 +1662129805575223040 +1662129805620224000 +1662129805662224896 +1662129805707225856 +1662129805764227072 +1662129805803227904 +1662129805842228736 +1662129805893229824 +1662129805938230784 +1662129805989231872 +1662129806031232768 +1662129806076233728 +1662129806124234752 +1662129806166235648 +1662129806205236480 +1662129806256237568 +1662129806295238400 +1662129806337239296 +1662129806379240192 +1662129806433241344 +1662129806475242240 +1662129806520243200 +1662129806565244160 +1662129806610245120 +1662129806652246016 +1662129806691246848 +1662129806736247808 +1662129806787248896 +1662129806826249728 +1662129806871250688 +1662129806916251648 +1662129806970252800 +1662129807012253696 +1662129807054254592 +1662129807096255488 +1662129807144256512 +1662129807189257472 +1662129807234258432 +1662129807282259456 +1662129807336260608 +1662129807378261504 +1662129807432262656 +1662129807480263680 +1662129807528264704 +1662129807576265728 +1662129807618266624 +1662129807657267456 +1662129807702268416 +1662129807753269504 +1662129807798270464 +1662129807840271360 +1662129807885272320 +1662129807927273216 +1662129807978274304 +1662129808017275136 +1662129808059276032 +1662129808104276992 +1662129808146277888 +1662129808197278976 +1662129808239279872 +1662129808278280704 +1662129808323281664 +1662129808374282752 +1662129808419283712 +1662129808470284800 +1662129808515285760 +1662129808557286656 +1662129808602287616 +1662129808644288512 +1662129808689289472 +1662129808734290432 +1662129808779291392 +1662129808824292352 +1662129808878293504 +1662129808920294400 +1662129808965295360 +1662129809007296256 +1662129809052297216 +1662129809094298112 +1662129809142299136 +1662129809190300160 +1662129809232301056 +1662129809277302016 +1662129809322302976 +1662129809367303936 +1662129809418305024 +1662129809460305920 +1662129809508306944 +1662129809553307904 +1662129809598308864 +1662129809646309888 +1662129809688310784 +1662129809733311744 +1662129809784312832 +1662129809832313856 +1662129809877314816 +1662129809925315840 +1662129809967316736 +1662129810012317696 +1662129810057318656 +1662129810099319552 +1662129810144320512 +1662129810186321408 +1662129810231322368 +1662129810276323328 +1662129810318324224 +1662129810360325120 +1662129810405326080 +1662129810447326976 +1662129810489327872 +1662129810543329024 +1662129810588329984 +1662129810639331072 +1662129810687332096 +1662129810732333056 +1662129810780334080 +1662129810819334912 +1662129810864335872 +1662129810909336832 +1662129810954337792 +1662129810999338752 +1662129811041339648 +1662129811086340608 +1662129811128341504 +1662129811170342400 +1662129811209343232 +1662129811263344384 +1662129811308345344 +1662129811359346432 +1662129811401347328 +1662129811446348288 +1662129811491349248 +1662129811533350144 +1662129811578351104 +1662129811626352128 +1662129811668353024 +1662129811710353920 +1662129811752354816 +1662129811794355712 +1662129811839356672 +1662129811881357568 +1662129811923358464 +1662129811974359552 +1662129812019360512 +1662129812067361536 +1662129812109362432 +1662129812151363328 +1662129812193364224 +1662129812235365120 +1662129812277366016 +1662129812322366976 +1662129812364367872 +1662129812409368832 +1662129812451369728 +1662129812499370752 +1662129812547371776 +1662129812589372672 +1662129812634373632 +1662129812679374592 +1662129812724375552 +1662129812778376704 +1662129812829377792 +1662129812874378752 +1662129812922379776 +1662129812967380736 +1662129813009381632 +1662129813057382656 +1662129813099383552 +1662129813147384576 +1662129813189385472 +1662129813231386368 +1662129813273387264 +1662129813318388224 +1662129813357389056 +1662129813402390016 +1662129813444390912 +1662129813489391872 +1662129813531392768 +1662129813579393792 +1662129813624394752 +1662129813666395648 +1662129813705396480 +1662129813747397376 +1662129813792398336 +1662129813834399232 +1662129813876400128 +1662129813918401024 +1662129813966402048 +1662129814011403008 +1662129814059404032 +1662129814104404992 +1662129814146405888 +1662129814191406848 +1662129814242407936 +1662129814284408832 +1662129814332409856 +1662129814371410688 +1662129814416411648 +1662129814467412736 +1662129814509413632 +1662129814551414528 +1662129814593415424 +1662129814635416320 +1662129814674417152 +1662129814722418176 +1662129814764419072 +1662129814818420224 +1662129814863421184 +1662129814908422144 +1662129814953423104 +1662129815001424128 +1662129815046425088 +1662129815091426048 +1662129815136427008 +1662129815181427968 +1662129815223428864 +1662129815265429760 +1662129815310430720 +1662129815352431616 +1662129815394432512 +1662129815436433408 +1662129815481434368 +1662129815526435328 +1662129815574436352 +1662129815625437440 +1662129815676438528 +1662129815721439488 +1662129815769440512 +1662129815814441472 +1662129815856442368 +1662129815910443520 +1662129815952444416 +1662129815997445376 +1662129816039446272 +1662129816087447296 +1662129816129448192 +1662129816171449088 +1662129816216450048 +1662129816264451072 +1662129816315452160 +1662129816360453120 +1662129816411454208 +1662129816456455168 +1662129816498456064 +1662129816540456960 +1662129816582457856 +1662129816627458816 +1662129816669459712 +1662129816717460736 +1662129816759461632 +1662129816813462784 +1662129816858463744 +1662129816900464640 +1662129816945465600 +1662129816996466688 +1662129817041467648 +1662129817083468544 +1662129817125469440 +1662129817179470592 +1662129817218471424 +1662129817266472448 +1662129817311473408 +1662129817359474432 +1662129817401475328 +1662129817443476224 +1662129817485477120 +1662129817527478016 +1662129817569478912 +1662129817611479808 +1662129817668481024 +1662129817713481984 +1662129817764483072 +1662129817812484096 +1662129817866485248 +1662129817908486144 +1662129817950487040 +1662129817992487936 +1662129818043489024 +1662129818094490112 +1662129818139491072 +1662129818181491968 +1662129818223492864 +1662129818268493824 +1662129818313494784 +1662129818367495936 +1662129818412496896 +1662129818454497792 +1662129818499498752 +1662129818544499712 +1662129818586500608 +1662129818631501568 +1662129818673502464 +1662129818718503424 +1662129818760504320 +1662129818802505216 +1662129818850506240 +1662129818892507136 +1662129818934508032 +1662129818982509056 +1662129819030510080 +1662129819075511040 +1662129819120512000 +1662129819162512896 +1662129819207513856 +1662129819261515008 +1662129819306515968 +1662129819354516992 +1662129819399517952 +1662129819447518976 +1662129819495520000 +1662129819534520832 +1662129819579521792 +1662129819621522688 +1662129819669523712 +1662129819714524672 +1662129819756525568 +1662129819801526528 +1662129819846527488 +1662129819888528384 +1662129819933529344 +1662129819978530304 +1662129820020531200 +1662129820062532096 +1662129820104532992 +1662129820152534016 +1662129820197534976 +1662129820239535872 +1662129820281536768 +1662129820323537664 +1662129820365538560 +1662129820410539520 +1662129820458540544 +1662129820500541440 +1662129820542542336 +1662129820587543296 +1662129820638544384 +1662129820689545472 +1662129820737546496 +1662129820782547456 +1662129820830548480 +1662129820881549568 +1662129820932550656 +1662129820983551744 +1662129821028552704 +1662129821070553600 +1662129821112554496 +1662129821157555456 +1662129821205556480 +1662129821256557568 +1662129821301558528 +1662129821343559424 +1662129821394560512 +1662129821451561728 +1662129821493562624 +1662129821535563520 +1662129821589564672 +1662129821634565632 +1662129821682566656 +1662129821724567552 +1662129821778568704 +1662129821826569728 +1662129821871570688 +1662129821913571584 +1662129821955572480 +1662129821997573376 +1662129822039574272 +1662129822084575232 +1662129822144576512 +1662129822192577536 +1662129822234578432 +1662129822276579328 +1662129822318580224 +1662129822363581184 +1662129822411582208 +1662129822453583104 +1662129822498584064 +1662129822540584960 +1662129822582585856 +1662129822624586752 +1662129822669587712 +1662129822708588544 +1662129822750589440 +1662129822792590336 +1662129822843591424 +1662129822885592320 +1662129822939593472 +1662129822981594368 +1662129823023595264 +1662129823062596096 +1662129823101596928 +1662129823143597824 +1662129823185598720 +1662129823233599744 +1662129823278600704 +1662129823332601856 +1662129823380602880 +1662129823425603840 +1662129823473604864 +1662129823521605888 +1662129823560606720 +1662129823605607680 +1662129823650608640 +1662129823698609664 +1662129823740610560 +1662129823791611648 +1662129823836612608 +1662129823878613504 +1662129823923614464 +1662129823971615488 +1662129824016616448 +1662129824067617536 +1662129824112618496 +1662129824154619392 +1662129824208620544 +1662129824253621504 +1662129824298622464 +1662129824340623360 +1662129824388624384 +1662129824430625280 +1662129824475626240 +1662129824514627072 +1662129824556627968 +1662129824607629056 +1662129824655630080 +1662129824703631104 +1662129824745632000 +1662129824790632960 +1662129824832633856 +1662129824880634880 +1662129824925635840 +1662129824970636800 +1662129825018637824 +1662129825063638784 +1662129825108639744 +1662129825153640704 +1662129825195641600 +1662129825249642752 +1662129825300643840 +1662129825345644800 +1662129825387645696 +1662129825435646720 +1662129825477647616 +1662129825522648576 +1662129825570649600 +1662129825615650560 +1662129825660651520 +1662129825702652416 +1662129825747653376 +1662129825792654336 +1662129825837655296 +1662129825876656128 +1662129825918657024 +1662129825960657920 +1662129826005658880 +1662129826047659776 +1662129826104660992 +1662129826152662016 +1662129826197662976 +1662129826236663808 +1662129826278664704 +1662129826323665664 +1662129826365666560 +1662129826416667648 +1662129826458668544 +1662129826506669568 +1662129826551670528 +1662129826599671552 +1662129826644672512 +1662129826695673600 +1662129826743674624 +1662129826785675520 +1662129826836676608 +1662129826887677696 +1662129826941678848 +1662129826992679936 +1662129827031680768 +1662129827079681792 +1662129827121682688 +1662129827166683648 +1662129827217684736 +1662129827262685696 +1662129827304686592 +1662129827349687552 +1662129827400688640 +1662129827451689728 +1662129827490690560 +1662129827544691712 +1662129827589692672 +1662129827631693568 +1662129827676694528 +1662129827730695680 +1662129827769696512 +1662129827811697408 +1662129827856698368 +1662129827901699328 +1662129827943700224 +1662129827985701120 +1662129828027702016 +1662129828072702976 +1662129828114703872 +1662129828162704896 +1662129828204705792 +1662129828246706688 +1662129828303707904 +1662129828345708800 +1662129828387709696 +1662129828432710656 +1662129828471711488 +1662129828513712384 +1662129828558713344 +1662129828612714496 +1662129828657715456 +1662129828699716352 +1662129828738717184 +1662129828780718080 +1662129828831719168 +1662129828876720128 +1662129828918721024 +1662129828963721984 +1662129829008722944 +1662129829050723840 +1662129829095724800 +1662129829134725632 +1662129829176726528 +1662129829224727552 +1662129829266728448 +1662129829311729408 +1662129829350730240 +1662129829392731136 +1662129829437732096 +1662129829479732992 +1662129829533734144 +1662129829578735104 +1662129829620736000 +1662129829671737088 +1662129829719738112 +1662129829761739008 +1662129829806739968 +1662129829854740992 +1662129829899741952 +1662129829947742976 +1662129829989743872 +1662129830034744832 +1662129830079745792 +1662129830121746688 +1662129830163747584 +1662129830205748480 +1662129830247749376 +1662129830289750272 +1662129830328751104 +1662129830376752128 +1662129830427753216 +1662129830469754112 +1662129830514755072 +1662129830565756160 +1662129830610757120 +1662129830652758016 +1662129830703759104 +1662129830745760000 +1662129830793761024 +1662129830844762112 +1662129830886763008 +1662129830928763904 +1662129830973764864 +1662129831015765760 +1662129831057766656 +1662129831099767552 +1662129831144768512 +1662129831186769408 +1662129831231770368 +1662129831276771328 +1662129831318772224 +1662129831357773056 +1662129831405774080 +1662129831447774976 +1662129831495776000 +1662129831537776896 +1662129831591778048 +1662129831636779008 +1662129831681779968 +1662129831729780992 +1662129831786782208 +1662129831834783232 +1662129831882784256 +1662129831921785088 +1662129831963785984 +1662129832005786880 +1662129832050787840 +1662129832101788928 +1662129832149789952 +1662129832188790784 +1662129832233791744 +1662129832275792640 +1662129832323793664 +1662129832368794624 +1662129832410795520 +1662129832452796416 +1662129832494797312 +1662129832536798208 +1662129832581799168 +1662129832626800128 +1662129832668801024 +1662129832710801920 +1662129832758802944 +1662129832800803840 +1662129832854804992 +1662129832896805888 +1662129832941806848 +1662129832989807872 +1662129833034808832 +1662129833076809728 +1662129833124810752 +1662129833166811648 +1662129833223812864 +1662129833265813760 +1662129833310814720 +1662129833355815680 +1662129833406816768 +1662129833448817664 +1662129833493818624 +1662129833541819648 +1662129833583820544 +1662129833628821504 +1662129833673822464 +1662129833715823360 +1662129833760824320 +1662129833799825152 +1662129833841826048 +1662129833889827072 +1662129833937828096 +1662129833985829120 +1662129834030830080 +1662129834069830912 +1662129834117831936 +1662129834162832896 +1662129834210833920 +1662129834255834880 +1662129834303835904 +1662129834348836864 +1662129834387837696 +1662129834432838656 +1662129834480839680 +1662129834528840704 +1662129834570841600 +1662129834609842432 +1662129834651843328 +1662129834693844224 +1662129834735845120 +1662129834786846208 +1662129834834847232 +1662129834876848128 +1662129834924849152 +1662129834966850048 +1662129835011851008 +1662129835056851968 +1662129835101852928 +1662129835158854144 +1662129835200855040 +1662129835245856000 +1662129835287856896 +1662129835341858048 +1662129835383858944 +1662129835428859904 +1662129835476860928 +1662129835521861888 +1662129835566862848 +1662129835605863680 +1662129835647864576 +1662129835698865664 +1662129835746866688 +1662129835788867584 +1662129835836868608 +1662129835878869504 +1662129835920870400 +1662129835965871360 +1662129836013872384 +1662129836052873216 +1662129836094874112 +1662129836142875136 +1662129836190876160 +1662129836238877184 +1662129836280878080 +1662129836328879104 +1662129836367879936 +1662129836415880960 +1662129836457881856 +1662129836499882752 +1662129836544883712 +1662129836586884608 +1662129836628885504 +1662129836679886592 +1662129836730887680 +1662129836772888576 +1662129836817889536 +1662129836862890496 +1662129836913891584 +1662129836958892544 +1662129837006893568 +1662129837057894656 +1662129837096895488 +1662129837135896320 +1662129837177897216 +1662129837219898112 +1662129837264899072 +1662129837309900032 +1662129837351900928 +1662129837393901824 +1662129837444902912 +1662129837483903744 +1662129837528904704 +1662129837573905664 +1662129837615906560 +1662129837657907456 +1662129837702908416 +1662129837747909376 +1662129837792910336 +1662129837843911424 +1662129837885912320 +1662129837930913280 +1662129837975914240 +1662129838020915200 +1662129838062916096 +1662129838104916992 +1662129838149917952 +1662129838191918848 +1662129838236919808 +1662129838278920704 +1662129838320921600 +1662129838374922752 +1662129838419923712 +1662129838464924672 +1662129838512925696 +1662129838554926592 +1662129838596927488 +1662129838638928384 +1662129838686929408 +1662129838728930304 +1662129838770931200 +1662129838812932096 +1662129838854932992 +1662129838896933888 +1662129838941934848 +1662129838983935744 +1662129839028936704 +1662129839070937600 +1662129839112938496 +1662129839154939392 +1662129839199940352 +1662129839244941312 +1662129839286942208 +1662129839328943104 +1662129839370944000 +1662129839421945088 +1662129839463945984 +1662129839508946944 +1662129839550947840 +1662129839589948672 +1662129839631949568 +1662129839673950464 +1662129839715951360 +1662129839757952256 +1662129839802953216 +1662129839844954112 +1662129839895955200 +1662129839940956160 +1662129839982957056 +1662129840024957952 +1662129840075959040 +1662129840126960128 +1662129840171961088 +1662129840213961984 +1662129840255962880 +1662129840297963776 +1662129840339964672 +1662129840381965568 +1662129840426966528 +1662129840468967424 +1662129840513968384 +1662129840564969472 +1662129840609970432 +1662129840660971520 +1662129840708972544 +1662129840759973632 +1662129840801974528 +1662129840843975424 +1662129840888976384 +1662129840933977344 +1662129840975978240 +1662129841020979200 +1662129841071980288 +1662129841116981248 +1662129841164982272 +1662129841203983104 +1662129841248984064 +1662129841302985216 +1662129841344986112 +1662129841392987136 +1662129841434988032 +1662129841479988992 +1662129841527990016 +1662129841569990912 +1662129841617991936 +1662129841662992896 +1662129841707993856 +1662129841749994752 +1662129841791995648 +1662129841833996544 +1662129841875997440 +1662129841914998272 +1662129841956999168 +1662129841999000064 +1662129842041000960 +1662129842086001920 +1662129842131002880 +1662129842188004096 +1662129842233005056 +1662129842278006016 +1662129842326007040 +1662129842368007936 +1662129842419009024 +1662129842458009856 +1662129842500010752 +1662129842542011648 +1662129842584012544 +1662129842626013440 +1662129842680014592 +1662129842719015424 +1662129842773016576 +1662129842818017536 +1662129842860018432 +1662129842905019392 +1662129842947020288 +1662129842992021248 +1662129843040022272 +1662129843079023104 +1662129843121024000 +1662129843166024960 +1662129843208025856 +1662129843250026752 +1662129843292027648 +1662129843337028608 +1662129843382029568 +1662129843433030656 +1662129843481031680 +1662129843526032640 +1662129843574033664 +1662129843625034752 +1662129843667035648 +1662129843709036544 +1662129843751037440 +1662129843793038336 +1662129843835039232 +1662129843880040192 +1662129843922041088 +1662129843973042176 +1662129844018043136 +1662129844066044160 +1662129844108045056 +1662129844150045952 +1662129844204047104 +1662129844255048192 +1662129844297049088 +1662129844339049984 +1662129844381050880 +1662129844423051776 +1662129844462052608 +1662129844504053504 +1662129844552054528 +1662129844597055488 +1662129844642056448 +1662129844687057408 +1662129844732058368 +1662129844771059200 +1662129844813060096 +1662129844855060992 +1662129844906062080 +1662129844948062976 +1662129844996064000 +1662129845035064832 +1662129845083065856 +1662129845137067008 +1662129845179067904 +1662129845227068928 +1662129845272069888 +1662129845314070784 +1662129845356071680 +1662129845401072640 +1662129845443073536 +1662129845485074432 +1662129845527075328 +1662129845572076288 +1662129845617077248 +1662129845662078208 +1662129845704079104 +1662129845746080000 +1662129845788080896 +1662129845836081920 +1662129845878082816 +1662129845926083840 +1662129845974084864 +1662129846019085824 +1662129846067086848 +1662129846112087808 +1662129846157088768 +1662129846202089728 +1662129846244090624 +1662129846286091520 +1662129846328092416 +1662129846385093632 +1662129846424094464 +1662129846469095424 +1662129846508096256 +1662129846553097216 +1662129846598098176 +1662129846649099264 +1662129846697100288 +1662129846739101184 +1662129846787102208 +1662129846832103168 +1662129846874104064 +1662129846919105024 +1662129846964105984 +1662129847006106880 +1662129847051107840 +1662129847105108992 +1662129847156110080 +1662129847201111040 +1662129847246112000 +1662129847288112896 +1662129847336113920 +1662129847384114944 +1662129847423115776 +1662129847468116736 +1662129847519117824 +1662129847567118848 +1662129847612119808 +1662129847654120704 +1662129847702121728 +1662129847744122624 +1662129847783123456 +1662129847831124480 +1662129847873125376 +1662129847921126400 +1662129847963127296 +1662129848005128192 +1662129848053129216 +1662129848107130368 +1662129848152131328 +1662129848197132288 +1662129848242133248 +1662129848284134144 +1662129848332135168 +1662129848380136192 +1662129848422137088 +1662129848467138048 +1662129848509138944 +1662129848551139840 +1662129848593140736 +1662129848632141568 +1662129848674142464 +1662129848719143424 +1662129848764144384 +1662129848812145408 +1662129848857146368 +1662129848896147200 +1662129848941148160 +1662129848992149248 +1662129849034150144 +1662129849076151040 +1662129849127152128 +1662129849169153024 +1662129849223154176 +1662129849277155328 +1662129849325156352 +1662129849367157248 +1662129849418158336 +1662129849466159360 +1662129849514160384 +1662129849556161280 +1662129849604162304 +1662129849652163328 +1662129849694164224 +1662129849736165120 +1662129849781166080 +1662129849832167168 +1662129849877168128 +1662129849922169088 +1662129849964169984 +1662129850009170944 +1662129850051171840 +1662129850093172736 +1662129850138173696 +1662129850180174592 +1662129850222175488 +1662129850264176384 +1662129850315177472 +1662129850360178432 +1662129850399179264 +1662129850444180224 +1662129850489181184 +1662129850531182080 +1662129850576183040 +1662129850621184000 +1662129850669185024 +1662129850714185984 +1662129850759186944 +1662129850804187904 +1662129850846188800 +1662129850894189824 +1662129850936190720 +1662129850987191808 +1662129851029192704 +1662129851074193664 +1662129851119194624 +1662129851164195584 +1662129851209196544 +1662129851254197504 +1662129851299198464 +1662129851338199296 +1662129851380200192 +1662129851422201088 +1662129851470202112 +1662129851515203072 +1662129851554203904 +1662129851596204800 +1662129851647205888 +1662129851695206912 +1662129851737207808 +1662129851785208832 +1662129851830209792 +1662129851872210688 +1662129851917211648 +1662129851959212544 +1662129852001213440 +1662129852049214464 +1662129852100215552 +1662129852148216576 +1662129852190217472 +1662129852229218304 +1662129852271219200 +1662129852313220096 +1662129852355220992 +1662129852409222144 +1662129852451223040 +1662129852496224000 +1662129852538224896 +1662129852583225856 +1662129852625226752 +1662129852676227840 +1662129852724228864 +1662129852766229760 +1662129852811230720 +1662129852859231744 +1662129852907232768 +1662129852955233792 +1662129852997234688 +1662129853042235648 +1662129853090236672 +1662129853138237696 +1662129853189238784 +1662129853237239808 +1662129853279240704 +1662129853324241664 +1662129853366242560 +1662129853408243456 +1662129853453244416 +1662129853501245440 +1662129853543246336 +1662129853591247360 +1662129853636248320 +1662129853678249216 +1662129853723250176 +1662129853771251200 +1662129853816252160 +1662129853873253376 +1662129853924254464 +1662129853969255424 +1662129854011256320 +1662129854056257280 +1662129854098258176 +1662129854140259072 +1662129854185260032 +1662129854233261056 +1662129854284262144 +1662129854329263104 +1662129854374264064 +1662129854422265088 +1662129854473266176 +1662129854521267200 +1662129854560268032 +1662129854605268992 +1662129854644269824 +1662129854686270720 +1662129854728271616 +1662129854782272768 +1662129854827273728 +1662129854869274624 +1662129854911275520 +1662129854962276608 +1662129855010277632 +1662129855055278592 +1662129855100279552 +1662129855142280448 +1662129855187281408 +1662129855235282432 +1662129855283283456 +1662129855328284416 +1662129855370285312 +1662129855409286144 +1662129855454287104 +1662129855499288064 +1662129855541288960 +1662129855580289792 +1662129855625290752 +1662129855670291712 +1662129855712292608 +1662129855754293504 +1662129855799294464 +1662129855841295360 +1662129855886296320 +1662129855937297408 +1662129855976298240 +1662129856018299136 +1662129856066300160 +1662129856111301120 +1662129856156302080 +1662129856204303104 +1662129856255304192 +1662129856297305088 +1662129856339305984 +1662129856381306880 +1662129856426307840 +1662129856465308672 +1662129856507309568 +1662129856549310464 +1662129856594311424 +1662129856636312320 +1662129856678313216 +1662129856720314112 +1662129856768315136 +1662129856813316096 +1662129856855316992 +1662129856897317888 +1662129856939318784 +1662129856984319744 +1662129857029320704 +1662129857074321664 +1662129857122322688 +1662129857167323648 +1662129857215324672 +1662129857260325632 +1662129857302326528 +1662129857350327552 +1662129857395328512 +1662129857437329408 +1662129857479330304 +1662129857521331200 +1662129857566332160 +1662129857614333184 +1662129857656334080 +1662129857698334976 +1662129857743335936 +1662129857785336832 +1662129857827337728 +1662129857875338752 +1662129857917339648 +1662129857959340544 +1662129858001341440 +1662129858049342464 +1662129858088343296 +1662129858127344128 +1662129858169345024 +1662129858211345920 +1662129858259346944 +1662129858301347840 +1662129858352348928 +1662129858403350016 +1662129858448350976 +1662129858496352000 +1662129858541352960 +1662129858589353984 +1662129858637355008 +1662129858688356096 +1662129858727356928 +1662129858769357824 +1662129858814358784 +1662129858856359680 +1662129858898360576 +1662129858943361536 +1662129858985362432 +1662129859042363648 +1662129859087364608 +1662129859126365440 +1662129859171366400 +1662129859213367296 +1662129859255368192 +1662129859300369152 +1662129859342370048 +1662129859390371072 +1662129859432371968 +1662129859477372928 +1662129859528374016 +1662129859570374912 +1662129859615375872 +1662129859657376768 +1662129859699377664 +1662129859750378752 +1662129859792379648 +1662129859834380544 +1662129859879381504 +1662129859921382400 +1662129859963383296 +1662129860008384256 +1662129860053385216 +1662129860095386112 +1662129860140387072 +1662129860182387968 +1662129860233389056 +1662129860275389952 +1662129860320390912 +1662129860368391936 +1662129860419393024 +1662129860464393984 +1662129860506394880 +1662129860548395776 +1662129860590396672 +1662129860641397760 +1662129860683398656 +1662129860731399680 +1662129860776400640 +1662129860818401536 +1662129860869402624 +1662129860917403648 +1662129860959404544 +1662129861007405568 +1662129861055406592 +1662129861097407488 +1662129861142408448 +1662129861184409344 +1662129861229410304 +1662129861274411264 +1662129861319412224 +1662129861364413184 +1662129861415414272 +1662129861457415168 +1662129861496416000 +1662129861538416896 +1662129861586417920 +1662129861625418752 +1662129861667419648 +1662129861712420608 +1662129861754421504 +1662129861796422400 +1662129861838423296 +1662129861886424320 +1662129861937425408 +1662129861982426368 +1662129862024427264 +1662129862066428160 +1662129862114429184 +1662129862159430144 +1662129862201431040 +1662129862243431936 +1662129862291432960 +1662129862336433920 +1662129862378434816 +1662129862423435776 +1662129862465436672 +1662129862516437760 +1662129862561438720 +1662129862603439616 +1662129862648440576 +1662129862687441408 +1662129862729442304 +1662129862777443328 +1662129862825444352 +1662129862867445248 +1662129862912446208 +1662129862960447232 +1662129863005448192 +1662129863056449280 +1662129863101450240 +1662129863140451072 +1662129863182451968 +1662129863224452864 +1662129863266453760 +1662129863317454848 +1662129863359455744 +1662129863407456768 +1662129863455457792 +1662129863497458688 +1662129863542459648 +1662129863584460544 +1662129863626461440 +1662129863674462464 +1662129863722463488 +1662129863764464384 +1662129863806465280 +1662129863845466112 +1662129863890467072 +1662129863932467968 +1662129863977468928 +1662129864019469824 +1662129864061470720 +1662129864106471680 +1662129864154472704 +1662129864202473728 +1662129864244474624 +1662129864286475520 +1662129864331476480 +1662129864382477568 +1662129864427478528 +1662129864472479488 +1662129864517480448 +1662129864559481344 +1662129864601482240 +1662129864646483200 +1662129864694484224 +1662129864733485056 +1662129864778486016 +1662129864829487104 +1662129864880488192 +1662129864922489088 +1662129864964489984 +1662129865006490880 +1662129865054491904 +1662129865099492864 +1662129865141493760 +1662129865183494656 +1662129865222495488 +1662129865270496512 +1662129865312497408 +1662129865351498240 +1662129865393499136 +1662129865438500096 +1662129865489501184 +1662129865534502144 +1662129865579503104 +1662129865624504064 +1662129865666504960 +1662129865708505856 +1662129865753506816 +1662129865804507904 +1662129865846508800 +1662129865894509824 +1662129865939510784 +1662129865981511680 +1662129866023512576 +1662129866077513728 +1662129866125514752 +1662129866167515648 +1662129866212516608 +1662129866257517568 +1662129866308518656 +1662129866353519616 +1662129866398520576 +1662129866440521472 +1662129866485522432 +1662129866530523392 +1662129866578524416 +1662129866620525312 +1662129866662526208 +1662129866707527168 +1662129866752528128 +1662129866794529024 +1662129866836529920 +1662129866875530752 +1662129866920531712 +1662129866974532864 +1662129867022533888 +1662129867064534784 +1662129867106535680 +1662129867151536640 +1662129867190537472 +1662129867244538624 +1662129867289539584 +1662129867331540480 +1662129867385541632 +1662129867427542528 +1662129867472543488 +1662129867517544448 +1662129867562545408 +1662129867607546368 +1662129867649547264 +1662129867697548288 +1662129867742549248 +1662129867787550208 +1662129867829551104 +1662129867868551936 +1662129867916552960 +1662129867961553920 +1662129868009554944 +1662129868054555904 +1662129868096556800 +1662129868150557952 +1662129868192558848 +1662129868234559744 +1662129868279560704 +1662129868327561728 +1662129868378562816 +1662129868423563776 +1662129868465564672 +1662129868507565568 +1662129868549566464 +1662129868591567360 +1662129868633568256 +1662129868675569152 +1662129868723570176 +1662129868768571136 +1662129868822572288 +1662129868867573248 +1662129868909574144 +1662129868957575168 +1662129869002576128 +1662129869050577152 +1662129869092578048 +1662129869137579008 +1662129869182579968 +1662129869224580864 +1662129869266581760 +1662129869314582784 +1662129869356583680 +1662129869401584640 +1662129869449585664 +1662129869491586560 +1662129869533587456 +1662129869575588352 +1662129869614589184 +1662129869659590144 +1662129869701591040 +1662129869749592064 +1662129869788592896 +1662129869830593792 +1662129869875594752 +1662129869917595648 +1662129869962596608 +1662129870010597632 +1662129870055598592 +1662129870097599488 +1662129870142600448 +1662129870184601344 +1662129870226602240 +1662129870271603200 +1662129870316604160 +1662129870355604992 +1662129870409606144 +1662129870451607040 +1662129870502608128 +1662129870541608960 +1662129870586609920 +1662129870628610816 +1662129870673611776 +1662129870718612736 +1662129870763613696 +1662129870808614656 +1662129870850615552 +1662129870892616448 +1662129870943617536 +1662129870985618432 +1662129871033619456 +1662129871078620416 +1662129871129621504 +1662129871171622400 +1662129871216623360 +1662129871258624256 +1662129871306625280 +1662129871348626176 +1662129871390627072 +1662129871432627968 +1662129871474628864 +1662129871525629952 +1662129871573630976 +1662129871615631872 +1662129871657632768 +1662129871702633728 +1662129871744634624 +1662129871789635584 +1662129871837636608 +1662129871885637632 +1662129871930638592 +1662129871972639488 +1662129872020640512 +1662129872065641472 +1662129872107642368 +1662129872149643264 +1662129872191644160 +1662129872239645184 +1662129872287646208 +1662129872332647168 +1662129872374648064 +1662129872419649024 +1662129872464649984 +1662129872509650944 +1662129872557651968 +1662129872602652928 +1662129872644653824 +1662129872689654784 +1662129872731655680 +1662129872773656576 +1662129872827657728 +1662129872875658752 +1662129872926659840 +1662129872977660928 +1662129873025661952 +1662129873070662912 +1662129873124664064 +1662129873178665216 +1662129873223666176 +1662129873271667200 +1662129873328668416 +1662129873370669312 +1662129873415670272 +1662129873460671232 +1662129873505672192 +1662129873547673088 +1662129873592674048 +1662129873634674944 +1662129873679675904 +1662129873721676800 +1662129873763677696 +1662129873808678656 +1662129873853679616 +1662129873898680576 +1662129873940681472 +1662129873982682368 +1662129874024683264 +1662129874072684288 +1662129874123685376 +1662129874168686336 +1662129874210687232 +1662129874255688192 +1662129874297689088 +1662129874348690176 +1662129874393691136 +1662129874435692032 +1662129874477692928 +1662129874522693888 +1662129874567694848 +1662129874609695744 +1662129874651696640 +1662129874693697536 +1662129874735698432 +1662129874780699392 +1662129874822700288 +1662129874867701248 +1662129874921702400 +1662129874966703360 +1662129875011704320 +1662129875053705216 +1662129875095706112 +1662129875137707008 +1662129875179707904 +1662129875221708800 +1662129875266709760 +1662129875311710720 +1662129875356711680 +1662129875395712512 +1662129875437713408 +1662129875482714368 +1662129875524715264 +1662129875569716224 +1662129875611717120 +1662129875650717952 +1662129875692718848 +1662129875743719936 +1662129875788720896 +1662129875830721792 +1662129875872722688 +1662129875917723648 +1662129875959724544 +1662129876001725440 +1662129876052726528 +1662129876103727616 +1662129876148728576 +1662129876190729472 +1662129876238730496 +1662129876286731520 +1662129876328732416 +1662129876373733376 +1662129876415734272 +1662129876463735296 +1662129876508736256 +1662129876550737152 +1662129876592738048 +1662129876634738944 +1662129876679739904 +1662129876727740928 +1662129876775741952 +1662129876817742848 +1662129876859743744 +1662129876904744704 +1662129876943745536 +1662129876985746432 +1662129877030747392 +1662129877075748352 +1662129877120749312 +1662129877165750272 +1662129877222751488 +1662129877270752512 +1662129877312753408 +1662129877357754368 +1662129877399755264 +1662129877441756160 +1662129877483757056 +1662129877528758016 +1662129877567758848 +1662129877609759744 +1662129877651760640 +1662129877696761600 +1662129877735762432 +1662129877783763456 +1662129877831764480 +1662129877873765376 +1662129877924766464 +1662129877969767424 +1662129878014768384 +1662129878053769216 +1662129878095770112 +1662129878140771072 +1662129878185772032 +1662129878227772928 +1662129878266773760 +1662129878311774720 +1662129878353775616 +1662129878401776640 +1662129878446777600 +1662129878488778496 +1662129878530779392 +1662129878578780416 +1662129878617781248 +1662129878665782272 +1662129878707783168 +1662129878752784128 +1662129878794785024 +1662129878845786112 +1662129878890787072 +1662129878932787968 +1662129878974788864 +1662129879025789952 +1662129879073790976 +1662129879115791872 +1662129879166792960 +1662129879214793984 +1662129879256794880 +1662129879295795712 +1662129879337796608 +1662129879382797568 +1662129879427798528 +1662129879469799424 +1662129879514800384 +1662129879559801344 +1662129879604802304 +1662129879652803328 +1662129879700804352 +1662129879742805248 +1662129879784806144 +1662129879832807168 +1662129879877808128 +1662129879925809152 +1662129879967810048 +1662129880009810944 +1662129880060812032 +1662129880105812992 +1662129880144813824 +1662129880189814784 +1662129880231815680 +1662129880279816704 +1662129880321817600 +1662129880366818560 +1662129880408819456 +1662129880456820480 +1662129880498821376 +1662129880540822272 +1662129880585823232 +1662129880624824064 +1662129880669825024 +1662129880711825920 +1662129880756826880 +1662129880801827840 +1662129880843828736 +1662129880885829632 +1662129880933830656 +1662129880981831680 +1662129881029832704 +1662129881074833664 +1662129881116834560 +1662129881158835456 +1662129881203836416 +1662129881245837312 +1662129881293838336 +1662129881335839232 +1662129881383840256 +1662129881425841152 +1662129881470842112 +1662129881524843264 +1662129881569844224 +1662129881611845120 +1662129881656846080 +1662129881704847104 +1662129881749848064 +1662129881794849024 +1662129881836849920 +1662129881887851008 +1662129881929851904 +1662129881977852928 +1662129882019853824 +1662129882064854784 +1662129882118855936 +1662129882163856896 +1662129882211857920 +1662129882253858816 +1662129882298859776 +1662129882340860672 +1662129882382861568 +1662129882421862400 +1662129882463863296 +1662129882508864256 +1662129882553865216 +1662129882601866240 +1662129882643867136 +1662129882685868032 +1662129882733869056 +1662129882781870080 +1662129882826871040 +1662129882871872000 +1662129882913872896 +1662129882955873792 +1662129882997874688 +1662129883036875520 +1662129883078876416 +1662129883132877568 +1662129883174878464 +1662129883216879360 +1662129883267880448 +1662129883309881344 +1662129883351882240 +1662129883399883264 +1662129883444884224 +1662129883483885056 +1662129883525885952 +1662129883576887040 +1662129883624888064 +1662129883675889152 +1662129883723890176 +1662129883762891008 +1662129883810892032 +1662129883861893120 +1662129883903894016 +1662129883948894976 +1662129883996896000 +1662129884038896896 +1662129884092898048 +1662129884137899008 +1662129884185900032 +1662129884230900992 +1662129884281902080 +1662129884320902912 +1662129884368903936 +1662129884407904768 +1662129884452905728 +1662129884497906688 +1662129884548907776 +1662129884593908736 +1662129884635909632 +1662129884686910720 +1662129884737911808 +1662129884782912768 +1662129884827913728 +1662129884872914688 +1662129884923915776 +1662129884968916736 +1662129885010917632 +1662129885049918464 +1662129885091919360 +1662129885142920448 +1662129885187921408 +1662129885229922304 +1662129885277923328 +1662129885322924288 +1662129885367925248 +1662129885409926144 +1662129885454927104 +1662129885505928192 +1662129885550929152 +1662129885595930112 +1662129885643931136 +1662129885685932032 +1662129885730932992 +1662129885772933888 +1662129885826935040 +1662129885877936128 +1662129885919937024 +1662129885961937920 +1662129886006938880 +1662129886060940032 +1662129886105940992 +1662129886147941888 +1662129886192942848 +1662129886234943744 +1662129886276944640 +1662129886318945536 +1662129886378946816 +1662129886423947776 +1662129886465948672 +1662129886510949632 +1662129886558950656 +1662129886603951616 +1662129886645952512 +1662129886687953408 +1662129886732954368 +1662129886777955328 +1662129886819956224 +1662129886861957120 +1662129886909958144 +1662129886951959040 +1662129886996960000 +1662129887038960896 +1662129887080961792 +1662129887134962944 +1662129887173963776 +1662129887218964736 +1662129887263965696 +1662129887308966656 +1662129887353967616 +1662129887398968576 +1662129887449969664 +1662129887491970560 +1662129887533971456 +1662129887578972416 +1662129887623973376 +1662129887665974272 +1662129887710975232 +1662129887758976256 +1662129887797977088 +1662129887839977984 +1662129887881978880 +1662129887929979904 +1662129887974980864 +1662129888019981824 +1662129888061982720 +1662129888112983808 +1662129888151984640 +1662129888199985664 +1662129888244986624 +1662129888286987520 +1662129888331988480 +1662129888376989440 +1662129888418990336 +1662129888460991232 +1662129888508992256 +1662129888553993216 +1662129888595994112 +1662129888637995008 +1662129888679995904 +1662129888721996800 +1662129888763997696 +1662129888808998656 +1662129888850999552 +1662129888893000448 +1662129888935001344 +1662129888980002304 +1662129889025003264 +1662129889064004096 +1662129889112005120 +1662129889157006080 +1662129889202007040 +1662129889241007872 +1662129889289008896 +1662129889331009792 +1662129889376010752 +1662129889424011776 +1662129889466012672 +1662129889508013568 +1662129889559014656 +1662129889604015616 +1662129889643016448 +1662129889685017344 +1662129889730018304 +1662129889772019200 +1662129889826020352 +1662129889865021184 +1662129889904022016 +1662129889952023040 +1662129889997024000 +1662129890039024896 +1662129890081025792 +1662129890123026688 +1662129890171027712 +1662129890213028608 +1662129890255029504 +1662129890297030400 +1662129890339031296 +1662129890381032192 +1662129890423033088 +1662129890471034112 +1662129890513035008 +1662129890558035968 +1662129890603036928 +1662129890648037888 +1662129890702039040 +1662129890750040064 +1662129890789040896 +1662129890840041984 +1662129890882042880 +1662129890927043840 +1662129890972044800 +1662129891020045824 +1662129891062046720 +1662129891116047872 +1662129891164048896 +1662129891209049856 +1662129891257050880 +1662129891299051776 +1662129891344052736 +1662129891386053632 +1662129891428054528 +1662129891467055360 +1662129891509056256 +1662129891554057216 +1662129891599058176 +1662129891644059136 +1662129891686060032 +1662129891743061248 +1662129891785062144 +1662129891824062976 +1662129891863063808 +1662129891911064832 +1662129891956065792 +1662129891998066688 +1662129892040067584 +1662129892088068608 +1662129892133069568 +1662129892175070464 +1662129892217071360 +1662129892259072256 +1662129892304073216 +1662129892346074112 +1662129892391075072 +1662129892436076032 +1662129892484077056 +1662129892523077888 +1662129892565078784 +1662129892610079744 +1662129892655080704 +1662129892697081600 +1662129892745082624 +1662129892787083520 +1662129892835084544 +1662129892880085504 +1662129892931086592 +1662129892973087488 +1662129893015088384 +1662129893057089280 +1662129893096090112 +1662129893138091008 +1662129893183091968 +1662129893228092928 +1662129893276093952 +1662129893327095040 +1662129893369095936 +1662129893414096896 +1662129893459097856 +1662129893501098752 +1662129893546099712 +1662129893600100864 +1662129893645101824 +1662129893687102720 +1662129893735103744 +1662129893774104576 +1662129893816105472 +1662129893858106368 +1662129893900107264 +1662129893948108288 +1662129893990109184 +1662129894035110144 +1662129894080111104 +1662129894128112128 +1662129894170113024 +1662129894215113984 +1662129894257114880 +1662129894299115776 +1662129894341116672 +1662129894386117632 +1662129894425118464 +1662129894467119360 +1662129894515120384 +1662129894560121344 +1662129894611122432 +1662129894650123264 +1662129894695124224 +1662129894737125120 +1662129894782126080 +1662129894833127168 +1662129894884128256 +1662129894929129216 +1662129894977130240 +1662129895034131456 +1662129895085132544 +1662129895130133504 +1662129895172134400 +1662129895214135296 +1662129895262136320 +1662129895304137216 +1662129895343138048 +1662129895385138944 +1662129895427139840 +1662129895466140672 +1662129895511141632 +1662129895568142848 +1662129895616143872 +1662129895661144832 +1662129895709145856 +1662129895760146944 +1662129895808147968 +1662129895850148864 +1662129895895149824 +1662129895934150656 +1662129895979151616 +1662129896033152768 +1662129896075153664 +1662129896126154752 +1662129896171155712 +1662129896216156672 +1662129896258157568 +1662129896303158528 +1662129896348159488 +1662129896390160384 +1662129896438161408 +1662129896486162432 +1662129896534163456 +1662129896582164480 +1662129896621165312 +1662129896669166336 +1662129896714167296 +1662129896756168192 +1662129896801169152 +1662129896849170176 +1662129896897171200 +1662129896945172224 +1662129896990173184 +1662129897032174080 +1662129897077175040 +1662129897122176000 +1662129897170177024 +1662129897212177920 +1662129897254178816 +1662129897299179776 +1662129897341180672 +1662129897380181504 +1662129897428182528 +1662129897479183616 +1662129897521184512 +1662129897566185472 +1662129897605186304 +1662129897647187200 +1662129897695188224 +1662129897734189056 +1662129897776189952 +1662129897821190912 +1662129897863191808 +1662129897908192768 +1662129897956193792 +1662129897998194688 +1662129898037195520 +1662129898085196544 +1662129898127197440 +1662129898169198336 +1662129898220199424 +1662129898262200320 +1662129898307201280 +1662129898349202176 +1662129898397203200 +1662129898448204288 +1662129898493205248 +1662129898538206208 +1662129898586207232 +1662129898646208512 +1662129898694209536 +1662129898736210432 +1662129898784211456 +1662129898829212416 +1662129898877213440 +1662129898919214336 +1662129898970215424 +1662129899015216384 +1662129899063217408 +1662129899111218432 +1662129899156219392 +1662129899204220416 +1662129899246221312 +1662129899291222272 +1662129899333223168 +1662129899378224128 +1662129899420225024 +1662129899462225920 +1662129899504226816 +1662129899549227776 +1662129899591228672 +1662129899636229632 +1662129899687230720 +1662129899732231680 +1662129899774232576 +1662129899816233472 +1662129899858234368 +1662129899900235264 +1662129899945236224 +1662129899993237248 +1662129900041238272 +1662129900083239168 +1662129900137240320 +1662129900188241408 +1662129900233242368 +1662129900284243456 +1662129900329244416 +1662129900371245312 +1662129900410246144 +1662129900449246976 +1662129900497248000 +1662129900539248896 +1662129900584249856 +1662129900635250944 +1662129900683251968 +1662129900725252864 +1662129900770253824 +1662129900821254912 +1662129900863255808 +1662129900905256704 +1662129900956257792 +1662129900998258688 +1662129901040259584 +1662129901082260480 +1662129901136261632 +1662129901178262528 +1662129901217263360 +1662129901262264320 +1662129901304265216 +1662129901352266240 +1662129901403267328 +1662129901448268288 +1662129901493269248 +1662129901535270144 +1662129901577271040 +1662129901631272192 +1662129901676273152 +1662129901715273984 +1662129901760274944 +1662129901799275776 +1662129901844276736 +1662129901886277632 +1662129901928278528 +1662129901973279488 +1662129902015280384 +1662129902057281280 +1662129902099282176 +1662129902141283072 +1662129902183283968 +1662129902225284864 +1662129902270285824 +1662129902318286848 +1662129902363287808 +1662129902408288768 +1662129902459289856 +1662129902507290880 +1662129902555291904 +1662129902597292800 +1662129902651293952 +1662129902696294912 +1662129902738295808 +1662129902789296896 +1662129902831297792 +1662129902882298880 +1662129902936300032 +1662129902978300928 +1662129903020301824 +1662129903062302720 +1662129903110303744 +1662129903155304704 +1662129903197305600 +1662129903239306496 +1662129903281307392 +1662129903323308288 +1662129903365309184 +1662129903410310144 +1662129903455311104 +1662129903494311936 +1662129903536312832 +1662129903578313728 +1662129903617314560 +1662129903662315520 +1662129903704316416 +1662129903749317376 +1662129903791318272 +1662129903833319168 +1662129903875320064 +1662129903920321024 +1662129903962321920 +1662129904019323136 +1662129904061324032 +1662129904106324992 +1662129904151325952 +1662129904199326976 +1662129904241327872 +1662129904289328896 +1662129904331329792 +1662129904379330816 +1662129904421331712 +1662129904463332608 +1662129904505333504 +1662129904547334400 +1662129904592335360 +1662129904634336256 +1662129904679337216 +1662129904721338112 +1662129904766339072 +1662129904805339904 +1662129904847340800 +1662129904889341696 +1662129904931342592 +1662129904976343552 +1662129905021344512 +1662129905063345408 +1662129905105346304 +1662129905156347392 +1662129905195348224 +1662129905231348992 +1662129905276349952 +1662129905318350848 +1662129905363351808 +1662129905405352704 +1662129905450353664 +1662129905492354560 +1662129905537355520 +1662129905591356672 +1662129905633357568 +1662129905687358720 +1662129905738359808 +1662129905780360704 +1662129905825361664 +1662129905867362560 +1662129905918363648 +1662129905960364544 +1662129906005365504 +1662129906047366400 +1662129906089367296 +1662129906131368192 +1662129906176369152 +1662129906224370176 +1662129906266371072 +1662129906311372032 +1662129906362373120 +1662129906404374016 +1662129906449374976 +1662129906494375936 +1662129906536376832 +1662129906578377728 +1662129906623378688 +1662129906668379648 +1662129906707380480 +1662129906749381376 +1662129906803382528 +1662129906845383424 +1662129906887384320 +1662129906932385280 +1662129906974386176 +1662129907019387136 +1662129907064388096 +1662129907106388992 +1662129907151389952 +1662129907196390912 +1662129907238391808 +1662129907286392832 +1662129907331393792 +1662129907370394624 +1662129907412395520 +1662129907454396416 +1662129907499397376 +1662129907541398272 +1662129907583399168 +1662129907625400064 +1662129907670401024 +1662129907712401920 +1662129907760402944 +1662129907811404032 +1662129907853404928 +1662129907898405888 +1662129907937406720 +1662129907982407680 +1662129908027408640 +1662129908072409600 +1662129908123410688 +1662129908168411648 +1662129908216412672 +1662129908258413568 +1662129908303414528 +1662129908345415424 +1662129908387416320 +1662129908441417472 +1662129908498418688 +1662129908549419776 +1662129908591420672 +1662129908639421696 +1662129908687422720 +1662129908729423616 +1662129908771424512 +1662129908816425472 +1662129908858426368 +1662129908915427584 +1662129908960428544 +1662129909005429504 +1662129909050430464 +1662129909095431424 +1662129909140432384 +1662129909179433216 +1662129909221434112 +1662129909266435072 +1662129909305435904 +1662129909347436800 +1662129909392437760 +1662129909434438656 +1662129909479439616 +1662129909521440512 +1662129909572441600 +1662129909611442432 +1662129909653443328 +1662129909698444288 +1662129909740445184 +1662129909782446080 +1662129909824446976 +1662129909866447872 +1662129909905448704 +1662129909959449856 +1662129910001450752 +1662129910049451776 +1662129910091452672 +1662129910136453632 +1662129910181454592 +1662129910223455488 +1662129910265456384 +1662129910313457408 +1662129910364458496 +1662129910409459456 +1662129910448460288 +1662129910496461312 +1662129910541462272 +1662129910589463296 +1662129910634464256 +1662129910679465216 +1662129910718466048 +1662129910760466944 +1662129910808467968 +1662129910850468864 +1662129910892469760 +1662129910934470656 +1662129910985471744 +1662129911030472704 +1662129911072473600 +1662129911114474496 +1662129911162475520 +1662129911204476416 +1662129911255477504 +1662129911306478592 +1662129911348479488 +1662129911390480384 +1662129911429481216 +1662129911474482176 +1662129911519483136 +1662129911561484032 +1662129911606484992 +1662129911651485952 +1662129911693486848 +1662129911732487680 +1662129911774488576 +1662129911828489728 +1662129911876490752 +1662129911924491776 +1662129911975492864 +1662129912020493824 +1662129912062494720 +1662129912107495680 +1662129912155496704 +1662129912197497600 +1662129912239498496 +1662129912281499392 +1662129912326500352 +1662129912368501248 +1662129912413502208 +1662129912452503040 +1662129912497504000 +1662129912539504896 +1662129912584505856 +1662129912626506752 +1662129912671507712 +1662129912710508544 +1662129912755509504 +1662129912797510400 +1662129912839511296 +1662129912881512192 +1662129912926513152 +1662129912974514176 +1662129913019515136 +1662129913067516160 +1662129913121517312 +1662129913169518336 +1662129913211519232 +1662129913253520128 +1662129913301521152 +1662129913349522176 +1662129913391523072 +1662129913436524032 +1662129913484525056 +1662129913529526016 +1662129913574526976 +1662129913616527872 +1662129913667528960 +1662129913709529856 +1662129913751530752 +1662129913793531648 +1662129913844532736 +1662129913889533696 +1662129913931534592 +1662129913979535616 +1662129914030536704 +1662129914078537728 +1662129914123538688 +1662129914168539648 +1662129914219540736 +1662129914267541760 +1662129914318542848 +1662129914363543808 +1662129914411544832 +1662129914453545728 +1662129914495546624 +1662129914540547584 +1662129914588548608 +1662129914633549568 +1662129914681550592 +1662129914729551616 +1662129914777552640 +1662129914825553664 +1662129914867554560 +1662129914909555456 +1662129914960556544 +1662129915002557440 +1662129915047558400 +1662129915089559296 +1662129915134560256 +1662129915176561152 +1662129915218562048 +1662129915260562944 +1662129915302563840 +1662129915353564928 +1662129915395565824 +1662129915440566784 +1662129915485567744 +1662129915533568768 +1662129915575569664 +1662129915617570560 +1662129915659571456 +1662129915704572416 +1662129915752573440 +1662129915797574400 +1662129915839575296 +1662129915881576192 +1662129915929577216 +1662129915971578112 +1662129916016579072 +1662129916067580160 +1662129916118581248 +1662129916160582144 +1662129916205583104 +1662129916244583936 +1662129916295585024 +1662129916349586176 +1662129916394587136 +1662129916442588160 +1662129916487589120 +1662129916535590144 +1662129916586591232 +1662129916631592192 +1662129916673593088 +1662129916721594112 +1662129916766595072 +1662129916811596032 +1662129916868597248 +1662129916913598208 +1662129916958599168 +1662129917000600064 +1662129917051601152 +1662129917096602112 +1662129917147603200 +1662129917192604160 +1662129917234605056 +1662129917276605952 +1662129917318606848 +1662129917360607744 +1662129917402608640 +1662129917450609664 +1662129917504610816 +1662129917549611776 +1662129917594612736 +1662129917639613696 +1662129917681614592 +1662129917732615680 +1662129917780616704 +1662129917825617664 +1662129917873618688 +1662129917921619712 +1662129917960620544 +1662129918005621504 +1662129918044622336 +1662129918089623296 +1662129918137624320 +1662129918182625280 +1662129918239626496 +1662129918278627328 +1662129918320628224 +1662129918362629120 +1662129918407630080 +1662129918455631104 +1662129918506632192 +1662129918554633216 +1662129918596634112 +1662129918641635072 +1662129918692636160 +1662129918740637184 +1662129918782638080 +1662129918824638976 +1662129918869639936 +1662129918917640960 +1662129918968642048 +1662129919013643008 +1662129919055643904 +1662129919100644864 +1662129919145645824 +1662129919187646720 +1662129919226647552 +1662129919280648704 +1662129919325649664 +1662129919367650560 +1662129919415651584 +1662129919463652608 +1662129919505653504 +1662129919556654592 +1662129919601655552 +1662129919649656576 +1662129919694657536 +1662129919736658432 +1662129919781659392 +1662129919823660288 +1662129919865661184 +1662129919910662144 +1662129919952663040 +1662129919991663872 +1662129920033664768 +1662129920081665792 +1662129920126666752 +1662129920168667648 +1662129920219668736 +1662129920261669632 +1662129920303670528 +1662129920348671488 +1662129920396672512 +1662129920444673536 +1662129920483674368 +1662129920534675456 +1662129920582676480 +1662129920627677440 +1662129920669678336 +1662129920711679232 +1662129920753680128 +1662129920798681088 +1662129920846682112 +1662129920891683072 +1662129920933683968 +1662129920975684864 +1662129921020685824 +1662129921062686720 +1662129921107687680 +1662129921149688576 +1662129921191689472 +1662129921233690368 +1662129921278691328 +1662129921329692416 +1662129921368693248 +1662129921410694144 +1662129921461695232 +1662129921506696192 +1662129921551697152 +1662129921593698048 +1662129921635698944 +1662129921677699840 +1662129921728700928 +1662129921773701888 +1662129921812702720 +1662129921854703616 +1662129921893704448 +1662129921941705472 +1662129921986706432 +1662129922028707328 +1662129922070708224 +1662129922115709184 +1662129922157710080 +1662129922202711040 +1662129922253712128 +1662129922298713088 +1662129922340713984 +1662129922391715072 +1662129922442716160 +1662129922490717184 +1662129922541718272 +1662129922583719168 +1662129922625720064 +1662129922670721024 +1662129922715721984 +1662129922757722880 +1662129922808723968 +1662129922850724864 +1662129922892725760 +1662129922937726720 +1662129922982727680 +1662129923027728640 +1662129923069729536 +1662129923111730432 +1662129923153731328 +1662129923201732352 +1662129923252733440 +1662129923297734400 +1662129923345735424 +1662129923396736512 +1662129923441737472 +1662129923483738368 +1662129923528739328 +1662129923570740224 +1662129923612741120 +1662129923657742080 +1662129923696742912 +1662129923738743808 +1662129923786744832 +1662129923834745856 +1662129923879746816 +1662129923930747904 +1662129923981748992 +1662129924020749824 +1662129924062750720 +1662129924101751552 +1662129924146752512 +1662129924200753664 +1662129924239754496 +1662129924287755520 +1662129924329756416 +1662129924368757248 +1662129924413758208 +1662129924461759232 +1662129924503760128 +1662129924545761024 +1662129924593762048 +1662129924641763072 +1662129924683763968 +1662129924725764864 +1662129924776765952 +1662129924827767040 +1662129924869767936 +1662129924914768896 +1662129924959769856 +1662129925001770752 +1662129925043771648 +1662129925085772544 +1662129925127773440 +1662129925172774400 +1662129925217775360 +1662129925259776256 +1662129925298777088 +1662129925343778048 +1662129925385778944 +1662129925430779904 +1662129925469780736 +1662129925511781632 +1662129925559782656 +1662129925607783680 +1662129925652784640 +1662129925697785600 +1662129925748786688 +1662129925790787584 +1662129925835788544 +1662129925883789568 +1662129925925790464 +1662129925970791424 +1662129926012792320 +1662129926054793216 +1662129926096794112 +1662129926138795008 +1662129926180795904 +1662129926225796864 +1662129926267797760 +1662129926312798720 +1662129926351799552 +1662129926393800448 +1662129926438801408 +1662129926489802496 +1662129926537803520 +1662129926579804416 +1662129926621805312 +1662129926675806464 +1662129926720807424 +1662129926762808320 +1662129926807809280 +1662129926852810240 +1662129926900811264 +1662129926951812352 +1662129926996813312 +1662129927044814336 +1662129927095815424 +1662129927146816512 +1662129927188817408 +1662129927233818368 +1662129927275819264 +1662129927320820224 +1662129927362821120 +1662129927407822080 +1662129927455823104 +1662129927497824000 +1662129927542824960 +1662129927587825920 +1662129927632826880 +1662129927680827904 +1662129927728828928 +1662129927779830016 +1662129927833831168 +1662129927878832128 +1662129927920833024 +1662129927962833920 +1662129928007834880 +1662129928049835776 +1662129928103836928 +1662129928145837824 +1662129928187838720 +1662129928229839616 +1662129928271840512 +1662129928316841472 +1662129928364842496 +1662129928409843456 +1662129928457844480 +1662129928493845248 +1662129928544846336 +1662129928586847232 +1662129928631848192 +1662129928676849152 +1662129928724850176 +1662129928763851008 +1662129928808851968 +1662129928847852800 +1662129928892853760 +1662129928940854784 +1662129928982855680 +1662129929024856576 +1662129929066857472 +1662129929108858368 +1662129929150859264 +1662129929195860224 +1662129929237861120 +1662129929279862016 +1662129929321862912 +1662129929363863808 +1662129929402864640 +1662129929447865600 +1662129929498866688 +1662129929540867584 +1662129929582868480 +1662129929627869440 +1662129929681870592 +1662129929729871616 +1662129929780872704 +1662129929825873664 +1662129929867874560 +1662129929918875648 +1662129929963876608 +1662129930008877568 +1662129930050878464 +1662129930092879360 +1662129930134880256 +1662129930182881280 +1662129930227882240 +1662129930269883136 +1662129930317884160 +1662129930362885120 +1662129930413886208 +1662129930458887168 +1662129930503888128 +1662129930551889152 +1662129930593890048 +1662129930635890944 +1662129930677891840 +1662129930719892736 +1662129930767893760 +1662129930818894848 +1662129930869895936 +1662129930914896896 +1662129930965897984 +1662129931010898944 +1662129931052899840 +1662129931100900864 +1662129931142901760 +1662129931184902656 +1662129931223903488 +1662129931265904384 +1662129931307905280 +1662129931346906112 +1662129931388907008 +1662129931433907968 +1662129931478908928 +1662129931526909952 +1662129931571910912 +1662129931619911936 +1662129931670913024 +1662129931721914112 +1662129931766915072 +1662129931820916224 +1662129931862917120 +1662129931910918144 +1662129931952919040 +1662129931997920000 +1662129932042920960 +1662129932084921856 +1662129932132922880 +1662129932177923840 +1662129932225924864 +1662129932267925760 +1662129932315926784 +1662129932363927808 +1662129932405928704 +1662129932447929600 +1662129932489930496 +1662129932537931520 +1662129932579932416 +1662129932621933312 +1662129932666934272 +1662129932711935232 +1662129932756936192 +1662129932807937280 +1662129932846938112 +1662129932885938944 +1662129932933939968 +1662129932984941056 +1662129933029942016 +1662129933068942848 +1662129933113943808 +1662129933155944704 +1662129933203945728 +1662129933245946624 +1662129933284947456 +1662129933326948352 +1662129933371949312 +1662129933416950272 +1662129933464951296 +1662129933506952192 +1662129933551953152 +1662129933593954048 +1662129933635954944 +1662129933686956032 +1662129933731956992 +1662129933773957888 +1662129933821958912 +1662129933863959808 +1662129933908960768 +1662129933956961792 +1662129933998962688 +1662129934040963584 +1662129934085964544 +1662129934130965504 +1662129934181966592 +1662129934226967552 +1662129934268968448 +1662129934313969408 +1662129934364970496 +1662129934409971456 +1662129934451972352 +1662129934508973568 +1662129934556974592 +1662129934604975616 +1662129934646976512 +1662129934688977408 +1662129934736978432 +1662129934778979328 +1662129934820980224 +1662129934862981120 +1662129934904982016 +1662129934946982912 +1662129934988983808 +1662129935033984768 +1662129935078985728 +1662129935120986624 +1662129935162987520 +1662129935204988416 +1662129935246989312 +1662129935294990336 +1662129935348991488 +1662129935399992576 +1662129935441993472 +1662129935483994368 +1662129935528995328 +1662129935570996224 +1662129935615997184 +1662129935657998080 +1662129935696998912 +1662129935738999808 +1662129935781000704 +1662129935826001664 +1662129935868002560 +1662129935910003456 +1662129935955004416 +1662129936000005376 +1662129936048006400 +1662129936099007488 +1662129936141008384 +1662129936192009472 +1662129936240010496 +1662129936285011456 +1662129936327012352 +1662129936369013248 +1662129936414014208 +1662129936471015424 +1662129936513016320 +1662129936564017408 +1662129936609018368 +1662129936654019328 +1662129936696020224 +1662129936738021120 +1662129936783022080 +1662129936825022976 +1662129936867023872 +1662129936912024832 +1662129936951025664 +1662129936993026560 +1662129937035027456 +1662129937086028544 +1662129937131029504 +1662129937176030464 +1662129937218031360 +1662129937260032256 +1662129937305033216 +1662129937353034240 +1662129937395035136 +1662129937437036032 +1662129937479036928 +1662129937524037888 +1662129937569038848 +1662129937608039680 +1662129937653040640 +1662129937701041664 +1662129937752042752 +1662129937797043712 +1662129937839044608 +1662129937881045504 +1662129937923046400 +1662129937974047488 +1662129938019048448 +1662129938073049600 +1662129938118050560 +1662129938169051648 +1662129938211052544 +1662129938259053568 +1662129938304054528 +1662129938349055488 +1662129938391056384 +1662129938436057344 +1662129938484058368 +1662129938532059392 +1662129938574060288 +1662129938619061248 +1662129938661062144 +1662129938703063040 +1662129938745063936 +1662129938787064832 +1662129938832065792 +1662129938871066624 +1662129938913067520 +1662129938961068544 +1662129939006069504 +1662129939048070400 +1662129939096071424 +1662129939135072256 +1662129939186073344 +1662129939231074304 +1662129939273075200 +1662129939315076096 +1662129939360077056 +1662129939408078080 +1662129939450078976 +1662129939492079872 +1662129939534080768 +1662129939579081728 +1662129939621082624 +1662129939669083648 +1662129939714084608 +1662129939759085568 +1662129939804086528 +1662129939843087360 +1662129939888088320 +1662129939933089280 +1662129939975090176 +1662129940017091072 +1662129940062092032 +1662129940107092992 +1662129940149093888 +1662129940191094784 +1662129940236095744 +1662129940275096576 +1662129940317097472 +1662129940359098368 +1662129940404099328 +1662129940452100352 +1662129940500101376 +1662129940539102208 +1662129940581103104 +1662129940629104128 +1662129940671105024 +1662129940716105984 +1662129940764107008 +1662129940812108032 +1662129940854108928 +1662129940896109824 +1662129940938110720 +1662129940980111616 +1662129941019112448 +1662129941061113344 +1662129941103114240 +1662129941148115200 +1662129941187116032 +1662129941235117056 +1662129941277117952 +1662129941322118912 +1662129941364119808 +1662129941406120704 +1662129941448121600 +1662129941496122624 +1662129941541123584 +1662129941586124544 +1662129941628125440 +1662129941685126656 +1662129941733127680 +1662129941778128640 +1662129941823129600 +1662129941865130496 +1662129941910131456 +1662129941967132672 +1662129942012133632 +1662129942051134464 +1662129942093135360 +1662129942135136256 +1662129942174137088 +1662129942216137984 +1662129942258138880 +1662129942297139712 +1662129942339140608 +1662129942390141696 +1662129942429142528 +1662129942471143424 +1662129942513144320 +1662129942558145280 +1662129942600146176 +1662129942639147008 +1662129942681147904 +1662129942723148800 +1662129942771149824 +1662129942810150656 +1662129942864151808 +1662129942906152704 +1662129942957153792 +1662129943005154816 +1662129943047155712 +1662129943086156544 +1662129943128157440 +1662129943167158272 +1662129943215159296 +1662129943257160192 +1662129943299161088 +1662129943344162048 +1662129943395163136 +1662129943440164096 +1662129943482164992 +1662129943527165952 +1662129943578167040 +1662129943623168000 +1662129943671169024 +1662129943710169856 +1662129943752170752 +1662129943797171712 +1662129943845172736 +1662129943893173760 +1662129943935174656 +1662129943977175552 +1662129944022176512 +1662129944064177408 +1662129944109178368 +1662129944151179264 +1662129944199180288 +1662129944247181312 +1662129944295182336 +1662129944337183232 +1662129944379184128 +1662129944421185024 +1662129944466185984 +1662129944511186944 +1662129944553187840 +1662129944595188736 +1662129944643189760 +1662129944685190656 +1662129944730191616 +1662129944772192512 +1662129944814193408 +1662129944859194368 +1662129944904195328 +1662129944946196224 +1662129944997197312 +1662129945039198208 +1662129945087199232 +1662129945135200256 +1662129945177201152 +1662129945222202112 +1662129945273203200 +1662129945324204288 +1662129945375205376 +1662129945426206464 +1662129945468207360 +1662129945510208256 +1662129945558209280 +1662129945609210368 +1662129945654211328 +1662129945696212224 +1662129945738213120 +1662129945783214080 +1662129945825214976 +1662129945873216000 +1662129945927217152 +1662129945966217984 +1662129946014219008 +1662129946059219968 +1662129946107220992 +1662129946155222016 +1662129946197222912 +1662129946242223872 +1662129946290224896 +1662129946332225792 +1662129946377226752 +1662129946425227776 +1662129946479228928 +1662129946521229824 +1662129946563230720 +1662129946608231680 +1662129946650232576 +1662129946692233472 +1662129946737234432 +1662129946782235392 +1662129946824236288 +1662129946866237184 +1662129946911238144 +1662129946956239104 +1662129946998240000 +1662129947040240896 +1662129947082241792 +1662129947124242688 +1662129947169243648 +1662129947211244544 +1662129947250245376 +1662129947292246272 +1662129947346247424 +1662129947391248384 +1662129947433249280 +1662129947478250240 +1662129947526251264 +1662129947574252288 +1662129947619253248 +1662129947667254272 +1662129947709255168 +1662129947754256128 +1662129947796257024 +1662129947841257984 +1662129947895259136 +1662129947940260096 +1662129947982260992 +1662129948033262080 +1662129948084263168 +1662129948129264128 +1662129948174265088 +1662129948219266048 +1662129948261266944 +1662129948312268032 +1662129948360269056 +1662129948402269952 +1662129948441270784 +1662129948486271744 +1662129948528272640 +1662129948570273536 +1662129948618274560 +1662129948660275456 +1662129948702276352 +1662129948750277376 +1662129948798278400 +1662129948840279296 +1662129948885280256 +1662129948927281152 +1662129948969282048 +1662129949011282944 +1662129949056283904 +1662129949095284736 +1662129949137285632 +1662129949185286656 +1662129949230287616 +1662129949272288512 +1662129949314289408 +1662129949356290304 +1662129949401291264 +1662129949443292160 +1662129949488293120 +1662129949533294080 +1662129949575294976 +1662129949617295872 +1662129949668296960 +1662129949710297856 +1662129949758298880 +1662129949800299776 +1662129949842300672 +1662129949884301568 +1662129949929302528 +1662129949977303552 +1662129950022304512 +1662129950067305472 +1662129950106306304 +1662129950148307200 +1662129950193308160 +1662129950235309056 +1662129950283310080 +1662129950328311040 +1662129950370311936 +1662129950415312896 +1662129950463313920 +1662129950505314816 +1662129950559315968 +1662129950601316864 +1662129950661318144 +1662129950706319104 +1662129950763320320 +1662129950808321280 +1662129950850322176 +1662129950892323072 +1662129950931323904 +1662129950982324992 +1662129951027325952 +1662129951069326848 +1662129951111327744 +1662129951156328704 +1662129951198329600 +1662129951240330496 +1662129951291331584 +1662129951333332480 +1662129951384333568 +1662129951429334528 +1662129951471335424 +1662129951516336384 +1662129951561337344 +1662129951606338304 +1662129951648339200 +1662129951693340160 +1662129951735341056 +1662129951780342016 +1662129951825342976 +1662129951867343872 +1662129951909344768 +1662129951954345728 +1662129951996346624 +1662129952044347648 +1662129952086348544 +1662129952128349440 +1662129952179350528 +1662129952221351424 +1662129952263352320 +1662129952305353216 +1662129952350354176 +1662129952386354944 +1662129952434355968 +1662129952479356928 +1662129952524357888 +1662129952572358912 +1662129952617359872 +1662129952665360896 +1662129952707361792 +1662129952752362752 +1662129952797363712 +1662129952842364672 +1662129952887365632 +1662129952929366528 +1662129952971367424 +1662129953016368384 +1662129953058369280 +1662129953106370304 +1662129953154371328 +1662129953199372288 +1662129953247373312 +1662129953298374400 +1662129953340375296 +1662129953394376448 +1662129953436377344 +1662129953475378176 +1662129953514379008 +1662129953568380160 +1662129953613381120 +1662129953655382016 +1662129953700382976 +1662129953739383808 +1662129953781384704 +1662129953826385664 +1662129953865386496 +1662129953907387392 +1662129953955388416 +1662129954000389376 +1662129954051390464 +1662129954093391360 +1662129954138392320 +1662129954183393280 +1662129954225394176 +1662129954267395072 +1662129954306395904 +1662129954354396928 +1662129954399397888 +1662129954441398784 +1662129954489399808 +1662129954531400704 +1662129954579401728 +1662129954630402816 +1662129954672403712 +1662129954714404608 +1662129954756405504 +1662129954798406400 +1662129954840407296 +1662129954888408320 +1662129954930409216 +1662129954975410176 +1662129955023411200 +1662129955071412224 +1662129955116413184 +1662129955158414080 +1662129955206415104 +1662129955254416128 +1662129955299417088 +1662129955344418048 +1662129955386418944 +1662129955428419840 +1662129955473420800 +1662129955518421760 +1662129955560422656 +1662129955608423680 +1662129955659424768 +1662129955701425664 +1662129955746426624 +1662129955800427776 +1662129955845428736 +1662129955887429632 +1662129955929430528 +1662129955968431360 +1662129956010432256 +1662129956052433152 +1662129956094434048 +1662129956139435008 +1662129956184435968 +1662129956226436864 +1662129956268437760 +1662129956313438720 +1662129956358439680 +1662129956406440704 +1662129956445441536 +1662129956490442496 +1662129956535443456 +1662129956583444480 +1662129956634445568 +1662129956676446464 +1662129956718447360 +1662129956760448256 +1662129956802449152 +1662129956850450176 +1662129956889451008 +1662129956931451904 +1662129956973452800 +1662129957015453696 +1662129957057454592 +1662129957102455552 +1662129957150456576 +1662129957198457600 +1662129957240458496 +1662129957288459520 +1662129957330460416 +1662129957378461440 +1662129957420462336 +1662129957462463232 +1662129957510464256 +1662129957555465216 +1662129957597466112 +1662129957642467072 +1662129957687468032 +1662129957729468928 +1662129957777469952 +1662129957825470976 +1662129957867471872 +1662129957912472832 +1662129957954473728 +1662129957999474688 +1662129958044475648 +1662129958089476608 +1662129958131477504 +1662129958191478784 +1662129958233479680 +1662129958278480640 +1662129958320481536 +1662129958362482432 +1662129958407483392 +1662129958452484352 +1662129958500485376 +1662129958545486336 +1662129958581487104 +1662129958626488064 +1662129958668488960 +1662129958710489856 +1662129958752490752 +1662129958797491712 +1662129958842492672 +1662129958884493568 +1662129958929494528 +1662129958971495424 +1662129959013496320 +1662129959055497216 +1662129959100498176 +1662129959142499072 +1662129959187500032 +1662129959229500928 +1662129959271501824 +1662129959313502720 +1662129959355503616 +1662129959397504512 +1662129959448505600 +1662129959499506688 +1662129959544507648 +1662129959589508608 +1662129959634509568 +1662129959679510528 +1662129959721511424 +1662129959766512384 +1662129959817513472 +1662129959859514368 +1662129959910515456 +1662129959955516416 +1662129959997517312 +1662129960039518208 +1662129960081519104 +1662129960123520000 +1662129960174521088 +1662129960219522048 +1662129960267523072 +1662129960309523968 +1662129960363525120 +1662129960405526016 +1662129960447526912 +1662129960489527808 +1662129960531528704 +1662129960576529664 +1662129960624530688 +1662129960666531584 +1662129960708532480 +1662129960750533376 +1662129960792534272 +1662129960831535104 +1662129960876536064 +1662129960921537024 +1662129960966537984 +1662129961005538816 +1662129961047539712 +1662129961092540672 +1662129961134541568 +1662129961179542528 +1662129961221543424 +1662129961263544320 +1662129961305545216 +1662129961350546176 +1662129961401547264 +1662129961443548160 +1662129961482548992 +1662129961524549888 +1662129961572550912 +1662129961614551808 +1662129961656552704 +1662129961698553600 +1662129961740554496 +1662129961779555328 +1662129961818556160 +1662129961860557056 +1662129961908558080 +1662129961953559040 +1662129961995559936 +1662129962037560832 +1662129962082561792 +1662129962124562688 +1662129962163563520 +1662129962205564416 +1662129962247565312 +1662129962289566208 +1662129962334567168 +1662129962385568256 +1662129962445569536 +1662129962496570624 +1662129962538571520 +1662129962583572480 +1662129962628573440 +1662129962676574464 +1662129962715575296 +1662129962757576192 +1662129962802577152 +1662129962847578112 +1662129962892579072 +1662129962943580160 +1662129962988581120 +1662129963039582208 +1662129963081583104 +1662129963126584064 +1662129963174585088 +1662129963216585984 +1662129963264587008 +1662129963306587904 +1662129963348588800 +1662129963390589696 +1662129963435590656 +1662129963477591552 +1662129963519592448 +1662129963561593344 +1662129963603594240 +1662129963648595200 +1662129963687596032 +1662129963729596928 +1662129963771597824 +1662129963822598912 +1662129963867599872 +1662129963909600768 +1662129963954601728 +1662129964005602816 +1662129964047603712 +1662129964101604864 +1662129964143605760 +1662129964188606720 +1662129964230607616 +1662129964275608576 +1662129964317609472 +1662129964359610368 +1662129964401611264 +1662129964446612224 +1662129964497613312 +1662129964539614208 +1662129964581615104 +1662129964626616064 +1662129964671617024 +1662129964713617920 +1662129964755618816 +1662129964800619776 +1662129964842620672 +1662129964887621632 +1662129964929622528 +1662129964977623552 +1662129965019624448 +1662129965067625472 +1662129965112626432 +1662129965157627392 +1662129965199628288 +1662129965253629440 +1662129965295630336 +1662129965334631168 +1662129965382632192 +1662129965427633152 +1662129965472634112 +1662129965514635008 +1662129965559635968 +1662129965604636928 +1662129965649637888 +1662129965694638848 +1662129965736639744 +1662129965784640768 +1662129965829641728 +1662129965880642816 +1662129965922643712 +1662129965964644608 +1662129966012645632 +1662129966054646528 +1662129966093647360 +1662129966138648320 +1662129966183649280 +1662129966228650240 +1662129966273651200 +1662129966324652288 +1662129966375653376 +1662129966420654336 +1662129966471655424 +1662129966516656384 +1662129966561657344 +1662129966606658304 +1662129966651659264 +1662129966696660224 +1662129966738661120 +1662129966780662016 +1662129966828663040 +1662129966870663936 +1662129966912664832 +1662129966954665728 +1662129966996666624 +1662129967041667584 +1662129967086668544 +1662129967128669440 +1662129967170670336 +1662129967209671168 +1662129967257672192 +1662129967296673024 +1662129967338673920 +1662129967386674944 +1662129967425675776 +1662129967467676672 +1662129967518677760 +1662129967560678656 +1662129967602679552 +1662129967647680512 +1662129967689681408 +1662129967731682304 +1662129967773683200 +1662129967818684160 +1662129967860685056 +1662129967905686016 +1662129967947686912 +1662129967992687872 +1662129968037688832 +1662129968088689920 +1662129968127690752 +1662129968172691712 +1662129968220692736 +1662129968271693824 +1662129968313694720 +1662129968355695616 +1662129968394696448 +1662129968433697280 +1662129968475698176 +1662129968517699072 +1662129968571700224 +1662129968622701312 +1662129968673702400 +1662129968715703296 +1662129968757704192 +1662129968805705216 +1662129968850706176 +1662129968895707136 +1662129968937708032 +1662129968979708928 +1662129969021709824 +1662129969063710720 +1662129969105711616 +1662129969162712832 +1662129969201713664 +1662129969252714752 +1662129969297715712 +1662129969339716608 +1662129969381717504 +1662129969423718400 +1662129969465719296 +1662129969513720320 +1662129969555721216 +1662129969600722176 +1662129969648723200 +1662129969690724096 +1662129969738725120 +1662129969783726080 +1662129969825726976 +1662129969870727936 +1662129969918728960 +1662129969966729984 +1662129970008730880 +1662129970059731968 +1662129970104732928 +1662129970149733888 +1662129970194734848 +1662129970242735872 +1662129970284736768 +1662129970335737856 +1662129970377738752 +1662129970419739648 +1662129970461740544 +1662129970503741440 +1662129970545742336 +1662129970590743296 +1662129970635744256 +1662129970677745152 +1662129970719746048 +1662129970764747008 +1662129970806747904 +1662129970851748864 +1662129970896749824 +1662129970941750784 +1662129970995751936 +1662129971043752960 +1662129971088753920 +1662129971136754944 +1662129971178755840 +1662129971220756736 +1662129971265757696 +1662129971313758720 +1662129971355759616 +1662129971403760640 +1662129971445761536 +1662129971496762624 +1662129971538763520 +1662129971583764480 +1662129971643765760 +1662129971682766592 +1662129971724767488 +1662129971769768448 +1662129971811769344 +1662129971859770368 +1662129971901771264 +1662129971943772160 +1662129971982772992 +1662129972024773888 +1662129972066774784 +1662129972108775680 +1662129972153776640 +1662129972195777536 +1662129972240778496 +1662129972285779456 +1662129972327780352 +1662129972369781248 +1662129972414782208 +1662129972456783104 +1662129972501784064 +1662129972540784896 +1662129972582785792 +1662129972627786752 +1662129972669787648 +1662129972717788672 +1662129972762789632 +1662129972804790528 +1662129972852791552 +1662129972894792448 +1662129972939793408 +1662129972981794304 +1662129973020795136 +1662129973062796032 +1662129973113797120 +1662129973155798016 +1662129973197798912 +1662129973239799808 +1662129973281800704 +1662129973323801600 +1662129973368802560 +1662129973416803584 +1662129973461804544 +1662129973506805504 +1662129973548806400 +1662129973590807296 +1662129973632808192 +1662129973674809088 +1662129973722810112 +1662129973773811200 +1662129973818812160 +1662129973866813184 +1662129973911814144 +1662129973953815040 +1662129973998816000 +1662129974040816896 +1662129974082817792 +1662129974124818688 +1662129974169819648 +1662129974211820544 +1662129974253821440 +1662129974295822336 +1662129974349823488 +1662129974391824384 +1662129974436825344 +1662129974481826304 +1662129974523827200 +1662129974580828416 +1662129974622829312 +1662129974667830272 +1662129974709831168 +1662129974754832128 +1662129974799833088 +1662129974844834048 +1662129974886834944 +1662129974940836096 +1662129974985837056 +1662129975027837952 +1662129975072838912 +1662129975114839808 +1662129975156840704 +1662129975201841664 +1662129975249842688 +1662129975291843584 +1662129975336844544 +1662129975384845568 +1662129975426846464 +1662129975471847424 +1662129975510848256 +1662129975561849344 +1662129975606850304 +1662129975657851392 +1662129975702852352 +1662129975747853312 +1662129975789854208 +1662129975834855168 +1662129975873856000 +1662129975918856960 +1662129975972858112 +1662129976017859072 +1662129976065860096 +1662129976110861056 +1662129976152861952 +1662129976197862912 +1662129976245863936 +1662129976287864832 +1662129976329865728 +1662129976377866752 +1662129976422867712 +1662129976473868800 +1662129976512869632 +1662129976557870592 +1662129976602871552 +1662129976644872448 +1662129976689873408 +1662129976731874304 +1662129976770875136 +1662129976812876032 +1662129976857876992 +1662129976896877824 +1662129976938878720 +1662129976983879680 +1662129977025880576 +1662129977070881536 +1662129977115882496 +1662129977154883328 +1662129977199884288 +1662129977250885376 +1662129977295886336 +1662129977334887168 +1662129977373888000 +1662129977415888896 +1662129977457889792 +1662129977499890688 +1662129977541891584 +1662129977583892480 +1662129977625893376 +1662129977670894336 +1662129977715895296 +1662129977757896192 +1662129977799897088 +1662129977844898048 +1662129977886898944 +1662129977937900032 +1662129977982900992 +1662129978030902016 +1662129978072902912 +1662129978111903744 +1662129978153904640 +1662129978201905664 +1662129978249906688 +1662129978297907712 +1662129978339908608 +1662129978381909504 +1662129978426910464 +1662129978477911552 +1662129978525912576 +1662129978567913472 +1662129978606914304 +1662129978648915200 +1662129978690916096 +1662129978732916992 +1662129978777917952 +1662129978822918912 +1662129978870919936 +1662129978921921024 +1662129978966921984 +1662129979014923008 +1662129979062924032 +1662129979104924928 +1662129979146925824 +1662129979188926720 +1662129979230927616 +1662129979272928512 +1662129979314929408 +1662129979353930240 +1662129979395931136 +1662129979437932032 +1662129979476932864 +1662129979521933824 +1662129979566934784 +1662129979611935744 +1662129979656936704 +1662129979704937728 +1662129979746938624 +1662129979788939520 +1662129979836940544 +1662129979875941376 +1662129979917942272 +1662129979956943104 +1662129980007944192 +1662129980052945152 +1662129980094946048 +1662129980139947008 +1662129980190948096 +1662129980232948992 +1662129980274949888 +1662129980316950784 +1662129980358951680 +1662129980400952576 +1662129980442953472 +1662129980490954496 +1662129980535955456 +1662129980577956352 +1662129980616957184 +1662129980661958144 +1662129980703959040 +1662129980745959936 +1662129980793960960 +1662129980841961984 +1662129980883962880 +1662129980928963840 +1662129980976964864 +1662129981027965952 +1662129981072966912 +1662129981117967872 +1662129981159968768 +1662129981201969664 +1662129981246970624 +1662129981285971456 +1662129981327972352 +1662129981378973440 +1662129981423974400 +1662129981462975232 +1662129981501976064 +1662129981543976960 +1662129981582977792 +1662129981624978688 +1662129981669979648 +1662129981711980544 +1662129981750981376 +1662129981792982272 +1662129981834983168 +1662129981876984064 +1662129981933985280 +1662129981975986176 +1662129982017987072 +1662129982059987968 +1662129982104988928 +1662129982146989824 +1662129982185990656 +1662129982230991616 +1662129982272992512 +1662129982314993408 +1662129982356994304 +1662129982401995264 +1662129982452996352 +1662129982494997248 +1662129982533998080 +1662129982575998976 +1662129982620999936 +1662129982669000960 +1662129982720002048 +1662129982774003200 +1662129982816004096 +1662129982858004992 +1662129982900005888 +1662129982942006784 +1662129982987007744 +1662129983029008640 +1662129983071009536 +1662129983131010816 +1662129983173011712 +1662129983221012736 +1662129983269013760 +1662129983311014656 +1662129983353015552 +1662129983398016512 +1662129983443017472 +1662129983488018432 +1662129983533019392 +1662129983575020288 +1662129983620021248 +1662129983668022272 +1662129983710023168 +1662129983752024064 +1662129983791024896 +1662129983833025792 +1662129983872026624 +1662129983917027584 +1662129983959028480 +1662129984013029632 +1662129984058030592 +1662129984100031488 +1662129984142032384 +1662129984181033216 +1662129984226034176 +1662129984274035200 +1662129984319036160 +1662129984367037184 +1662129984409038080 +1662129984457039104 +1662129984496039936 +1662129984541040896 +1662129984583041792 +1662129984628042752 +1662129984670043648 +1662129984724044800 +1662129984766045696 +1662129984811046656 +1662129984850047488 +1662129984892048384 +1662129984937049344 +1662129984979050240 +1662129985024051200 +1662129985069052160 +1662129985108052992 +1662129985150053888 +1662129985195054848 +1662129985243055872 +1662129985297057024 +1662129985342057984 +1662129985387058944 +1662129985432059904 +1662129985480060928 +1662129985525061888 +1662129985567062784 +1662129985615063808 +1662129985660064768 +1662129985711065856 +1662129985753066752 +1662129985792067584 +1662129985837068544 +1662129985879069440 +1662129985927070464 +1662129985975071488 +1662129986017072384 +1662129986065073408 +1662129986104074240 +1662129986149075200 +1662129986194076160 +1662129986233076992 +1662129986275077888 +1662129986320078848 +1662129986362079744 +1662129986404080640 +1662129986446081536 +1662129986488082432 +1662129986527083264 +1662129986569084160 +1662129986614085120 +1662129986665086208 +1662129986707087104 +1662129986755088128 +1662129986800089088 +1662129986842089984 +1662129986881090816 +1662129986923091712 +1662129986968092672 +1662129987013093632 +1662129987055094528 +1662129987097095424 +1662129987139096320 +1662129987178097152 +1662129987220098048 +1662129987268099072 +1662129987310099968 +1662129987352100864 +1662129987394101760 +1662129987439102720 +1662129987481103616 +1662129987529104640 +1662129987574105600 +1662129987622106624 +1662129987664107520 +1662129987706108416 +1662129987745109248 +1662129987790110208 +1662129987835111168 +1662129987880112128 +1662129987922113024 +1662129987961113856 +1662129988006114816 +1662129988048115712 +1662129988090116608 +1662129988132117504 +1662129988180118528 +1662129988225119488 +1662129988267120384 +1662129988309121280 +1662129988348122112 +1662129988390123008 +1662129988432123904 +1662129988474124800 +1662129988513125632 +1662129988561126656 +1662129988600127488 +1662129988648128512 +1662129988696129536 +1662129988738130432 +1662129988780131328 +1662129988831132416 +1662129988873133312 +1662129988921134336 +1662129988966135296 +1662129989011136256 +1662129989053137152 +1662129989092137984 +1662129989134138880 +1662129989179139840 +1662129989227140864 +1662129989269141760 +1662129989311142656 +1662129989356143616 +1662129989401144576 +1662129989443145472 +1662129989491146496 +1662129989533147392 +1662129989587148544 +1662129989629149440 +1662129989683150592 +1662129989725151488 +1662129989770152448 +1662129989812153344 +1662129989857154304 +1662129989899155200 +1662129989944156160 +1662129989986157056 +1662129990037158144 +1662129990079159040 +1662129990118159872 +1662129990160160768 +1662129990208161792 +1662129990253162752 +1662129990298163712 +1662129990334164480 +1662129990379165440 +1662129990421166336 +1662129990466167296 +1662129990508168192 +1662129990550169088 +1662129990601170176 +1662129990646171136 +1662129990691172096 +1662129990736173056 +1662129990781174016 +1662129990823174912 +1662129990865175808 +1662129990907176704 +1662129990949177600 +1662129990988178432 +1662129991027179264 +1662129991072180224 +1662129991111181056 +1662129991150181888 +1662129991192182784 +1662129991234183680 +1662129991276184576 +1662129991321185536 +1662129991366186496 +1662129991420187648 +1662129991462188544 +1662129991501189376 +1662129991540190208 +1662129991579191040 +1662129991621191936 +1662129991663192832 +1662129991708193792 +1662129991750194688 +1662129991792195584 +1662129991834196480 +1662129991882197504 +1662129991924198400 +1662129991966199296 +1662129992008200192 +1662129992047201024 +1662129992089201920 +1662129992131202816 +1662129992170203648 +1662129992209204480 +1662129992251205376 +1662129992290206208 +1662129992335207168 +1662129992380208128 +1662129992422209024 +1662129992464209920 +1662129992506210816 +1662129992551211776 +1662129992599212800 +1662129992641213696 +1662129992686214656 +1662129992731215616 +1662129992773216512 +1662129992821217536 +1662129992860218368 +1662129992905219328 +1662129992947220224 +1662129992989221120 +1662129993031222016 +1662129993073222912 +1662129993115223808 +1662129993163224832 +1662129993208225792 +1662129993250226688 +1662129993298227712 +1662129993355228928 +1662129993397229824 +1662129993439230720 +1662129993481231616 +1662129993523232512 +1662129993562233344 +1662129993607234304 +1662129993649235200 +1662129993691236096 +1662129993733236992 +1662129993775237888 +1662129993826238976 +1662129993877240064 +1662129993922241024 +1662129993976242176 +1662129994027243264 +1662129994072244224 +1662129994114245120 +1662129994156246016 +1662129994198246912 +1662129994243247872 +1662129994285248768 +1662129994327249664 +1662129994372250624 +1662129994414251520 +1662129994456252416 +1662129994498253312 +1662129994537254144 +1662129994579255040 +1662129994627256064 +1662129994672257024 +1662129994717257984 +1662129994759258880 +1662129994798259712 +1662129994843260672 +1662129994882261504 +1662129994924262400 +1662129994966263296 +1662129995008264192 +1662129995056265216 +1662129995104266240 +1662129995155267328 +1662129995197268224 +1662129995242269184 +1662129995287270144 +1662129995329271040 +1662129995371271936 +1662129995419272960 +1662129995458273792 +1662129995500274688 +1662129995545275648 +1662129995593276672 +1662129995635277568 +1662129995677278464 +1662129995719279360 +1662129995761280256 +1662129995803281152 +1662129995845282048 +1662129995887282944 +1662129995932283904 +1662129995983284992 +1662129996025285888 +1662129996067286784 +1662129996115287808 +1662129996157288704 +1662129996202289664 +1662129996244290560 +1662129996295291648 +1662129996340292608 +1662129996397293824 +1662129996442294784 +1662129996493295872 +1662129996538296832 +1662129996580297728 +1662129996622298624 +1662129996667299584 +1662129996712300544 +1662129996754301440 +1662129996796302336 +1662129996838303232 +1662129996880304128 +1662129996928305152 +1662129996970306048 +1662129997009306880 +1662129997054307840 +1662129997102308864 +1662129997147309824 +1662129997192310784 +1662129997234311680 +1662129997279312640 +1662129997321313536 +1662129997363314432 +1662129997405315328 +1662129997447316224 +1662129997489317120 +1662129997531318016 +1662129997573318912 +1662129997615319808 +1662129997657320704 +1662129997702321664 +1662129997741322496 +1662129997783323392 +1662129997828324352 +1662129997870325248 +1662129997912326144 +1662129997954327040 +1662129997999328000 +1662129998050329088 +1662129998098330112 +1662129998140331008 +1662129998188332032 +1662129998230332928 +1662129998275333888 +1662129998320334848 +1662129998365335808 +1662129998407336704 +1662129998446337536 +1662129998491338496 +1662129998542339584 +1662129998584340480 +1662129998626341376 +1662129998668342272 +1662129998713343232 +1662129998764344320 +1662129998806345216 +1662129998845346048 +1662129998887346944 +1662129998926347776 +1662129998968348672 +1662129999010349568 +1662129999052350464 +1662129999094351360 +1662129999139352320 +1662129999181353216 +1662129999226354176 +1662129999274355200 +1662129999316356096 +1662129999358356992 +1662129999406358016 +1662129999448358912 +1662129999496359936 +1662129999538360832 +1662129999577361664 +1662129999616362496 +1662129999658363392 +1662129999697364224 +1662129999739365120 +1662129999778365952 +1662129999817366784 +1662129999874368000 +1662129999916368896 +1662129999958369792 +1662130000012370944 +1662130000057371904 +1662130000099372800 +1662130000147373824 +1662130000189374720 +1662130000240375808 +1662130000282376704 +1662130000327377664 +1662130000375378688 +1662130000420379648 +1662130000462380544 +1662130000504381440 +1662130000546382336 +1662130000588383232 +1662130000630384128 +1662130000672385024 +1662130000714385920 +1662130000762386944 +1662130000807387904 +1662130000855388928 +1662130000903389952 +1662130000948390912 +1662130000987391744 +1662130001029392640 +1662130001071393536 +1662130001113394432 +1662130001161395456 +1662130001203396352 +1662130001245397248 +1662130001299398400 +1662130001341399296 +1662130001389400320 +1662130001428401152 +1662130001479402240 +1662130001524403200 +1662130001572404224 +1662130001620405248 +1662130001662406144 +1662130001704407040 +1662130001746407936 +1662130001788408832 +1662130001830409728 +1662130001872410624 +1662130001911411456 +1662130001953412352 +1662130001995413248 +1662130002037414144 +1662130002079415040 +1662130002124416000 +1662130002169416960 +1662130002214417920 +1662130002256418816 +1662130002301419776 +1662130002349420800 +1662130002394421760 +1662130002436422656 +1662130002481423616 +1662130002523424512 +1662130002568425472 +1662130002610426368 +1662130002652427264 +1662130002697428224 +1662130002739429120 +1662130002781430016 +1662130002826430976 +1662130002874432000 +1662130002916432896 +1662130002955433728 +1662130003000434688 +1662130003039435520 +1662130003081436416 +1662130003126437376 +1662130003171438336 +1662130003213439232 +1662130003255440128 +1662130003297441024 +1662130003339441920 +1662130003381442816 +1662130003423443712 +1662130003465444608 +1662130003507445504 +1662130003549446400 +1662130003591447296 +1662130003639448320 +1662130003681449216 +1662130003723450112 +1662130003768451072 +1662130003813452032 +1662130003855452928 +1662130003900453888 +1662130003948454912 +1662130003993455872 +1662130004035456768 +1662130004077457664 +1662130004122458624 +1662130004164459520 +1662130004209460480 +1662130004257461504 +1662130004302462464 +1662130004344463360 +1662130004398464512 +1662130004437465344 +1662130004485466368 +1662130004530467328 +1662130004578468352 +1662130004626469376 +1662130004665470208 +1662130004710471168 +1662130004749472000 +1662130004791472896 +1662130004833473792 +1662130004875474688 +1662130004917475584 +1662130004959476480 +1662130005013477632 +1662130005058478592 +1662130005103479552 +1662130005145480448 +1662130005184481280 +1662130005223482112 +1662130005265483008 +1662130005319484160 +1662130005361485056 +1662130005406486016 +1662130005448486912 +1662130005496487936 +1662130005538488832 +1662130005580489728 +1662130005628490752 +1662130005679491840 +1662130005721492736 +1662130005763493632 +1662130005817494784 +1662130005859495680 +1662130005901496576 +1662130005952497664 +1662130005991498496 +1662130006030499328 +1662130006075500288 +1662130006126501376 +1662130006171502336 +1662130006213503232 +1662130006261504256 +1662130006303505152 +1662130006342505984 +1662130006390507008 +1662130006432507904 +1662130006480508928 +1662130006522509824 +1662130006573510912 +1662130006615511808 +1662130006660512768 +1662130006702513664 +1662130006744514560 +1662130006786515456 +1662130006828516352 +1662130006867517184 +1662130006912518144 +1662130006960519168 +1662130006999520000 +1662130007041520896 +1662130007083521792 +1662130007128522752 +1662130007179523840 +1662130007227524864 +1662130007272525824 +1662130007317526784 +1662130007356527616 +1662130007398528512 +1662130007440529408 +1662130007485530368 +1662130007527531264 +1662130007572532224 +1662130007614533120 +1662130007665534208 +1662130007707535104 +1662130007749536000 +1662130007800537088 +1662130007848538112 +1662130007893539072 +1662130007938540032 +1662130007977540864 +1662130008022541824 +1662130008064542720 +1662130008115543808 +1662130008160544768 +1662130008208545792 +1662130008253546752 +1662130008295547648 +1662130008340548608 +1662130008385549568 +1662130008424550400 +1662130008466551296 +1662130008508552192 +1662130008547553024 +1662130008589553920 +1662130008634554880 +1662130008676555776 +1662130008724556800 +1662130008763557632 +1662130008805558528 +1662130008847559424 +1662130008895560448 +1662130008937561344 +1662130008982562304 +1662130009024563200 +1662130009063564032 +1662130009111565056 +1662130009153565952 +1662130009198566912 +1662130009240567808 +1662130009282568704 +1662130009327569664 +1662130009375570688 +1662130009417571584 +1662130009468572672 +1662130009519573760 +1662130009561574656 +1662130009603575552 +1662130009645576448 +1662130009687577344 +1662130009732578304 +1662130009774579200 +1662130009816580096 +1662130009864581120 +1662130009912582144 +1662130009954583040 +1662130009996583936 +1662130010038584832 +1662130010080585728 +1662130010128586752 +1662130010170587648 +1662130010209588480 +1662130010248589312 +1662130010290590208 +1662130010332591104 +1662130010386592256 +1662130010434593280 +1662130010476594176 +1662130010521595136 +1662130010560595968 +1662130010602596864 +1662130010650597888 +1662130010695598848 +1662130010737599744 +1662130010788600832 +1662130010830601728 +1662130010875602688 +1662130010920603648 +1662130010968604672 +1662130011013605632 +1662130011058606592 +1662130011100607488 +1662130011142608384 +1662130011190609408 +1662130011229610240 +1662130011286611456 +1662130011331612416 +1662130011373613312 +1662130011415614208 +1662130011463615232 +1662130011508616192 +1662130011550617088 +1662130011592617984 +1662130011637618944 +1662130011679619840 +1662130011724620800 +1662130011766621696 +1662130011811622656 +1662130011856623616 +1662130011904624640 +1662130011946625536 +1662130011988626432 +1662130012030627328 +1662130012072628224 +1662130012114629120 +1662130012156630016 +1662130012198630912 +1662130012237631744 +1662130012279632640 +1662130012321633536 +1662130012369634560 +1662130012414635520 +1662130012456636416 +1662130012513637632 +1662130012555638528 +1662130012606639616 +1662130012648640512 +1662130012690641408 +1662130012732642304 +1662130012777643264 +1662130012819644160 +1662130012867645184 +1662130012912646144 +1662130012954647040 +1662130013002648064 +1662130013053649152 +1662130013095650048 +1662130013140651008 +1662130013185651968 +1662130013230652928 +1662130013275653888 +1662130013317654784 +1662130013365655808 +1662130013407656704 +1662130013455657728 +1662130013494658560 +1662130013542659584 +1662130013584660480 +1662130013626661376 +1662130013668662272 +1662130013713663232 +1662130013767664384 +1662130013812665344 +1662130013851666176 +1662130013902667264 +1662130013941668096 +1662130013983668992 +1662130014028669952 +1662130014070670848 +1662130014112671744 +1662130014154672640 +1662130014208673792 +1662130014259674880 +1662130014301675776 +1662130014352676864 +1662130014400677888 +1662130014442678784 +1662130014484679680 +1662130014523680512 +1662130014565681408 +1662130014610682368 +1662130014652683264 +1662130014700684288 +1662130014742685184 +1662130014787686144 +1662130014832687104 +1662130014874688000 +1662130014919688960 +1662130014976690176 +1662130015024691200 +1662130015072692224 +1662130015114693120 +1662130015156694016 +1662130015201694976 +1662130015240695808 +1662130015279696640 +1662130015321697536 +1662130015369698560 +1662130015420699648 +1662130015462700544 +1662130015504701440 +1662130015552702464 +1662130015594703360 +1662130015636704256 +1662130015678705152 +1662130015720706048 +1662130015768707072 +1662130015819708160 +1662130015861709056 +1662130015903709952 +1662130015945710848 +1662130015996711936 +1662130016038712832 +1662130016080713728 +1662130016128714752 +1662130016179715840 +1662130016221716736 +1662130016263717632 +1662130016308718592 +1662130016362719744 +1662130016401720576 +1662130016443721472 +1662130016482722304 +1662130016527723264 +1662130016569724160 +1662130016611725056 +1662130016668726272 +1662130016710727168 +1662130016761728256 +1662130016812729344 +1662130016854730240 +1662130016896731136 +1662130016938732032 +1662130016977732864 +1662130017022733824 +1662130017061734656 +1662130017103735552 +1662130017154736640 +1662130017202737664 +1662130017247738624 +1662130017289739520 +1662130017334740480 +1662130017379741440 +1662130017421742336 +1662130017469743360 +1662130017517744384 +1662130017559745280 +1662130017601746176 +1662130017649747200 +1662130017691748096 +1662130017733748992 +1662130017781750016 +1662130017826750976 +1662130017877752064 +1662130017922753024 +1662130017964753920 +1662130018006754816 +1662130018045755648 +1662130018093756672 +1662130018147757824 +1662130018189758720 +1662130018228759552 +1662130018273760512 +1662130018318761472 +1662130018357762304 +1662130018402763264 +1662130018447764224 +1662130018489765120 +1662130018528765952 +1662130018573766912 +1662130018618767872 +1662130018660768768 +1662130018702769664 +1662130018744770560 +1662130018795771648 +1662130018837772544 +1662130018888773632 +1662130018936774656 +1662130018978775552 +1662130019032776704 +1662130019077777664 +1662130019116778496 +1662130019161779456 +1662130019209780480 +1662130019248781312 +1662130019287782144 +1662130019335783168 +1662130019383784192 +1662130019425785088 +1662130019473786112 +1662130019515787008 +1662130019557787904 +1662130019596788736 +1662130019644789760 +1662130019683790592 +1662130019728791552 +1662130019776792576 +1662130019821793536 +1662130019863794432 +1662130019905795328 +1662130019950796288 +1662130019992797184 +1662130020055798528 +1662130020097799424 +1662130020145800448 +1662130020190801408 +1662130020232802304 +1662130020274803200 +1662130020316804096 +1662130020364805120 +1662130020412806144 +1662130020454807040 +1662130020505808128 +1662130020550809088 +1662130020592809984 +1662130020634810880 +1662130020682811904 +1662130020724812800 +1662130020769813760 +1662130020811814656 +1662130020859815680 +1662130020904816640 +1662130020946817536 +1662130021000818688 +1662130021045819648 +1662130021093820672 +1662130021138821632 +1662130021180822528 +1662130021222823424 +1662130021267824384 +1662130021315825408 +1662130021357826304 +1662130021399827200 +1662130021441828096 +1662130021483828992 +1662130021522829824 +1662130021570830848 +1662130021615831808 +1662130021666832896 +1662130021720834048 +1662130021768835072 +1662130021822836224 +1662130021873837312 +1662130021921838336 +1662130021969839360 +1662130022014840320 +1662130022059841280 +1662130022104842240 +1662130022143843072 +1662130022188844032 +1662130022230844928 +1662130022278845952 +1662130022323846912 +1662130022374848000 +1662130022416848896 +1662130022467849984 +1662130022512850944 +1662130022554851840 +1662130022599852800 +1662130022638853632 +1662130022680854528 +1662130022722855424 +1662130022764856320 +1662130022812857344 +1662130022854858240 +1662130022896859136 +1662130022947860224 +1662130022989861120 +1662130023034862080 +1662130023076862976 +1662130023112863744 +1662130023157864704 +1662130023199865600 +1662130023244866560 +1662130023292867584 +1662130023334868480 +1662130023376869376 +1662130023418870272 +1662130023463871232 +1662130023505872128 +1662130023556873216 +1662130023607874304 +1662130023655875328 +1662130023697876224 +1662130023739877120 +1662130023787878144 +1662130023829879040 +1662130023877880064 +1662130023925881088 +1662130023970882048 +1662130024012882944 +1662130024054883840 +1662130024096884736 +1662130024150885888 +1662130024195886848 +1662130024240887808 +1662130024279888640 +1662130024324889600 +1662130024369890560 +1662130024414891520 +1662130024456892416 +1662130024501893376 +1662130024546894336 +1662130024597895424 +1662130024645896448 +1662130024690897408 +1662130024732898304 +1662130024774899200 +1662130024816900096 +1662130024858900992 +1662130024903901952 +1662130024948902912 +1662130024999904000 +1662130025041904896 +1662130025080905728 +1662130025128906752 +1662130025170907648 +1662130025224908800 +1662130025263909632 +1662130025302910464 +1662130025353911552 +1662130025398912512 +1662130025443913472 +1662130025485914368 +1662130025527915264 +1662130025569916160 +1662130025611917056 +1662130025647917824 +1662130025689918720 +1662130025734919680 +1662130025776920576 +1662130025824921600 +1662130025866922496 +1662130025908923392 +1662130025947924224 +1662130025989925120 +1662130026031926016 +1662130026076926976 +1662130026118927872 +1662130026163928832 +1662130026202929664 +1662130026244930560 +1662130026289931520 +1662130026337932544 +1662130026382933504 +1662130026424934400 +1662130026466935296 +1662130026508936192 +1662130026553937152 +1662130026595938048 +1662130026640939008 +1662130026682939904 +1662130026721940736 +1662130026763941632 +1662130026811942656 +1662130026856943616 +1662130026904944640 +1662130026955945728 +1662130026994946560 +1662130027039947520 +1662130027081948416 +1662130027117949184 +1662130027165950208 +1662130027207951104 +1662130027249952000 +1662130027297953024 +1662130027351954176 +1662130027396955136 +1662130027444956160 +1662130027489957120 +1662130027537958144 +1662130027579959040 +1662130027621959936 +1662130027660960768 +1662130027711961856 +1662130027753962752 +1662130027795963648 +1662130027837964544 +1662130027885965568 +1662130027930966528 +1662130027975967488 +1662130028026968576 +1662130028068969472 +1662130028113970432 +1662130028161971456 +1662130028209972480 +1662130028257973504 +1662130028296974336 +1662130028341975296 +1662130028383976192 +1662130028428977152 +1662130028473978112 +1662130028521979136 +1662130028563980032 +1662130028605980928 +1662130028647981824 +1662130028689982720 +1662130028731983616 +1662130028779984640 +1662130028815985408 +1662130028863986432 +1662130028908987392 +1662130028956988416 +1662130028998989312 +1662130029043990272 +1662130029085991168 +1662130029136992256 +1662130029178993152 +1662130029226994176 +1662130029271995136 +1662130029307995904 +1662130029352996864 +1662130029388997632 +1662130029433998592 +1662130029475999488 +1662130029518000384 +1662130029560001280 +1662130029605002240 +1662130029650003200 +1662130029692004096 +1662130029740005120 +1662130029782006016 +1662130029827006976 +1662130029872007936 +1662130029914008832 +1662130029959009792 +1662130030004010752 +1662130030058011904 +1662130030100012800 +1662130030145013760 +1662130030193014784 +1662130030238015744 +1662130030277016576 +1662130030319017472 +1662130030364018432 +1662130030406019328 +1662130030448020224 +1662130030496021248 +1662130030538022144 +1662130030583023104 +1662130030628024064 +1662130030676025088 +1662130030721026048 +1662130030763026944 +1662130030811027968 +1662130030856028928 +1662130030904029952 +1662130030952030976 +1662130030997031936 +1662130031045032960 +1662130031087033856 +1662130031126034688 +1662130031171035648 +1662130031213036544 +1662130031261037568 +1662130031306038528 +1662130031354039552 +1662130031396040448 +1662130031441041408 +1662130031480042240 +1662130031522043136 +1662130031567044096 +1662130031615045120 +1662130031660046080 +1662130031702046976 +1662130031744047872 +1662130031786048768 +1662130031831049728 +1662130031879050752 +1662130031921051648 +1662130031972052736 +1662130032020053760 +1662130032059054592 +1662130032110055680 +1662130032152056576 +1662130032191057408 +1662130032233058304 +1662130032278059264 +1662130032326060288 +1662130032368061184 +1662130032410062080 +1662130032452062976 +1662130032491063808 +1662130032530064640 +1662130032575065600 +1662130032617066496 +1662130032659067392 +1662130032701068288 +1662130032743069184 +1662130032782070016 +1662130032827070976 +1662130032869071872 +1662130032917072896 +1662130032959073792 +1662130033004074752 +1662130033046075648 +1662130033088076544 +1662130033133077504 +1662130033181078528 +1662130033226079488 +1662130033271080448 +1662130033319081472 +1662130033364082432 +1662130033406083328 +1662130033445084160 +1662130033493085184 +1662130033535086080 +1662130033577086976 +1662130033619087872 +1662130033661088768 +1662130033709089792 +1662130033751090688 +1662130033796091648 +1662130033838092544 +1662130033889093632 +1662130033931094528 +1662130033976095488 +1662130034018096384 +1662130034066097408 +1662130034108098304 +1662130034150099200 +1662130034195100160 +1662130034240101120 +1662130034285102080 +1662130034324102912 +1662130034366103808 +1662130034411104768 +1662130034453105664 +1662130034501106688 +1662130034543107584 +1662130034579108352 +1662130034621109248 +1662130034663110144 +1662130034708111104 +1662130034756112128 +1662130034798113024 +1662130034846114048 +1662130034888114944 +1662130034930115840 +1662130034969116672 +1662130035017117696 +1662130035059118592 +1662130035104119552 +1662130035149120512 +1662130035194121472 +1662130035236122368 +1662130035278123264 +1662130035323124224 +1662130035362125056 +1662130035404125952 +1662130035452126976 +1662130035500128000 +1662130035551129088 +1662130035593129984 +1662130035638130944 +1662130035686131968 +1662130035734132992 +1662130035776133888 +1662130035821134848 +1662130035863135744 +1662130035911136768 +1662130035953137664 +1662130036004138752 +1662130036046139648 +1662130036094140672 +1662130036139141632 +1662130036190142720 +1662130036235143680 +1662130036277144576 +1662130036328145664 +1662130036370146560 +1662130036415147520 +1662130036463148544 +1662130036502149376 +1662130036547150336 +1662130036586151168 +1662130036628152064 +1662130036676153088 +1662130036718153984 +1662130036760154880 +1662130036802155776 +1662130036844156672 +1662130036889157632 +1662130036931158528 +1662130036982159616 +1662130037021160448 +1662130037063161344 +1662130037105162240 +1662130037141163008 +1662130037183163904 +1662130037228164864 +1662130037270165760 +1662130037312166656 +1662130037354167552 +1662130037405168640 +1662130037450169600 +1662130037495170560 +1662130037537171456 +1662130037576172288 +1662130037627173376 +1662130037672174336 +1662130037711175168 +1662130037753176064 +1662130037795176960 +1662130037837177856 +1662130037885178880 +1662130037930179840 +1662130037972180736 +1662130038020181760 +1662130038059182592 +1662130038110183680 +1662130038161184768 +1662130038203185664 +1662130038251186688 +1662130038296187648 +1662130038341188608 +1662130038392189696 +1662130038434190592 +1662130038476191488 +1662130038524192512 +1662130038566193408 +1662130038614194432 +1662130038665195520 +1662130038713196544 +1662130038758197504 +1662130038800198400 +1662130038839199232 +1662130038881200128 +1662130038935201280 +1662130038980202240 +1662130039022203136 +1662130039064204032 +1662130039109204992 +1662130039154205952 +1662130039196206848 +1662130039241207808 +1662130039286208768 +1662130039325209600 +1662130039364210432 +1662130039412211456 +1662130039457212416 +1662130039499213312 +1662130039544214272 +1662130039592215296 +1662130039637216256 +1662130039679217152 +1662130039724218112 +1662130039769219072 +1662130039811219968 +1662130039853220864 +1662130039901221888 +1662130039946222848 +1662130039988223744 +1662130040027224576 +1662130040078225664 +1662130040132226816 +1662130040174227712 +1662130040213228544 +1662130040255229440 +1662130040294230272 +1662130040336231168 +1662130040375232000 +1662130040420232960 +1662130040468233984 +1662130040516235008 +1662130040558235904 +1662130040603236864 +1662130040648237824 +1662130040693238784 +1662130040738239744 +1662130040789240832 +1662130040828241664 +1662130040870242560 +1662130040912243456 +1662130040954244352 +1662130040999245312 +1662130041044246272 +1662130041089247232 +1662130041128248064 +1662130041170248960 +1662130041212249856 +1662130041254250752 +1662130041299251712 +1662130041341252608 +1662130041383253504 +1662130041428254464 +1662130041467255296 +1662130041518256384 +1662130041563257344 +1662130041608258304 +1662130041653259264 +1662130041698260224 +1662130041749261312 +1662130041785262080 +1662130041830263040 +1662130041872263936 +1662130041914264832 +1662130041971266048 +1662130042013266944 +1662130042061267968 +1662130042103268864 +1662130042145269760 +1662130042187270656 +1662130042238271744 +1662130042283272704 +1662130042334273792 +1662130042376274688 +1662130042418275584 +1662130042460276480 +1662130042517277696 +1662130042559278592 +1662130042601279488 +1662130042643280384 +1662130042691281408 +1662130042733282304 +1662130042775283200 +1662130042817284096 +1662130042859284992 +1662130042907286016 +1662130042955287040 +1662130043000288000 +1662130043054289152 +1662130043096290048 +1662130043135290880 +1662130043177291776 +1662130043228292864 +1662130043270293760 +1662130043312294656 +1662130043363295744 +1662130043405296640 +1662130043447297536 +1662130043501298688 +1662130043549299712 +1662130043594300672 +1662130043633301504 +1662130043678302464 +1662130043720303360 +1662130043759304192 +1662130043813305344 +1662130043858306304 +1662130043900307200 +1662130043945308160 +1662130043984308992 +1662130044026309888 +1662130044065310720 +1662130044110311680 +1662130044152312576 +1662130044194313472 +1662130044257314816 +1662130044293315584 +1662130044341316608 +1662130044383317504 +1662130044428318464 +1662130044470319360 +1662130044512320256 +1662130044557321216 +1662130044599322112 +1662130044647323136 +1662130044689324032 +1662130044734324992 +1662130044785326080 +1662130044827326976 +1662130044869327872 +1662130044911328768 +1662130044950329600 +1662130045001330688 +1662130045043331584 +1662130045091332608 +1662130045133333504 +1662130045175334400 +1662130045226335488 +1662130045268336384 +1662130045313337344 +1662130045355338240 +1662130045400339200 +1662130045448340224 +1662130045493341184 +1662130045544342272 +1662130045586343168 +1662130045628344064 +1662130045673345024 +1662130045715345920 +1662130045757346816 +1662130045799347712 +1662130045844348672 +1662130045886349568 +1662130045931350528 +1662130045973351424 +1662130046012352256 +1662130046054353152 +1662130046099354112 +1662130046138354944 +1662130046177355776 +1662130046219356672 +1662130046258357504 +1662130046300358400 +1662130046351359488 +1662130046396360448 +1662130046438361344 +1662130046477362176 +1662130046522363136 +1662130046561363968 +1662130046600364800 +1662130046642365696 +1662130046684366592 +1662130046726367488 +1662130046765368320 +1662130046807369216 +1662130046852370176 +1662130046900371200 +1662130046948372224 +1662130046990373120 +1662130047041374208 +1662130047086375168 +1662130047128376064 +1662130047170376960 +1662130047227378176 +1662130047269379072 +1662130047311379968 +1662130047356380928 +1662130047398381824 +1662130047443382784 +1662130047485383680 +1662130047530384640 +1662130047578385664 +1662130047626386688 +1662130047674387712 +1662130047725388800 +1662130047776389888 +1662130047815390720 +1662130047854391552 +1662130047896392448 +1662130047947393536 +1662130047995394560 +1662130048040395520 +1662130048088396544 +1662130048133397504 +1662130048181398528 +1662130048226399488 +1662130048274400512 +1662130048316401408 +1662130048364402432 +1662130048412403456 +1662130048460404480 +1662130048502405376 +1662130048553406464 +1662130048595407360 +1662130048643408384 +1662130048685409280 +1662130048736410368 +1662130048778411264 +1662130048829412352 +1662130048871413248 +1662130048916414208 +1662130048955415040 +1662130049003416064 +1662130049045416960 +1662130049090417920 +1662130049132418816 +1662130049180419840 +1662130049225420800 +1662130049270421760 +1662130049312422656 +1662130049375424000 +1662130049417424896 +1662130049462425856 +1662130049507426816 +1662130049552427776 +1662130049594428672 +1662130049633429504 +1662130049675430400 +1662130049726431488 +1662130049768432384 +1662130049810433280 +1662130049852434176 +1662130049897435136 +1662130049936435968 +1662130049984436992 +1662130050026437888 +1662130050068438784 +1662130050110439680 +1662130050155440640 +1662130050200441600 +1662130050245442560 +1662130050287443456 +1662130050329444352 +1662130050368445184 +1662130050410446080 +1662130050452446976 +1662130050500448000 +1662130050545448960 +1662130050587449856 +1662130050629450752 +1662130050674451712 +1662130050716452608 +1662130050761453568 +1662130050800454400 +1662130050845455360 +1662130050896456448 +1662130050941457408 +1662130050986458368 +1662130051031459328 +1662130051076460288 +1662130051118461184 +1662130051163462144 +1662130051211463168 +1662130051253464064 +1662130051298465024 +1662130051340465920 +1662130051385466880 +1662130051430467840 +1662130051478468864 +1662130051526469888 +1662130051571470848 +1662130051619471872 +1662130051664472832 +1662130051709473792 +1662130051751474688 +1662130051796475648 +1662130051838476544 +1662130051883477504 +1662130051925478400 +1662130051967479296 +1662130052006480128 +1662130052048481024 +1662130052090481920 +1662130052132482816 +1662130052180483840 +1662130052231484928 +1662130052273485824 +1662130052321486848 +1662130052363487744 +1662130052408488704 +1662130052453489664 +1662130052498490624 +1662130052546491648 +1662130052588492544 +1662130052639493632 +1662130052687494656 +1662130052729495552 +1662130052771496448 +1662130052816497408 +1662130052867498496 +1662130052912499456 +1662130052957500416 +1662130053008501504 +1662130053062502656 +1662130053107503616 +1662130053155504640 +1662130053197505536 +1662130053239506432 +1662130053281507328 +1662130053320508160 +1662130053362509056 +1662130053404509952 +1662130053446510848 +1662130053488511744 +1662130053536512768 +1662130053575513600 +1662130053629514752 +1662130053668515584 +1662130053713516544 +1662130053755517440 +1662130053800518400 +1662130053851519488 +1662130053896520448 +1662130053941521408 +1662130053983522304 +1662130054028523264 +1662130054073524224 +1662130054118525184 +1662130054160526080 +1662130054208527104 +1662130054250528000 +1662130054298529024 +1662130054346530048 +1662130054385530880 +1662130054427531776 +1662130054472532736 +1662130054514533632 +1662130054556534528 +1662130054604535552 +1662130054646536448 +1662130054694537472 +1662130054748538624 +1662130054796539648 +1662130054838540544 +1662130054880541440 +1662130054928542464 +1662130054976543488 +1662130055018544384 +1662130055060545280 +1662130055105546240 +1662130055153547264 +1662130055201548288 +1662130055246549248 +1662130055294550272 +1662130055342551296 +1662130055387552256 +1662130055429553152 +1662130055471554048 +1662130055510554880 +1662130055552555776 +1662130055594556672 +1662130055636557568 +1662130055693558784 +1662130055735559680 +1662130055777560576 +1662130055819561472 +1662130055861562368 +1662130055906563328 +1662130055948564224 +1662130055987565056 +1662130056032566016 +1662130056077566976 +1662130056119567872 +1662130056161568768 +1662130056203569664 +1662130056251570688 +1662130056290571520 +1662130056338572544 +1662130056386573568 +1662130056431574528 +1662130056476575488 +1662130056518576384 +1662130056563577344 +1662130056611578368 +1662130056656579328 +1662130056701580288 +1662130056743581184 +1662130056785582080 +1662130056827582976 +1662130056869583872 +1662130056914584832 +1662130056965585920 +1662130057010586880 +1662130057058587904 +1662130057106588928 +1662130057151589888 +1662130057193590784 +1662130057244591872 +1662130057286592768 +1662130057328593664 +1662130057376594688 +1662130057421595648 +1662130057466596608 +1662130057514597632 +1662130057553598464 +1662130057598599424 +1662130057646600448 +1662130057688601344 +1662130057730602240 +1662130057775603200 +1662130057823604224 +1662130057868605184 +1662130057910606080 +1662130057955607040 +1662130057994607872 +1662130058039608832 +1662130058084609792 +1662130058132610816 +1662130058180611840 +1662130058228612864 +1662130058279613952 +1662130058321614848 +1662130058363615744 +1662130058405616640 +1662130058450617600 +1662130058492618496 +1662130058537619456 +1662130058579620352 +1662130058624621312 diff --git a/Examples/Stereo/MIMIR_TimeStamps/SandPipe_track0_dark.txt b/Examples/Stereo/MIMIR_TimeStamps/SandPipe_track0_dark.txt new file mode 100644 index 0000000000..656025a687 --- /dev/null +++ b/Examples/Stereo/MIMIR_TimeStamps/SandPipe_track0_dark.txt @@ -0,0 +1,2741 @@ +1662063934494348032 +1662063934536348928 +1662063934587350016 +1662063934629350912 +1662063934671351808 +1662063934713352704 +1662063934758353664 +1662063934803354624 +1662063934848355584 +1662063934893356544 +1662063934938357504 +1662063934977358336 +1662063935022359296 +1662063935064360192 +1662063935103361024 +1662063935145361920 +1662063935187362816 +1662063935229363712 +1662063935268364544 +1662063935310365440 +1662063935352366336 +1662063935394367232 +1662063935436368128 +1662063935478369024 +1662063935535370240 +1662063935577371136 +1662063935619372032 +1662063935670373120 +1662063935712374016 +1662063935757374976 +1662063935799375872 +1662063935844376832 +1662063935886377728 +1662063935931378688 +1662063935973379584 +1662063936015380480 +1662063936057381376 +1662063936099382272 +1662063936141383168 +1662063936180384000 +1662063936222384896 +1662063936267385856 +1662063936312386816 +1662063936360387840 +1662063936405388800 +1662063936447389696 +1662063936489390592 +1662063936531391488 +1662063936573392384 +1662063936615393280 +1662063936657394176 +1662063936699395072 +1662063936744396032 +1662063936786396928 +1662063936828397824 +1662063936870398720 +1662063936909399552 +1662063936948400384 +1662063936990401280 +1662063937038402304 +1662063937089403392 +1662063937134404352 +1662063937182405376 +1662063937224406272 +1662063937269407232 +1662063937314408192 +1662063937356409088 +1662063937401410048 +1662063937449411072 +1662063937488411904 +1662063937539412992 +1662063937584413952 +1662063937638415104 +1662063937677415936 +1662063937719416832 +1662063937761417728 +1662063937803418624 +1662063937842419456 +1662063937887420416 +1662063937935421440 +1662063937977422336 +1662063938019423232 +1662063938061424128 +1662063938106425088 +1662063938148425984 +1662063938193426944 +1662063938238427904 +1662063938283428864 +1662063938325429760 +1662063938370430720 +1662063938412431616 +1662063938457432576 +1662063938499433472 +1662063938544434432 +1662063938586435328 +1662063938631436288 +1662063938676437248 +1662063938718438144 +1662063938760439040 +1662063938802439936 +1662063938850440960 +1662063938898441984 +1662063938943442944 +1662063938988443904 +1662063939036444928 +1662063939078445824 +1662063939126446848 +1662063939165447680 +1662063939210448640 +1662063939252449536 +1662063939300450560 +1662063939342451456 +1662063939387452416 +1662063939429453312 +1662063939471454208 +1662063939510455040 +1662063939552455936 +1662063939594456832 +1662063939639457792 +1662063939681458688 +1662063939723459584 +1662063939765460480 +1662063939807461376 +1662063939852462336 +1662063939894463232 +1662063939939464192 +1662063939981465088 +1662063940026466048 +1662063940068466944 +1662063940113467904 +1662063940158468864 +1662063940209469952 +1662063940257470976 +1662063940299471872 +1662063940341472768 +1662063940383473664 +1662063940422474496 +1662063940464475392 +1662063940506476288 +1662063940548477184 +1662063940590478080 +1662063940632478976 +1662063940674479872 +1662063940716480768 +1662063940767481856 +1662063940806482688 +1662063940851483648 +1662063940899484672 +1662063940941485568 +1662063940989486592 +1662063941034487552 +1662063941079488512 +1662063941124489472 +1662063941169490432 +1662063941214491392 +1662063941262492416 +1662063941304493312 +1662063941346494208 +1662063941391495168 +1662063941436496128 +1662063941475496960 +1662063941517497856 +1662063941562498816 +1662063941604499712 +1662063941646500608 +1662063941688501504 +1662063941736502528 +1662063941784503552 +1662063941832504576 +1662063941874505472 +1662063941922506496 +1662063941964507392 +1662063942009508352 +1662063942051509248 +1662063942093510144 +1662063942138511104 +1662063942180512000 +1662063942222512896 +1662063942267513856 +1662063942309514752 +1662063942351515648 +1662063942396516608 +1662063942447517696 +1662063942498518784 +1662063942543519744 +1662063942585520640 +1662063942630521600 +1662063942672522496 +1662063942714523392 +1662063942762524416 +1662063942807525376 +1662063942852526336 +1662063942897527296 +1662063942942528256 +1662063942984529152 +1662063943029530112 +1662063943074531072 +1662063943116531968 +1662063943167533056 +1662063943206533888 +1662063943248534784 +1662063943287535616 +1662063943329536512 +1662063943374537472 +1662063943416538368 +1662063943458539264 +1662063943503540224 +1662063943545541120 +1662063943584541952 +1662063943629542912 +1662063943671543808 +1662063943710544640 +1662063943752545536 +1662063943794546432 +1662063943836547328 +1662063943884548352 +1662063943935549440 +1662063943977550336 +1662063944019551232 +1662063944061552128 +1662063944103553024 +1662063944145553920 +1662063944184554752 +1662063944229555712 +1662063944277556736 +1662063944319557632 +1662063944361558528 +1662063944418559744 +1662063944463560704 +1662063944508561664 +1662063944553562624 +1662063944595563520 +1662063944640564480 +1662063944682565376 +1662063944733566464 +1662063944778567424 +1662063944823568384 +1662063944865569280 +1662063944910570240 +1662063944955571200 +1662063944997572096 +1662063945039572992 +1662063945081573888 +1662063945126574848 +1662063945171575808 +1662063945213576704 +1662063945255577600 +1662063945297578496 +1662063945339579392 +1662063945381580288 +1662063945420581120 +1662063945465582080 +1662063945507582976 +1662063945549583872 +1662063945588584704 +1662063945642585856 +1662063945690586880 +1662063945732587776 +1662063945780588800 +1662063945822589696 +1662063945867590656 +1662063945912591616 +1662063945954592512 +1662063945999593472 +1662063946041594368 +1662063946089595392 +1662063946131596288 +1662063946173597184 +1662063946215598080 +1662063946263599104 +1662063946302599936 +1662063946344600832 +1662063946392601856 +1662063946437602816 +1662063946479603712 +1662063946524604672 +1662063946566605568 +1662063946608606464 +1662063946650607360 +1662063946692608256 +1662063946731609088 +1662063946776610048 +1662063946818610944 +1662063946863611904 +1662063946908612864 +1662063946950613760 +1662063946992614656 +1662063947037615616 +1662063947076616448 +1662063947124617472 +1662063947163618304 +1662063947205619200 +1662063947247620096 +1662063947292621056 +1662063947337622016 +1662063947382622976 +1662063947430624000 +1662063947472624896 +1662063947517625856 +1662063947565626880 +1662063947604627712 +1662063947649628672 +1662063947694629632 +1662063947736630528 +1662063947787631616 +1662063947832632576 +1662063947871633408 +1662063947913634304 +1662063947955635200 +1662063947997636096 +1662063948045637120 +1662063948087638016 +1662063948129638912 +1662063948171639808 +1662063948213640704 +1662063948270641920 +1662063948309642752 +1662063948354643712 +1662063948402644736 +1662063948444645632 +1662063948486646528 +1662063948534647552 +1662063948576648448 +1662063948621649408 +1662063948663650304 +1662063948699651072 +1662063948741651968 +1662063948783652864 +1662063948831653888 +1662063948879654912 +1662063948924655872 +1662063948966656768 +1662063949008657664 +1662063949050658560 +1662063949092659456 +1662063949134660352 +1662063949176661248 +1662063949215662080 +1662063949263663104 +1662063949305664000 +1662063949347664896 +1662063949389665792 +1662063949431666688 +1662063949473667584 +1662063949518668544 +1662063949563669504 +1662063949602670336 +1662063949641671168 +1662063949686672128 +1662063949728673024 +1662063949770673920 +1662063949812674816 +1662063949854675712 +1662063949902676736 +1662063949941677568 +1662063949986678528 +1662063950031679488 +1662063950073680384 +1662063950112681216 +1662063950154682112 +1662063950199683072 +1662063950244684032 +1662063950289684992 +1662063950334685952 +1662063950382686976 +1662063950430688000 +1662063950472688896 +1662063950520689920 +1662063950562690816 +1662063950604691712 +1662063950646692608 +1662063950688693504 +1662063950733694464 +1662063950778695424 +1662063950823696384 +1662063950865697280 +1662063950907698176 +1662063950949699072 +1662063951003700224 +1662063951042701056 +1662063951084701952 +1662063951135703040 +1662063951177703936 +1662063951222704896 +1662063951267705856 +1662063951309706752 +1662063951357707776 +1662063951402708736 +1662063951447709696 +1662063951495710720 +1662063951537711616 +1662063951585712640 +1662063951627713536 +1662063951672714496 +1662063951717715456 +1662063951759716352 +1662063951807717376 +1662063951849718272 +1662063951891719168 +1662063951933720064 +1662063951975720960 +1662063952017721856 +1662063952062722816 +1662063952104723712 +1662063952149724672 +1662063952194725632 +1662063952242726656 +1662063952287727616 +1662063952335728640 +1662063952380729600 +1662063952425730560 +1662063952470731520 +1662063952512732416 +1662063952551733248 +1662063952590734080 +1662063952635735040 +1662063952680736000 +1662063952722736896 +1662063952767737856 +1662063952809738752 +1662063952851739648 +1662063952890740480 +1662063952932741376 +1662063952980742400 +1662063953022743296 +1662063953067744256 +1662063953112745216 +1662063953154746112 +1662063953199747072 +1662063953241747968 +1662063953280748800 +1662063953325749760 +1662063953370750720 +1662063953415751680 +1662063953457752576 +1662063953502753536 +1662063953544754432 +1662063953586755328 +1662063953628756224 +1662063953676757248 +1662063953718758144 +1662063953763759104 +1662063953808760064 +1662063953850760960 +1662063953892761856 +1662063953934762752 +1662063953979763712 +1662063954024764672 +1662063954066765568 +1662063954108766464 +1662063954150767360 +1662063954192768256 +1662063954240769280 +1662063954282770176 +1662063954330771200 +1662063954375772160 +1662063954414772992 +1662063954456773888 +1662063954501774848 +1662063954543775744 +1662063954588776704 +1662063954633777664 +1662063954678778624 +1662063954720779520 +1662063954765780480 +1662063954807781376 +1662063954849782272 +1662063954891783168 +1662063954933784064 +1662063954975784960 +1662063955017785856 +1662063955065786880 +1662063955113787904 +1662063955155788800 +1662063955197789696 +1662063955242790656 +1662063955284791552 +1662063955329792512 +1662063955374793472 +1662063955425794560 +1662063955464795392 +1662063955509796352 +1662063955548797184 +1662063955590798080 +1662063955629798912 +1662063955671799808 +1662063955713800704 +1662063955755801600 +1662063955800802560 +1662063955854803712 +1662063955896804608 +1662063955938805504 +1662063955986806528 +1662063956031807488 +1662063956079808512 +1662063956121809408 +1662063956163810304 +1662063956205811200 +1662063956247812096 +1662063956289812992 +1662063956331813888 +1662063956376814848 +1662063956415815680 +1662063956457816576 +1662063956502817536 +1662063956547818496 +1662063956589819392 +1662063956637820416 +1662063956679821312 +1662063956718822144 +1662063956766823168 +1662063956814824192 +1662063956865825280 +1662063956910826240 +1662063956952827136 +1662063956997828096 +1662063957039828992 +1662063957084829952 +1662063957126830848 +1662063957171831808 +1662063957216832768 +1662063957261833728 +1662063957303834624 +1662063957348835584 +1662063957387836416 +1662063957429837312 +1662063957474838272 +1662063957522839296 +1662063957564840192 +1662063957603841024 +1662063957645841920 +1662063957690842880 +1662063957732843776 +1662063957777844736 +1662063957819845632 +1662063957864846592 +1662063957912847616 +1662063957954848512 +1662063957996849408 +1662063958041850368 +1662063958083851264 +1662063958131852288 +1662063958176853248 +1662063958224854272 +1662063958269855232 +1662063958320856320 +1662063958365857280 +1662063958407858176 +1662063958452859136 +1662063958494860032 +1662063958536860928 +1662063958584861952 +1662063958626862848 +1662063958668863744 +1662063958713864704 +1662063958752865536 +1662063958803866624 +1662063958848867584 +1662063958893868544 +1662063958941869568 +1662063958992870656 +1662063959034871552 +1662063959079872512 +1662063959121873408 +1662063959166874368 +1662063959208875264 +1662063959253876224 +1662063959301877248 +1662063959355878400 +1662063959397879296 +1662063959436880128 +1662063959478881024 +1662063959529882112 +1662063959574883072 +1662063959616883968 +1662063959658884864 +1662063959700885760 +1662063959742886656 +1662063959784887552 +1662063959829888512 +1662063959871889408 +1662063959913890304 +1662063959955891200 +1662063959997892096 +1662063960039892992 +1662063960084893952 +1662063960129894912 +1662063960174895872 +1662063960216896768 +1662063960258897664 +1662063960300898560 +1662063960342899456 +1662063960387900416 +1662063960429901312 +1662063960474902272 +1662063960525903360 +1662063960567904256 +1662063960606905088 +1662063960648905984 +1662063960687906816 +1662063960732907776 +1662063960774908672 +1662063960816909568 +1662063960861910528 +1662063960906911488 +1662063960948912384 +1662063960990913280 +1662063961032914176 +1662063961074915072 +1662063961119916032 +1662063961164916992 +1662063961209917952 +1662063961254918912 +1662063961299919872 +1662063961344920832 +1662063961389921792 +1662063961428922624 +1662063961470923520 +1662063961515924480 +1662063961563925504 +1662063961608926464 +1662063961650927360 +1662063961689928192 +1662063961728929024 +1662063961776930048 +1662063961821931008 +1662063961863931904 +1662063961908932864 +1662063961956933888 +1662063961998934784 +1662063962040935680 +1662063962088936704 +1662063962136937728 +1662063962178938624 +1662063962223939584 +1662063962271940608 +1662063962316941568 +1662063962367942656 +1662063962409943552 +1662063962451944448 +1662063962496945408 +1662063962547946496 +1662063962592947456 +1662063962640948480 +1662063962682949376 +1662063962724950272 +1662063962769951232 +1662063962814952192 +1662063962871953408 +1662063962913954304 +1662063962958955264 +1662063963006956288 +1662063963045957120 +1662063963090958080 +1662063963132958976 +1662063963183960064 +1662063963225960960 +1662063963267961856 +1662063963309962752 +1662063963354963712 +1662063963396964608 +1662063963435965440 +1662063963483966464 +1662063963531967488 +1662063963579968512 +1662063963621969408 +1662063963663970304 +1662063963711971328 +1662063963759972352 +1662063963801973248 +1662063963840974080 +1662063963885975040 +1662063963927975936 +1662063963972976896 +1662063964017977856 +1662063964059978752 +1662063964101979648 +1662063964143980544 +1662063964185981440 +1662063964227982336 +1662063964275983360 +1662063964320984320 +1662063964359985152 +1662063964401986048 +1662063964440986880 +1662063964479987712 +1662063964524988672 +1662063964566989568 +1662063964608990464 +1662063964653991424 +1662063964701992448 +1662063964749993472 +1662063964794994432 +1662063964836995328 +1662063964878996224 +1662063964923997184 +1662063964968998144 +1662063965010999040 +1662063965052999936 +1662063965098000896 +1662063965155002112 +1662063965197003008 +1662063965245004032 +1662063965287004928 +1662063965332005888 +1662063965377006848 +1662063965422007808 +1662063965461008640 +1662063965506009600 +1662063965545010432 +1662063965593011456 +1662063965635012352 +1662063965677013248 +1662063965719014144 +1662063965761015040 +1662063965809016064 +1662063965851016960 +1662063965893017856 +1662063965935018752 +1662063965980019712 +1662063966028020736 +1662063966073021696 +1662063966115022592 +1662063966160023552 +1662063966205024512 +1662063966250025472 +1662063966295026432 +1662063966337027328 +1662063966382028288 +1662063966427029248 +1662063966472030208 +1662063966514031104 +1662063966559032064 +1662063966601032960 +1662063966646033920 +1662063966688034816 +1662063966736035840 +1662063966781036800 +1662063966823037696 +1662063966868038656 +1662063966919039744 +1662063966964040704 +1662063967009041664 +1662063967054042624 +1662063967096043520 +1662063967138044416 +1662063967183045376 +1662063967225046272 +1662063967267047168 +1662063967309048064 +1662063967351048960 +1662063967393049856 +1662063967435050752 +1662063967477051648 +1662063967525052672 +1662063967570053632 +1662063967612054528 +1662063967654055424 +1662063967702056448 +1662063967741057280 +1662063967786058240 +1662063967828059136 +1662063967867059968 +1662063967909060864 +1662063967954061824 +1662063968002062848 +1662063968047063808 +1662063968089064704 +1662063968137065728 +1662063968179066624 +1662063968230067712 +1662063968275068672 +1662063968320069632 +1662063968365070592 +1662063968410071552 +1662063968455072512 +1662063968497073408 +1662063968539074304 +1662063968584075264 +1662063968623076096 +1662063968665076992 +1662063968710077952 +1662063968761079040 +1662063968803079936 +1662063968848080896 +1662063968893081856 +1662063968938082816 +1662063968983083776 +1662063969025084672 +1662063969073085696 +1662063969115086592 +1662063969157087488 +1662063969205088512 +1662063969253089536 +1662063969295090432 +1662063969346091520 +1662063969391092480 +1662063969433093376 +1662063969478094336 +1662063969523095296 +1662063969565096192 +1662063969610097152 +1662063969655098112 +1662063969700099072 +1662063969739099904 +1662063969781100800 +1662063969826101760 +1662063969868102656 +1662063969913103616 +1662063969967104768 +1662063970009105664 +1662063970051106560 +1662063970093107456 +1662063970132108288 +1662063970180109312 +1662063970228110336 +1662063970267111168 +1662063970309112064 +1662063970360113152 +1662063970405114112 +1662063970447115008 +1662063970492115968 +1662063970531116800 +1662063970576117760 +1662063970615118592 +1662063970660119552 +1662063970711120640 +1662063970750121472 +1662063970792122368 +1662063970834123264 +1662063970876124160 +1662063970918125056 +1662063970960125952 +1662063971002126848 +1662063971044127744 +1662063971089128704 +1662063971131129600 +1662063971176130560 +1662063971218131456 +1662063971260132352 +1662063971299133184 +1662063971341134080 +1662063971389135104 +1662063971431136000 +1662063971473136896 +1662063971515137792 +1662063971557138688 +1662063971605139712 +1662063971650140672 +1662063971692141568 +1662063971740142592 +1662063971782143488 +1662063971827144448 +1662063971869145344 +1662063971914146304 +1662063971956147200 +1662063971998148096 +1662063972040148992 +1662063972088150016 +1662063972142151168 +1662063972187152128 +1662063972232153088 +1662063972271153920 +1662063972316154880 +1662063972358155776 +1662063972400156672 +1662063972448157696 +1662063972490158592 +1662063972535159552 +1662063972577160448 +1662063972622161408 +1662063972661162240 +1662063972703163136 +1662063972754164224 +1662063972802165248 +1662063972853166336 +1662063972895167232 +1662063972937168128 +1662063972982169088 +1662063973024169984 +1662063973072171008 +1662063973114171904 +1662063973156172800 +1662063973201173760 +1662063973252174848 +1662063973300175872 +1662063973348176896 +1662063973402178048 +1662063973444178944 +1662063973486179840 +1662063973525180672 +1662063973564181504 +1662063973618182656 +1662063973660183552 +1662063973699184384 +1662063973744185344 +1662063973789186304 +1662063973834187264 +1662063973876188160 +1662063973921189120 +1662063973963190016 +1662063974014191104 +1662063974056192000 +1662063974095192832 +1662063974137193728 +1662063974176194560 +1662063974218195456 +1662063974260196352 +1662063974302197248 +1662063974350198272 +1662063974389199104 +1662063974440200192 +1662063974482201088 +1662063974527202048 +1662063974572203008 +1662063974614203904 +1662063974659204864 +1662063974704205824 +1662063974749206784 +1662063974797207808 +1662063974839208704 +1662063974881209600 +1662063974929210624 +1662063974971211520 +1662063975016212480 +1662063975064213504 +1662063975106214400 +1662063975154215424 +1662063975196216320 +1662063975238217216 +1662063975280218112 +1662063975325219072 +1662063975370220032 +1662063975412220928 +1662063975454221824 +1662063975493222656 +1662063975532223488 +1662063975577224448 +1662063975619225344 +1662063975661226240 +1662063975703227136 +1662063975748228096 +1662063975790228992 +1662063975832229888 +1662063975874230784 +1662063975910231552 +1662063975955232512 +1662063975994233344 +1662063976036234240 +1662063976084235264 +1662063976126236160 +1662063976168237056 +1662063976219238144 +1662063976261239040 +1662063976303239936 +1662063976345240832 +1662063976387241728 +1662063976429242624 +1662063976471243520 +1662063976519244544 +1662063976561245440 +1662063976603246336 +1662063976648247296 +1662063976693248256 +1662063976735249152 +1662063976780250112 +1662063976822251008 +1662063976867251968 +1662063976909252864 +1662063976954253824 +1662063977002254848 +1662063977044255744 +1662063977089256704 +1662063977134257664 +1662063977176258560 +1662063977218259456 +1662063977263260416 +1662063977305261312 +1662063977347262208 +1662063977389263104 +1662063977434264064 +1662063977476264960 +1662063977521265920 +1662063977563266816 +1662063977617267968 +1662063977659268864 +1662063977704269824 +1662063977761271040 +1662063977806272000 +1662063977854273024 +1662063977896273920 +1662063977938274816 +1662063977977275648 +1662063978022276608 +1662063978067277568 +1662063978112278528 +1662063978151279360 +1662063978196280320 +1662063978238281216 +1662063978286282240 +1662063978340283392 +1662063978397284608 +1662063978445285632 +1662063978484286464 +1662063978529287424 +1662063978571288320 +1662063978616289280 +1662063978658290176 +1662063978703291136 +1662063978745292032 +1662063978784292864 +1662063978826293760 +1662063978868294656 +1662063978913295616 +1662063978961296640 +1662063979003297536 +1662063979051298560 +1662063979093299456 +1662063979138300416 +1662063979186301440 +1662063979228302336 +1662063979267303168 +1662063979318304256 +1662063979363305216 +1662063979408306176 +1662063979453307136 +1662063979495308032 +1662063979534308864 +1662063979585309952 +1662063979627310848 +1662063979669311744 +1662063979711312640 +1662063979756313600 +1662063979798314496 +1662063979843315456 +1662063979888316416 +1662063979930317312 +1662063979978318336 +1662063980020319232 +1662063980065320192 +1662063980110321152 +1662063980158322176 +1662063980200323072 +1662063980239323904 +1662063980284324864 +1662063980326325760 +1662063980368326656 +1662063980410327552 +1662063980455328512 +1662063980503329536 +1662063980545330432 +1662063980587331328 +1662063980635332352 +1662063980683333376 +1662063980722334208 +1662063980764335104 +1662063980806336000 +1662063980854337024 +1662063980896337920 +1662063980947339008 +1662063980992339968 +1662063981034340864 +1662063981073341696 +1662063981118342656 +1662063981157343488 +1662063981199344384 +1662063981250345472 +1662063981292346368 +1662063981337347328 +1662063981379348224 +1662063981421349120 +1662063981472350208 +1662063981517351168 +1662063981574352384 +1662063981616353280 +1662063981667354368 +1662063981712355328 +1662063981757356288 +1662063981796357120 +1662063981841358080 +1662063981889359104 +1662063981931360000 +1662063981982361088 +1662063982024361984 +1662063982066362880 +1662063982114363904 +1662063982159364864 +1662063982201365760 +1662063982240366592 +1662063982288367616 +1662063982333368576 +1662063982384369664 +1662063982426370560 +1662063982465371392 +1662063982519372544 +1662063982561373440 +1662063982606374400 +1662063982648375296 +1662063982693376256 +1662063982738377216 +1662063982780378112 +1662063982822379008 +1662063982867379968 +1662063982909380864 +1662063982954381824 +1662063982993382656 +1662063983035383552 +1662063983080384512 +1662063983122385408 +1662063983173386496 +1662063983212387328 +1662063983257388288 +1662063983296389120 +1662063983338390016 +1662063983386391040 +1662063983434392064 +1662063983479393024 +1662063983524393984 +1662063983566394880 +1662063983608395776 +1662063983656396800 +1662063983698397696 +1662063983737398528 +1662063983779399424 +1662063983824400384 +1662063983863401216 +1662063983905402112 +1662063983959403264 +1662063984001404160 +1662063984043405056 +1662063984085405952 +1662063984124406784 +1662063984166407680 +1662063984220408832 +1662063984262409728 +1662063984310410752 +1662063984355411712 +1662063984397412608 +1662063984436413440 +1662063984478414336 +1662063984520415232 +1662063984568416256 +1662063984613417216 +1662063984658418176 +1662063984703419136 +1662063984745420032 +1662063984790420992 +1662063984835421952 +1662063984880422912 +1662063984940424192 +1662063984979425024 +1662063985021425920 +1662063985063426816 +1662063985111427840 +1662063985153428736 +1662063985195429632 +1662063985249430784 +1662063985291431680 +1662063985330432512 +1662063985375433472 +1662063985420434432 +1662063985459435264 +1662063985504436224 +1662063985546437120 +1662063985591438080 +1662063985636439040 +1662063985678439936 +1662063985726440960 +1662063985765441792 +1662063985807442688 +1662063985855443712 +1662063985900444672 +1662063985939445504 +1662063985987446528 +1662063986029447424 +1662063986074448384 +1662063986116449280 +1662063986158450176 +1662063986200451072 +1662063986248452096 +1662063986290452992 +1662063986335453952 +1662063986377454848 +1662063986419455744 +1662063986461456640 +1662063986509457664 +1662063986551458560 +1662063986593459456 +1662063986647460608 +1662063986686461440 +1662063986728462336 +1662063986770463232 +1662063986809464064 +1662063986851464960 +1662063986896465920 +1662063986938466816 +1662063986980467712 +1662063987022468608 +1662063987070469632 +1662063987112470528 +1662063987157471488 +1662063987196472320 +1662063987238473216 +1662063987289474304 +1662063987334475264 +1662063987391476480 +1662063987430477312 +1662063987475478272 +1662063987517479168 +1662063987559480064 +1662063987601480960 +1662063987637481728 +1662063987679482624 +1662063987721483520 +1662063987763484416 +1662063987805485312 +1662063987847486208 +1662063987889487104 +1662063987937488128 +1662063987979489024 +1662063988021489920 +1662063988057490688 +1662063988102491648 +1662063988144492544 +1662063988186493440 +1662063988231494400 +1662063988273495296 +1662063988318496256 +1662063988360497152 +1662063988402498048 +1662063988441498880 +1662063988483499776 +1662063988525500672 +1662063988567501568 +1662063988609502464 +1662063988651503360 +1662063988696504320 +1662063988738505216 +1662063988783506176 +1662063988825507072 +1662063988879508224 +1662063988921509120 +1662063988963510016 +1662063989008510976 +1662063989050511872 +1662063989092512768 +1662063989140513792 +1662063989185514752 +1662063989227515648 +1662063989269516544 +1662063989317517568 +1662063989362518528 +1662063989404519424 +1662063989449520384 +1662063989491521280 +1662063989533522176 +1662063989578523136 +1662063989623524096 +1662063989665524992 +1662063989707525888 +1662063989755526912 +1662063989797527808 +1662063989839528704 +1662063989881529600 +1662063989926530560 +1662063989971531520 +1662063990016532480 +1662063990055533312 +1662063990097534208 +1662063990139535104 +1662063990181536000 +1662063990223536896 +1662063990265537792 +1662063990307538688 +1662063990349539584 +1662063990391540480 +1662063990439541504 +1662063990481542400 +1662063990526543360 +1662063990571544320 +1662063990610545152 +1662063990652546048 +1662063990694546944 +1662063990739547904 +1662063990784548864 +1662063990826549760 +1662063990874550784 +1662063990916551680 +1662063990958552576 +1662063991003553536 +1662063991045554432 +1662063991087555328 +1662063991135556352 +1662063991183557376 +1662063991231558400 +1662063991270559232 +1662063991318560256 +1662063991360561152 +1662063991405562112 +1662063991450563072 +1662063991492563968 +1662063991540564992 +1662063991579565824 +1662063991618566656 +1662063991666567680 +1662063991708568576 +1662063991753569536 +1662063991801570560 +1662063991843571456 +1662063991888572416 +1662063991930573312 +1662063991975574272 +1662063992020575232 +1662063992065576192 +1662063992113577216 +1662063992158578176 +1662063992197579008 +1662063992245580032 +1662063992284580864 +1662063992332581888 +1662063992374582784 +1662063992422583808 +1662063992470584832 +1662063992521585920 +1662063992563586816 +1662063992602587648 +1662063992647588608 +1662063992692589568 +1662063992740590592 +1662063992785591552 +1662063992836592640 +1662063992875593472 +1662063992917594368 +1662063992962595328 +1662063993004596224 +1662063993049597184 +1662063993094598144 +1662063993139599104 +1662063993178599936 +1662063993223600896 +1662063993262601728 +1662063993304602624 +1662063993349603584 +1662063993388604416 +1662063993430605312 +1662063993475606272 +1662063993517607168 +1662063993559608064 +1662063993601608960 +1662063993649609984 +1662063993691610880 +1662063993733611776 +1662063993775612672 +1662063993826613760 +1662063993865614592 +1662063993907615488 +1662063993949616384 +1662063994000617472 +1662063994045618432 +1662063994084619264 +1662063994126620160 +1662063994162620928 +1662063994207621888 +1662063994255622912 +1662063994303623936 +1662063994345624832 +1662063994399625984 +1662063994444626944 +1662063994486627840 +1662063994525628672 +1662063994573629696 +1662063994621630720 +1662063994669631744 +1662063994711632640 +1662063994756633600 +1662063994798634496 +1662063994846635520 +1662063994888636416 +1662063994939637504 +1662063994990638592 +1662063995032639488 +1662063995077640448 +1662063995119641344 +1662063995164642304 +1662063995209643264 +1662063995254644224 +1662063995299645184 +1662063995347646208 +1662063995389647104 +1662063995434648064 +1662063995479649024 +1662063995527650048 +1662063995569650944 +1662063995608651776 +1662063995650652672 +1662063995695653632 +1662063995737654528 +1662063995785655552 +1662063995830656512 +1662063995872657408 +1662063995914658304 +1662063995953659136 +1662063995998660096 +1662063996040660992 +1662063996085661952 +1662063996133662976 +1662063996181664000 +1662063996229665024 +1662063996283666176 +1662063996325667072 +1662063996373668096 +1662063996412668928 +1662063996463670016 +1662063996508670976 +1662063996550671872 +1662063996592672768 +1662063996637673728 +1662063996679674624 +1662063996730675712 +1662063996775676672 +1662063996817677568 +1662063996859678464 +1662063996904679424 +1662063996952680448 +1662063996997681408 +1662063997048682496 +1662063997087683328 +1662063997126684160 +1662063997177685248 +1662063997222686208 +1662063997264687104 +1662063997306688000 +1662063997345688832 +1662063997396689920 +1662063997444690944 +1662063997486691840 +1662063997531692800 +1662063997573693696 +1662063997621694720 +1662063997666695680 +1662063997708696576 +1662063997750697472 +1662063997795698432 +1662063997840699392 +1662063997888700416 +1662063997933701376 +1662063997975702272 +1662063998020703232 +1662063998062704128 +1662063998107705088 +1662063998149705984 +1662063998200707072 +1662063998242707968 +1662063998287708928 +1662063998335709952 +1662063998377710848 +1662063998428711936 +1662063998473712896 +1662063998527714048 +1662063998575715072 +1662063998626716160 +1662063998677717248 +1662063998725718272 +1662063998770719232 +1662063998812720128 +1662063998854721024 +1662063998896721920 +1662063998944722944 +1662063998986723840 +1662063999028724736 +1662063999079725824 +1662063999121726720 +1662063999163727616 +1662063999208728576 +1662063999250729472 +1662063999292730368 +1662063999334731264 +1662063999385732352 +1662063999433733376 +1662063999475734272 +1662063999517735168 +1662063999559736064 +1662063999604737024 +1662063999646737920 +1662063999688738816 +1662063999730739712 +1662063999769740544 +1662063999811741440 +1662063999856742400 +1662063999904743424 +1662063999946744320 +1662063999988745216 +1662064000027746048 +1662064000069746944 +1662064000114747904 +1662064000156748800 +1662064000201749760 +1662064000246750720 +1662064000291751680 +1662064000333752576 +1662064000378753536 +1662064000420754432 +1662064000465755392 +1662064000510756352 +1662064000555757312 +1662064000603758336 +1662064000648759296 +1662064000687760128 +1662064000729761024 +1662064000771761920 +1662064000816762880 +1662064000864763904 +1662064000906764800 +1662064000948765696 +1662064000993766656 +1662064001044767744 +1662064001086768640 +1662064001128769536 +1662064001173770496 +1662064001215771392 +1662064001260772352 +1662064001308773376 +1662064001350774272 +1662064001398775296 +1662064001440776192 +1662064001488777216 +1662064001533778176 +1662064001578779136 +1662064001629780224 +1662064001671781120 +1662064001713782016 +1662064001755782912 +1662064001797783808 +1662064001839784704 +1662064001881785600 +1662064001929786624 +1662064001971787520 +1662064002013788416 +1662064002055789312 +1662064002097790208 +1662064002142791168 +1662064002187792128 +1662064002229793024 +1662064002274793984 +1662064002319794944 +1662064002373796096 +1662064002415796992 +1662064002457797888 +1662064002499798784 +1662064002550799872 +1662064002592800768 +1662064002634801664 +1662064002673802496 +1662064002718803456 +1662064002760804352 +1662064002805805312 +1662064002847806208 +1662064002889807104 +1662064002931808000 +1662064002979809024 +1662064003030810112 +1662064003075811072 +1662064003120812032 +1662064003168813056 +1662064003207813888 +1662064003249814784 +1662064003294815744 +1662064003342816768 +1662064003390817792 +1662064003435818752 +1662064003477819648 +1662064003522820608 +1662064003564821504 +1662064003606822400 +1662064003654823424 +1662064003699824384 +1662064003747825408 +1662064003789826304 +1662064003828827136 +1662064003873828096 +1662064003915828992 +1662064003960829952 +1662064004008830976 +1662064004053831936 +1662064004092832768 +1662064004134833664 +1662064004176834560 +1662064004218835456 +1662064004266836480 +1662064004308837376 +1662064004350838272 +1662064004392839168 +1662064004434840064 +1662064004485841152 +1662064004527842048 +1662064004575843072 +1662064004617843968 +1662064004668845056 +1662064004713846016 +1662064004758846976 +1662064004800847872 +1662064004842848768 +1662064004887849728 +1662064004929850624 +1662064004971851520 +1662064005019852544 +1662064005064853504 +1662064005115854592 +1662064005160855552 +1662064005202856448 +1662064005247857408 +1662064005289858304 +1662064005331859200 +1662064005373860096 +1662064005424861184 +1662064005466862080 +1662064005511863040 +1662064005553863936 +1662064005598864896 +1662064005640865792 +1662064005682866688 +1662064005736867840 +1662064005781868800 +1662064005826869760 +1662064005871870720 +1662064005910871552 +1662064005955872512 +1662064006000873472 +1662064006045874432 +1662064006090875392 +1662064006132876288 +1662064006177877248 +1662064006222878208 +1662064006264879104 +1662064006309880064 +1662064006360881152 +1662064006402882048 +1662064006444882944 +1662064006489883904 +1662064006531884800 +1662064006576885760 +1662064006621886720 +1662064006669887744 +1662064006717888768 +1662064006762889728 +1662064006804890624 +1662064006855891712 +1662064006897892608 +1662064006942893568 +1662064006990894592 +1662064007032895488 +1662064007077896448 +1662064007119897344 +1662064007161898240 +1662064007206899200 +1662064007248900096 +1662064007290900992 +1662064007332901888 +1662064007374902784 +1662064007425903872 +1662064007464904704 +1662064007512905728 +1662064007557906688 +1662064007602907648 +1662064007647908608 +1662064007692909568 +1662064007746910720 +1662064007791911680 +1662064007833912576 +1662064007878913536 +1662064007920914432 +1662064007962915328 +1662064008004916224 +1662064008046917120 +1662064008091918080 +1662064008133918976 +1662064008175919872 +1662064008220920832 +1662064008262921728 +1662064008307922688 +1662064008352923648 +1662064008394924544 +1662064008436925440 +1662064008478926336 +1662064008520927232 +1662064008565928192 +1662064008610929152 +1662064008664930304 +1662064008709931264 +1662064008754932224 +1662064008796933120 +1662064008844934144 +1662064008889935104 +1662064008934936064 +1662064008985937152 +1662064009027938048 +1662064009075939072 +1662064009120940032 +1662064009162940928 +1662064009207941888 +1662064009249942784 +1662064009288943616 +1662064009339944704 +1662064009381945600 +1662064009423946496 +1662064009465947392 +1662064009510948352 +1662064009558949376 +1662064009597950208 +1662064009636951040 +1662064009678951936 +1662064009717952768 +1662064009762953728 +1662064009807954688 +1662064009849955584 +1662064009897956608 +1662064009948957696 +1662064009990958592 +1662064010035959552 +1662064010077960448 +1662064010122961408 +1662064010170962432 +1662064010215963392 +1662064010260964352 +1662064010317965568 +1662064010365966592 +1662064010410967552 +1662064010458968576 +1662064010500969472 +1662064010542970368 +1662064010587971328 +1662064010629972224 +1662064010674973184 +1662064010719974144 +1662064010767975168 +1662064010809976064 +1662064010857977088 +1662064010902978048 +1662064010947979008 +1662064010989979904 +1662064011031980800 +1662064011073981696 +1662064011121982720 +1662064011172983808 +1662064011214984704 +1662064011259985664 +1662064011307986688 +1662064011346987520 +1662064011391988480 +1662064011436989440 +1662064011478990336 +1662064011523991296 +1662064011568992256 +1662064011610993152 +1662064011655994112 +1662064011700995072 +1662064011748996096 +1662064011790996992 +1662064011835997952 +1662064011877998848 +1662064011919999744 +1662064011965000704 +1662064012010001664 +1662064012049002496 +1662064012091003392 +1662064012133004288 +1662064012175005184 +1662064012217006080 +1662064012262007040 +1662064012301007872 +1662064012346008832 +1662064012391009792 +1662064012433010688 +1662064012481011712 +1662064012526012672 +1662064012568013568 +1662064012610014464 +1662064012652015360 +1662064012694016256 +1662064012748017408 +1662064012790018304 +1662064012832019200 +1662064012874020096 +1662064012916020992 +1662064012961021952 +1662064013015023104 +1662064013060024064 +1662064013105025024 +1662064013150025984 +1662064013192026880 +1662064013237027840 +1662064013279028736 +1662064013321029632 +1662064013369030656 +1662064013411031552 +1662064013456032512 +1662064013501033472 +1662064013543034368 +1662064013585035264 +1662064013630036224 +1662064013678037248 +1662064013720038144 +1662064013768039168 +1662064013810040064 +1662064013855041024 +1662064013900041984 +1662064013948043008 +1662064013993043968 +1662064014038044928 +1662064014089046016 +1662064014134046976 +1662064014179047936 +1662064014224048896 +1662064014275049984 +1662064014314050816 +1662064014356051712 +1662064014401052672 +1662064014446053632 +1662064014488054528 +1662064014533055488 +1662064014578056448 +1662064014623057408 +1662064014662058240 +1662064014710059264 +1662064014758060288 +1662064014797061120 +1662064014839062016 +1662064014887063040 +1662064014935064064 +1662064014980065024 +1662064015031066112 +1662064015082067200 +1662064015124068096 +1662064015166068992 +1662064015211069952 +1662064015259070976 +1662064015304071936 +1662064015349072896 +1662064015391073792 +1662064015436074752 +1662064015478075648 +1662064015520076544 +1662064015574077696 +1662064015634078976 +1662064015685080064 +1662064015727080960 +1662064015769081856 +1662064015811082752 +1662064015850083584 +1662064015889084416 +1662064015931085312 +1662064015973086208 +1662064016018087168 +1662064016060088064 +1662064016111089152 +1662064016153090048 +1662064016198091008 +1662064016240091904 +1662064016294093056 +1662064016342094080 +1662064016387095040 +1662064016435096064 +1662064016477096960 +1662064016522097920 +1662064016564098816 +1662064016609099776 +1662064016660100864 +1662064016705101824 +1662064016750102784 +1662064016792103680 +1662064016837104640 +1662064016879105536 +1662064016924106496 +1662064016966107392 +1662064017011108352 +1662064017053109248 +1662064017095110144 +1662064017140111104 +1662064017182112000 +1662064017227112960 +1662064017269113856 +1662064017311114752 +1662064017353115648 +1662064017395116544 +1662064017437117440 +1662064017482118400 +1662064017524119296 +1662064017566120192 +1662064017608121088 +1662064017656122112 +1662064017704123136 +1662064017749124096 +1662064017791124992 +1662064017836125952 +1662064017878126848 +1662064017920127744 +1662064017965128704 +1662064018010129664 +1662064018055130624 +1662064018103131648 +1662064018145132544 +1662064018187133440 +1662064018232134400 +1662064018289135616 +1662064018334136576 +1662064018382137600 +1662064018421138432 +1662064018463139328 +1662064018505140224 +1662064018550141184 +1662064018595142144 +1662064018640143104 +1662064018682144000 +1662064018721144832 +1662064018766145792 +1662064018808146688 +1662064018850147584 +1662064018892148480 +1662064018934149376 +1662064018976150272 +1662064019024151296 +1662064019066152192 +1662064019111153152 +1662064019153154048 +1662064019198155008 +1662064019243155968 +1662064019288156928 +1662064019327157760 +1662064019378158848 +1662064019417159680 +1662064019462160640 +1662064019507161600 +1662064019552162560 +1662064019594163456 +1662064019636164352 +1662064019672165120 +1662064019717166080 +1662064019756166912 +1662064019798167808 +1662064019843168768 +1662064019888169728 +1662064019936170752 +1662064019978171648 +1662064020020172544 +1662064020065173504 +1662064020107174400 +1662064020152175360 +1662064020194176256 +1662064020239177216 +1662064020284178176 +1662064020329179136 +1662064020377180160 +1662064020428181248 +1662064020479182336 +1662064020521183232 +1662064020572184320 +1662064020614185216 +1662064020662186240 +1662064020707187200 +1662064020752188160 +1662064020794189056 +1662064020836189952 +1662064020878190848 +1662064020923191808 +1662064020968192768 +1662064021013193728 +1662064021058194688 +1662064021100195584 +1662064021154196736 +1662064021205197824 +1662064021247198720 +1662064021289199616 +1662064021331200512 +1662064021373201408 +1662064021421202432 +1662064021463203328 +1662064021508204288 +1662064021553205248 +1662064021595206144 +1662064021637207040 +1662064021682208000 +1662064021724208896 +1662064021766209792 +1662064021811210752 +1662064021853211648 +1662064021901212672 +1662064021949213696 +1662064021994214656 +1662064022036215552 +1662064022081216512 +1662064022120217344 +1662064022162218240 +1662064022210219264 +1662064022255220224 +1662064022297221120 +1662064022342222080 +1662064022384222976 +1662064022432224000 +1662064022474224896 +1662064022525225984 +1662064022567226880 +1662064022612227840 +1662064022660228864 +1662064022702229760 +1662064022747230720 +1662064022789231616 +1662064022831232512 +1662064022888233728 +1662064022930234624 +1662064022978235648 +1662064023017236480 +1662064023065237504 +1662064023116238592 +1662064023155239424 +1662064023197240320 +1662064023239241216 +1662064023281242112 +1662064023323243008 +1662064023365243904 +1662064023407244800 +1662064023449245696 +1662064023500246784 +1662064023542247680 +1662064023584248576 +1662064023632249600 +1662064023677250560 +1662064023725251584 +1662064023767252480 +1662064023809253376 +1662064023857254400 +1662064023902255360 +1662064023944256256 +1662064023989257216 +1662064024031258112 +1662064024076259072 +1662064024127260160 +1662064024175261184 +1662064024217262080 +1662064024262263040 +1662064024304263936 +1662064024352264960 +1662064024397265920 +1662064024448267008 +1662064024496268032 +1662064024538268928 +1662064024583269888 +1662064024634270976 +1662064024679271936 +1662064024727272960 +1662064024778274048 +1662064024820274944 +1662064024871276032 +1662064024913276928 +1662064024955277824 +1662064024997278720 +1662064025039279616 +1662064025090280704 +1662064025129281536 +1662064025177282560 +1662064025228283648 +1662064025270284544 +1662064025312285440 +1662064025354286336 +1662064025396287232 +1662064025456288512 +1662064025507289600 +1662064025549290496 +1662064025594291456 +1662064025636292352 +1662064025678293248 +1662064025720294144 +1662064025768295168 +1662064025807296000 +1662064025852296960 +1662064025891297792 +1662064025933298688 +1662064025972299520 +1662064026020300544 +1662064026059301376 +1662064026101302272 +1662064026152303360 +1662064026197304320 +1662064026242305280 +1662064026284306176 +1662064026326307072 +1662064026368307968 +1662064026413308928 +1662064026455309824 +1662064026500310784 +1662064026539311616 +1662064026578312448 +1662064026620313344 +1662064026659314176 +1662064026701315072 +1662064026740315904 +1662064026785316864 +1662064026833317888 +1662064026878318848 +1662064026917319680 +1662064026962320640 +1662064027007321600 +1662064027061322752 +1662064027103323648 +1662064027142324480 +1662064027184325376 +1662064027226326272 +1662064027271327232 +1662064027313328128 +1662064027355329024 +1662064027397329920 +1662064027442330880 +1662064027484331776 +1662064027532332800 +1662064027571333632 +1662064027613334528 +1662064027655335424 +1662064027700336384 +1662064027745337344 +1662064027787338240 +1662064027832339200 +1662064027877340160 +1662064027922341120 +1662064027964342016 +1662064028006342912 +1662064028051343872 +1662064028093344768 +1662064028144345856 +1662064028192346880 +1662064028234347776 +1662064028288348928 +1662064028333349888 +1662064028378350848 +1662064028423351808 +1662064028462352640 +1662064028510353664 +1662064028549354496 +1662064028591355392 +1662064028636356352 +1662064028678357248 +1662064028723358208 +1662064028768359168 +1662064028810360064 +1662064028849360896 +1662064028891361792 +1662064028933362688 +1662064028975363584 +1662064029029364736 +1662064029071365632 +1662064029113366528 +1662064029158367488 +1662064029203368448 +1662064029245369344 +1662064029284370176 +1662064029329371136 +1662064029374372096 +1662064029416372992 +1662064029458373888 +1662064029503374848 +1662064029545375744 +1662064029593376768 +1662064029635377664 +1662064029683378688 +1662064029725379584 +1662064029767380480 +1662064029818381568 +1662064029866382592 +1662064029908383488 +1662064029950384384 +1662064029998385408 +1662064030052386560 +1662064030097387520 +1662064030145388544 +1662064030196389632 +1662064030238390528 +1662064030286391552 +1662064030331392512 +1662064030385393664 +1662064030430394624 +1662064030469395456 +1662064030514396416 +1662064030574397696 +1662064030616398592 +1662064030658399488 +1662064030700400384 +1662064030748401408 +1662064030793402368 +1662064030841403392 +1662064030886404352 +1662064030928405248 +1662064030979406336 +1662064031024407296 +1662064031066408192 +1662064031114409216 +1662064031156410112 +1662064031204411136 +1662064031246412032 +1662064031291412992 +1662064031333413888 +1662064031378414848 +1662064031417415680 +1662064031459416576 +1662064031519417856 +1662064031564418816 +1662064031612419840 +1662064031654420736 +1662064031699421696 +1662064031747422720 +1662064031798423808 +1662064031846424832 +1662064031888425728 +1662064031930426624 +1662064031972427520 +1662064032014428416 +1662064032056429312 +1662064032098430208 +1662064032143431168 +1662064032188432128 +1662064032230433024 +1662064032272433920 +1662064032314434816 +1662064032356435712 +1662064032401436672 +1662064032443437568 +1662064032488438528 +1662064032530439424 +1662064032584440576 +1662064032623441408 +1662064032665442304 +1662064032716443392 +1662064032758444288 +1662064032800445184 +1662064032845446144 +1662064032899447296 +1662064032947448320 +1662064032989449216 +1662064033031450112 +1662064033070450944 +1662064033112451840 +1662064033154452736 +1662064033205453824 +1662064033247454720 +1662064033295455744 +1662064033337456640 +1662064033385457664 +1662064033427458560 +1662064033472459520 +1662064033514460416 +1662064033559461376 +1662064033607462400 +1662064033652463360 +1662064033694464256 +1662064033736465152 +1662064033781466112 +1662064033826467072 +1662064033868467968 +1662064033910468864 +1662064033955469824 +1662064033997470720 +1662064034042471680 +1662064034084472576 +1662064034129473536 +1662064034168474368 +1662064034210475264 +1662064034252476160 +1662064034294477056 +1662064034336477952 +1662064034378478848 +1662064034417479680 +1662064034459480576 +1662064034504481536 +1662064034549482496 +1662064034597483520 +1662064034636484352 +1662064034681485312 +1662064034723486208 +1662064034765487104 +1662064034810488064 +1662064034855489024 +1662064034897489920 +1662064034936490752 +1662064034984491776 +1662064035032492800 +1662064035074493696 +1662064035122494720 +1662064035164495616 +1662064035206496512 +1662064035248497408 +1662064035290498304 +1662064035332499200 +1662064035374500096 +1662064035419501056 +1662064035458501888 +1662064035500502784 +1662064035542503680 +1662064035584504576 +1662064035626505472 +1662064035671506432 +1662064035713507328 +1662064035758508288 +1662064035806509312 +1662064035854510336 +1662064035896511232 +1662064035947512320 +1662064035995513344 +1662064036037514240 +1662064036085515264 +1662064036130516224 +1662064036172517120 +1662064036214518016 +1662064036256518912 +1662064036310520064 +1662064036352520960 +1662064036400521984 +1662064036445522944 +1662064036487523840 +1662064036529524736 +1662064036571525632 +1662064036613526528 +1662064036658527488 +1662064036697528320 +1662064036739529216 +1662064036787530240 +1662064036835531264 +1662064036877532160 +1662064036922533120 +1662064036967534080 +1662064037015535104 +1662064037057536000 +1662064037099536896 +1662064037147537920 +1662064037189538816 +1662064037234539776 +1662064037282540800 +1662064037324541696 +1662064037369542656 +1662064037408543488 +1662064037450544384 +1662064037492545280 +1662064037534546176 +1662064037576547072 +1662064037621548032 +1662064037663548928 +1662064037705549824 +1662064037750550784 +1662064037795551744 +1662064037843552768 +1662064037885553664 +1662064037930554624 +1662064037972555520 +1662064038014556416 +1662064038056557312 +1662064038104558336 +1662064038149559296 +1662064038191560192 +1662064038239561216 +1662064038281562112 +1662064038323563008 +1662064038365563904 +1662064038413564928 +1662064038455565824 +1662064038497566720 +1662064038542567680 +1662064038590568704 +1662064038638569728 +1662064038680570624 +1662064038719571456 +1662064038761572352 +1662064038806573312 +1662064038851574272 +1662064038896575232 +1662064038938576128 +1662064038983577088 +1662064039028578048 +1662064039076579072 +1662064039118579968 +1662064039160580864 +1662064039205581824 +1662064039253582848 +1662064039295583744 +1662064039340584704 +1662064039382585600 +1662064039424586496 +1662064039469587456 +1662064039508588288 +1662064039550589184 +1662064039595590144 +1662064039637591040 +1662064039685592064 +1662064039727592960 +1662064039766593792 +1662064039811594752 +1662064039853595648 +1662064039898596608 +1662064039940597504 +1662064039982598400 +1662064040024599296 +1662064040072600320 +1662064040114601216 +1662064040162602240 +1662064040207603200 +1662064040252604160 +1662064040303605248 +1662064040348606208 +1662064040390607104 +1662064040435608064 +1662064040477608960 +1662064040519609856 +1662064040561610752 +1662064040603611648 +1662064040642612480 +1662064040699613696 +1662064040738614528 +1662064040777615360 +1662064040819616256 +1662064040864617216 +1662064040906618112 +1662064040945618944 +1662064040990619904 +1662064041032620800 +1662064041074621696 +1662064041122622720 +1662064041164623616 +1662064041209624576 +1662064041254625536 +1662064041296626432 +1662064041347627520 +1662064041395628544 +1662064041443629568 +1662064041488630528 +1662064041533631488 +1662064041584632576 +1662064041629633536 +1662064041671634432 +1662064041713635328 +1662064041755636224 +1662064041806637312 +1662064041845638144 +1662064041887639040 +1662064041932640000 +1662064041977640960 +1662064042025641984 +1662064042076643072 +1662064042121644032 +1662064042163644928 +1662064042205645824 +1662064042247646720 +1662064042292647680 +1662064042334648576 +1662064042379649536 +1662064042424650496 +1662064042466651392 +1662064042508652288 +1662064042553653248 +1662064042598654208 +1662064042646655232 +1662064042691656192 +1662064042733657088 +1662064042778658048 +1662064042829659136 +1662064042871660032 +1662064042916660992 +1662064042964662016 +1662064043015663104 +1662064043057664000 +1662064043108665088 +1662064043153666048 +1662064043198667008 +1662064043240667904 +1662064043288668928 +1662064043330669824 +1662064043378670848 +1662064043423671808 +1662064043471672832 +1662064043513673728 +1662064043558674688 +1662064043603675648 +1662064043657676800 +1662064043705677824 +1662064043750678784 +1662064043792679680 +1662064043843680768 +1662064043882681600 +1662064043927682560 +1662064043966683392 +1662064044011684352 +1662064044062685440 +1662064044107686400 +1662064044146687232 +1662064044197688320 +1662064044239689216 +1662064044290690304 +1662064044332691200 +1662064044383692288 +1662064044431693312 +1662064044473694208 +1662064044515695104 +1662064044563696128 +1662064044602696960 +1662064044647697920 +1662064044698699008 +1662064044743699968 +1662064044788700928 +1662064044830701824 +1662064044872702720 +1662064044923703808 +1662064044965704704 +1662064045016705792 +1662064045058706688 +1662064045100707584 +1662064045145708544 +1662064045187709440 +1662064045238710528 +1662064045280711424 +1662064045328712448 +1662064045370713344 +1662064045415714304 +1662064045454715136 +1662064045496716032 +1662064045544717056 +1662064045589718016 +1662064045634718976 +1662064045679719936 +1662064045721720832 +1662064045763721728 +1662064045805722624 +1662064045850723584 +1662064045895724544 +1662064045940725504 +1662064045982726400 +1662064046027727360 +1662064046075728384 +1662064046123729408 +1662064046165730304 +1662064046207731200 +1662064046258732288 +1662064046303733248 +1662064046351734272 +1662064046396735232 +1662064046441736192 +1662064046492737280 +1662064046534738176 +1662064046576739072 +1662064046621740032 +1662064046666740992 +1662064046711741952 +1662064046756742912 +1662064046804743936 +1662064046846744832 +1662064046885745664 +1662064046927746560 +1662064046969747456 +1662064047014748416 +1662064047056749312 +1662064047101750272 +1662064047149751296 +1662064047194752256 +1662064047239753216 +1662064047284754176 +1662064047326755072 +1662064047371756032 +1662064047419757056 +1662064047464758016 +1662064047509758976 +1662064047554759936 +1662064047605761024 +1662064047653762048 +1662064047707763200 +1662064047752764160 +1662064047794765056 +1662064047836765952 +1662064047878766848 +1662064047923767808 +1662064047965768704 +1662064048010769664 +1662064048052770560 +1662064048094771456 +1662064048142772480 +1662064048184773376 +1662064048226774272 +1662064048277775360 +1662064048319776256 +1662064048361777152 +1662064048406778112 +1662064048448779008 +1662064048493779968 +1662064048535780864 +1662064048577781760 +1662064048619782656 +1662064048664783616 +1662064048706784512 +1662064048754785536 +1662064048793786368 +1662064048832787200 +1662064048877788160 +1662064048922789120 +1662064048967790080 +1662064049009790976 +1662064049048791808 +1662064049096792832 +1662064049141793792 +1662064049186794752 +1662064049234795776 +1662064049276796672 +1662064049318797568 +1662064049366798592 +1662064049408799488 +1662064049450800384 +1662064049495801344 +1662064049537802240 +1662064049576803072 +1662064049618803968 +1662064049660804864 +1662064049702805760 +1662064049744806656 +1662064049789807616 +1662064049834808576 +1662064049876809472 +1662064049918810368 +1662064049960811264 +1662064050002812160 +1662064050053813248 +1662064050095814144 +1662064050137815040 +1662064050179815936 +1662064050221816832 +1662064050263817728 +1662064050305818624 +1662064050347819520 +1662064050389820416 +1662064050434821376 +1662064050482822400 +1662064050524823296 +1662064050584824576 +1662064050626825472 +1662064050668826368 +1662064050713827328 +1662064050755828224 +1662064050797829120 +1662064050845830144 +1662064050887831040 +1662064050932832000 +1662064050977832960 +1662064051016833792 +1662064051070834944 +1662064051115835904 +1662064051157836800 +1662064051199837696 +1662064051241838592 +1662064051283839488 +1662064051325840384 +1662064051367841280 +1662064051409842176 +1662064051454843136 +1662064051499844096 +1662064051544845056 +1662064051592846080 +1662064051631846912 +1662064051673847808 +1662064051715848704 +1662064051763849728 +1662064051808850688 +1662064051853851648 +1662064051901852672 +1662064051943853568 +1662064051985854464 +1662064052036855552 +1662064052081856512 +1662064052129857536 +1662064052171858432 +1662064052213859328 +1662064052261860352 +1662064052303861248 +1662064052345862144 +1662064052387863040 +1662064052438864128 +1662064052483865088 +1662064052525865984 +1662064052573867008 +1662064052624868096 +1662064052669869056 +1662064052714870016 +1662064052759870976 +1662064052795871744 +1662064052840872704 +1662064052885873664 +1662064052924874496 +1662064052969875456 +1662064053011876352 +1662064053056877312 +1662064053098878208 +1662064053143879168 +1662064053188880128 +1662064053233881088 +1662064053278882048 +1662064053323883008 +1662064053365883904 +1662064053407884800 +1662064053452885760 +1662064053491886592 +1662064053533887488 +1662064053575888384 +1662064053614889216 +1662064053659890176 +1662064053698891008 +1662064053746892032 +1662064053791892992 +1662064053842894080 +1662064053884894976 +1662064053929895936 +1662064053974896896 +1662064054019897856 +1662064054061898752 +1662064054103899648 +1662064054142900480 +1662064054184901376 +1662064054223902208 +1662064054265903104 +1662064054307904000 +1662064054355905024 +1662064054409906176 +1662064054457907200 +1662064054502908160 +1662064054541908992 +1662064054589910016 +1662064054631910912 +1662064054676911872 +1662064054727912960 +1662064054772913920 +1662064054814914816 +1662064054865915904 +1662064054910916864 +1662064054946917632 +1662064054997918720 +1662064055042919680 +1662064055090920704 +1662064055138921728 +1662064055180922624 +1662064055225923584 +1662064055270924544 +1662064055315925504 +1662064055360926464 diff --git a/Examples/Stereo/MIMIR_TimeStamps/SandPipe_track0_light.txt b/Examples/Stereo/MIMIR_TimeStamps/SandPipe_track0_light.txt new file mode 100644 index 0000000000..b9447370b4 --- /dev/null +++ b/Examples/Stereo/MIMIR_TimeStamps/SandPipe_track0_light.txt @@ -0,0 +1,2605 @@ +1662121584099220736 +1662121584144221696 +1662121584186222592 +1662121584234223616 +1662121584279224576 +1662121584321225472 +1662121584369226496 +1662121584417227520 +1662121584459228416 +1662121584498229248 +1662121584540230144 +1662121584582231040 +1662121584624231936 +1662121584669232896 +1662121584717233920 +1662121584762234880 +1662121584807235840 +1662121584855236864 +1662121584900237824 +1662121584942238720 +1662121584987239680 +1662121585032240640 +1662121585074241536 +1662121585119242496 +1662121585161243392 +1662121585203244288 +1662121585251245312 +1662121585296246272 +1662121585338247168 +1662121585389248256 +1662121585434249216 +1662121585476250112 +1662121585524251136 +1662121585575252224 +1662121585617253120 +1662121585671254272 +1662121585716255232 +1662121585758256128 +1662121585803257088 +1662121585845257984 +1662121585887258880 +1662121585932259840 +1662121585977260800 +1662121586019261696 +1662121586061262592 +1662121586106263552 +1662121586151264512 +1662121586193265408 +1662121586235266304 +1662121586277267200 +1662121586319268096 +1662121586364269056 +1662121586409270016 +1662121586460271104 +1662121586502272000 +1662121586553273088 +1662121586595273984 +1662121586634274816 +1662121586679275776 +1662121586724276736 +1662121586766277632 +1662121586823278848 +1662121586868279808 +1662121586916280832 +1662121586961281792 +1662121587003282688 +1662121587048283648 +1662121587093284608 +1662121587135285504 +1662121587177286400 +1662121587216287232 +1662121587258288128 +1662121587303289088 +1662121587345289984 +1662121587387290880 +1662121587429291776 +1662121587474292736 +1662121587522293760 +1662121587567294720 +1662121587615295744 +1662121587657296640 +1662121587702297600 +1662121587747298560 +1662121587789299456 +1662121587834300416 +1662121587876301312 +1662121587921302272 +1662121587966303232 +1662121588008304128 +1662121588053305088 +1662121588101306112 +1662121588143307008 +1662121588197308160 +1662121588245309184 +1662121588290310144 +1662121588332311040 +1662121588383312128 +1662121588428313088 +1662121588470313984 +1662121588512314880 +1662121588557315840 +1662121588602316800 +1662121588644317696 +1662121588686318592 +1662121588737319680 +1662121588779320576 +1662121588821321472 +1662121588872322560 +1662121588914323456 +1662121588962324480 +1662121589004325376 +1662121589043326208 +1662121589088327168 +1662121589130328064 +1662121589172328960 +1662121589214329856 +1662121589265330944 +1662121589307331840 +1662121589349332736 +1662121589397333760 +1662121589439334656 +1662121589478335488 +1662121589520336384 +1662121589565337344 +1662121589604338176 +1662121589646339072 +1662121589691340032 +1662121589739341056 +1662121589784342016 +1662121589826342912 +1662121589871343872 +1662121589919344896 +1662121589961345792 +1662121590003346688 +1662121590051347712 +1662121590093348608 +1662121590135349504 +1662121590183350528 +1662121590228351488 +1662121590279352576 +1662121590321353472 +1662121590360354304 +1662121590405355264 +1662121590447356160 +1662121590492357120 +1662121590540358144 +1662121590579358976 +1662121590621359872 +1662121590663360768 +1662121590705361664 +1662121590747362560 +1662121590792363520 +1662121590837364480 +1662121590885365504 +1662121590927366400 +1662121590969367296 +1662121591014368256 +1662121591062369280 +1662121591107370240 +1662121591155371264 +1662121591194372096 +1662121591236372992 +1662121591284374016 +1662121591329374976 +1662121591374375936 +1662121591428377088 +1662121591473378048 +1662121591518379008 +1662121591560379904 +1662121591611380992 +1662121591650381824 +1662121591701382912 +1662121591743383808 +1662121591785384704 +1662121591830385664 +1662121591875386624 +1662121591917387520 +1662121591962388480 +1662121592007389440 +1662121592049390336 +1662121592091391232 +1662121592133392128 +1662121592175393024 +1662121592226394112 +1662121592268395008 +1662121592313395968 +1662121592352396800 +1662121592391397632 +1662121592439398656 +1662121592496399872 +1662121592538400768 +1662121592583401728 +1662121592625402624 +1662121592670403584 +1662121592712404480 +1662121592751405312 +1662121592799406336 +1662121592844407296 +1662121592883408128 +1662121592925409024 +1662121592970409984 +1662121593024411136 +1662121593069412096 +1662121593114413056 +1662121593156413952 +1662121593201414912 +1662121593246415872 +1662121593294416896 +1662121593342417920 +1662121593390418944 +1662121593444420096 +1662121593486420992 +1662121593531421952 +1662121593576422912 +1662121593627424000 +1662121593672424960 +1662121593726426112 +1662121593777427200 +1662121593816428032 +1662121593855428864 +1662121593900429824 +1662121593948430848 +1662121594005432064 +1662121594050433024 +1662121594092433920 +1662121594143435008 +1662121594185435904 +1662121594230436864 +1662121594278437888 +1662121594323438848 +1662121594371439872 +1662121594416440832 +1662121594461441792 +1662121594503442688 +1662121594551443712 +1662121594599444736 +1662121594641445632 +1662121594683446528 +1662121594725447424 +1662121594770448384 +1662121594812449280 +1662121594857450240 +1662121594899451136 +1662121594941452032 +1662121594983452928 +1662121595034454016 +1662121595076454912 +1662121595124455936 +1662121595184457216 +1662121595226458112 +1662121595274459136 +1662121595316460032 +1662121595361460992 +1662121595406461952 +1662121595454462976 +1662121595496463872 +1662121595541464832 +1662121595583465728 +1662121595631466752 +1662121595676467712 +1662121595724468736 +1662121595772469760 +1662121595826470912 +1662121595868471808 +1662121595919472896 +1662121595964473856 +1662121596006474752 +1662121596051475712 +1662121596099476736 +1662121596144477696 +1662121596186478592 +1662121596234479616 +1662121596276480512 +1662121596318481408 +1662121596357482240 +1662121596399483136 +1662121596447484160 +1662121596489485056 +1662121596534486016 +1662121596576486912 +1662121596630488064 +1662121596675489024 +1662121596720489984 +1662121596768491008 +1662121596819492096 +1662121596861492992 +1662121596912494080 +1662121596951494912 +1662121596993495808 +1662121597038496768 +1662121597083497728 +1662121597125498624 +1662121597173499648 +1662121597215500544 +1662121597260501504 +1662121597305502464 +1662121597344503296 +1662121597389504256 +1662121597443505408 +1662121597485506304 +1662121597524507136 +1662121597572508160 +1662121597617509120 +1662121597662510080 +1662121597710511104 +1662121597761512192 +1662121597812513280 +1662121597863514368 +1662121597908515328 +1662121597950516224 +1662121598001517312 +1662121598043518208 +1662121598097519360 +1662121598148520448 +1662121598190521344 +1662121598238522368 +1662121598283523328 +1662121598334524416 +1662121598379525376 +1662121598427526400 +1662121598472527360 +1662121598520528384 +1662121598565529344 +1662121598607530240 +1662121598652531200 +1662121598694532096 +1662121598742533120 +1662121598781533952 +1662121598823534848 +1662121598868535808 +1662121598913536768 +1662121598955537664 +1662121598997538560 +1662121599042539520 +1662121599090540544 +1662121599135541504 +1662121599183542528 +1662121599231543552 +1662121599279544576 +1662121599324545536 +1662121599369546496 +1662121599411547392 +1662121599456548352 +1662121599498549248 +1662121599543550208 +1662121599585551104 +1662121599633552128 +1662121599678553088 +1662121599717553920 +1662121599762554880 +1662121599807555840 +1662121599852556800 +1662121599894557696 +1662121599936558592 +1662121599984559616 +1662121600026560512 +1662121600071561472 +1662121600122562560 +1662121600179563776 +1662121600221564672 +1662121600263565568 +1662121600302566400 +1662121600350567424 +1662121600395568384 +1662121600437569280 +1662121600482570240 +1662121600536571392 +1662121600581572352 +1662121600623573248 +1662121600665574144 +1662121600710575104 +1662121600752576000 +1662121600806577152 +1662121600848578048 +1662121600890578944 +1662121600932579840 +1662121600974580736 +1662121601025581824 +1662121601070582784 +1662121601115583744 +1662121601157584640 +1662121601205585664 +1662121601247586560 +1662121601289587456 +1662121601337588480 +1662121601382589440 +1662121601433590528 +1662121601475591424 +1662121601517592320 +1662121601559593216 +1662121601604594176 +1662121601652595200 +1662121601697596160 +1662121601742597120 +1662121601784598016 +1662121601835599104 +1662121601880600064 +1662121601928601088 +1662121601970601984 +1662121602027603200 +1662121602075604224 +1662121602117605120 +1662121602162606080 +1662121602204606976 +1662121602255608064 +1662121602297608960 +1662121602336609792 +1662121602378610688 +1662121602426611712 +1662121602468612608 +1662121602519613696 +1662121602555614464 +1662121602600615424 +1662121602645616384 +1662121602699617536 +1662121602741618432 +1662121602783619328 +1662121602825620224 +1662121602867621120 +1662121602909622016 +1662121602951622912 +1662121602999623936 +1662121603047624960 +1662121603089625856 +1662121603140626944 +1662121603185627904 +1662121603227628800 +1662121603281629952 +1662121603326630912 +1662121603368631808 +1662121603422632960 +1662121603467633920 +1662121603509634816 +1662121603563635968 +1662121603608636928 +1662121603650637824 +1662121603692638720 +1662121603734639616 +1662121603776640512 +1662121603818641408 +1662121603860642304 +1662121603905643264 +1662121603953644288 +1662121604001645312 +1662121604043646208 +1662121604088647168 +1662121604133648128 +1662121604175649024 +1662121604217649920 +1662121604262650880 +1662121604307651840 +1662121604355652864 +1662121604394653696 +1662121604442654720 +1662121604484655616 +1662121604523656448 +1662121604574657536 +1662121604619658496 +1662121604664659456 +1662121604709660416 +1662121604754661376 +1662121604805662464 +1662121604850663424 +1662121604895664384 +1662121604940665344 +1662121604988666368 +1662121605042667520 +1662121605084668416 +1662121605129669376 +1662121605174670336 +1662121605216671232 +1662121605255672064 +1662121605300673024 +1662121605342673920 +1662121605396675072 +1662121605438675968 +1662121605480676864 +1662121605528677888 +1662121605573678848 +1662121605618679808 +1662121605663680768 +1662121605705681664 +1662121605747682560 +1662121605798683648 +1662121605840684544 +1662121605882685440 +1662121605930686464 +1662121605975687424 +1662121606017688320 +1662121606059689216 +1662121606104690176 +1662121606146691072 +1662121606188691968 +1662121606230692864 +1662121606275693824 +1662121606323694848 +1662121606368695808 +1662121606413696768 +1662121606455697664 +1662121606497698560 +1662121606542699520 +1662121606587700480 +1662121606626701312 +1662121606665702144 +1662121606710703104 +1662121606758704128 +1662121606803705088 +1662121606857706240 +1662121606902707200 +1662121606944708096 +1662121606986708992 +1662121607031709952 +1662121607076710912 +1662121607124711936 +1662121607169712896 +1662121607217713920 +1662121607262714880 +1662121607304715776 +1662121607346716672 +1662121607391717632 +1662121607436718592 +1662121607487719680 +1662121607532720640 +1662121607577721600 +1662121607628722688 +1662121607670723584 +1662121607715724544 +1662121607763725568 +1662121607805726464 +1662121607847727360 +1662121607889728256 +1662121607928729088 +1662121607970729984 +1662121608018731008 +1662121608060731904 +1662121608102732800 +1662121608147733760 +1662121608198734848 +1662121608246735872 +1662121608288736768 +1662121608333737728 +1662121608375738624 +1662121608426739712 +1662121608468740608 +1662121608510741504 +1662121608552742400 +1662121608597743360 +1662121608639744256 +1662121608681745152 +1662121608729746176 +1662121608777747200 +1662121608822748160 +1662121608867749120 +1662121608909750016 +1662121608951750912 +1662121609002752000 +1662121609044752896 +1662121609086753792 +1662121609134754816 +1662121609182755840 +1662121609230756864 +1662121609272757760 +1662121609317758720 +1662121609359759616 +1662121609398760448 +1662121609443761408 +1662121609491762432 +1662121609533763328 +1662121609575764224 +1662121609617765120 +1662121609662766080 +1662121609710767104 +1662121609755768064 +1662121609797768960 +1662121609839769856 +1662121609884770816 +1662121609935771904 +1662121609977772800 +1662121610022773760 +1662121610064774656 +1662121610106775552 +1662121610151776512 +1662121610196777472 +1662121610238778368 +1662121610292779520 +1662121610331780352 +1662121610382781440 +1662121610427782400 +1662121610469783296 +1662121610511784192 +1662121610559785216 +1662121610604786176 +1662121610646787072 +1662121610691788032 +1662121610733788928 +1662121610787790080 +1662121610832791040 +1662121610874791936 +1662121610922792960 +1662121610964793856 +1662121611006794752 +1662121611048795648 +1662121611096796672 +1662121611147797760 +1662121611198798848 +1662121611252800000 +1662121611294800896 +1662121611336801792 +1662121611381802752 +1662121611432803840 +1662121611474804736 +1662121611519805696 +1662121611561806592 +1662121611603807488 +1662121611651808512 +1662121611702809600 +1662121611747810560 +1662121611789811456 +1662121611834812416 +1662121611879813376 +1662121611927814400 +1662121611972815360 +1662121612017816320 +1662121612062817280 +1662121612107818240 +1662121612152819200 +1662121612194820096 +1662121612236820992 +1662121612278821888 +1662121612323822848 +1662121612368823808 +1662121612410824704 +1662121612449825536 +1662121612491826432 +1662121612548827648 +1662121612593828608 +1662121612635829504 +1662121612683830528 +1662121612731831552 +1662121612770832384 +1662121612818833408 +1662121612860834304 +1662121612902835200 +1662121612947836160 +1662121612989837056 +1662121613037838080 +1662121613082839040 +1662121613124839936 +1662121613166840832 +1662121613211841792 +1662121613259842816 +1662121613307843840 +1662121613349844736 +1662121613397845760 +1662121613442846720 +1662121613484847616 +1662121613526848512 +1662121613577849600 +1662121613625850624 +1662121613670851584 +1662121613724852736 +1662121613769853696 +1662121613817854720 +1662121613859855616 +1662121613907856640 +1662121613958857728 +1662121614009858816 +1662121614054859776 +1662121614096860672 +1662121614138861568 +1662121614177862400 +1662121614219863296 +1662121614267864320 +1662121614318865408 +1662121614360866304 +1662121614405867264 +1662121614450868224 +1662121614492869120 +1662121614540870144 +1662121614582871040 +1662121614630872064 +1662121614672872960 +1662121614720873984 +1662121614768875008 +1662121614816876032 +1662121614855876864 +1662121614897877760 +1662121614939878656 +1662121614987879680 +1662121615032880640 +1662121615077881600 +1662121615119882496 +1662121615164883456 +1662121615209884416 +1662121615254885376 +1662121615302886400 +1662121615350887424 +1662121615395888384 +1662121615443889408 +1662121615488890368 +1662121615530891264 +1662121615584892416 +1662121615626893312 +1662121615668894208 +1662121615707895040 +1662121615752896000 +1662121615800897024 +1662121615845897984 +1662121615896899072 +1662121615947900160 +1662121615992901120 +1662121616034902016 +1662121616079902976 +1662121616127904000 +1662121616178905088 +1662121616223906048 +1662121616268907008 +1662121616316908032 +1662121616358908928 +1662121616412910080 +1662121616463911168 +1662121616505912064 +1662121616547912960 +1662121616589913856 +1662121616634914816 +1662121616679915776 +1662121616727916800 +1662121616769917696 +1662121616823918848 +1662121616865919744 +1662121616913920768 +1662121616955921664 +1662121616997922560 +1662121617045923584 +1662121617087924480 +1662121617132925440 +1662121617177926400 +1662121617222927360 +1662121617264928256 +1662121617312929280 +1662121617360930304 +1662121617402931200 +1662121617444932096 +1662121617501933312 +1662121617543934208 +1662121617591935232 +1662121617639936256 +1662121617690937344 +1662121617741938432 +1662121617789939456 +1662121617831940352 +1662121617873941248 +1662121617918942208 +1662121617966943232 +1662121618014944256 +1662121618062945280 +1662121618104946176 +1662121618149947136 +1662121618200948224 +1662121618245949184 +1662121618287950080 +1662121618326950912 +1662121618368951808 +1662121618410952704 +1662121618452953600 +1662121618500954624 +1662121618545955584 +1662121618599956736 +1662121618641957632 +1662121618686958592 +1662121618728959488 +1662121618770960384 +1662121618815961344 +1662121618863962368 +1662121618905963264 +1662121618947964160 +1662121618992965120 +1662121619034966016 +1662121619079966976 +1662121619124967936 +1662121619166968832 +1662121619211969792 +1662121619253970688 +1662121619304971776 +1662121619346972672 +1662121619400973824 +1662121619442974720 +1662121619490975744 +1662121619535976704 +1662121619577977600 +1662121619619978496 +1662121619667979520 +1662121619706980352 +1662121619751981312 +1662121619802982400 +1662121619847983360 +1662121619892984320 +1662121619937985280 +1662121619979986176 +1662121620027987200 +1662121620075988224 +1662121620117989120 +1662121620162990080 +1662121620207991040 +1662121620252992000 +1662121620306993152 +1662121620351994112 +1662121620396995072 +1662121620438995968 +1662121620480996864 +1662121620525997824 +1662121620570998784 +1662121620615999744 +1662121620658000640 +1662121620703001600 +1662121620757002752 +1662121620799003648 +1662121620847004672 +1662121620892005632 +1662121620934006528 +1662121620976007424 +1662121621018008320 +1662121621060009216 +1662121621111010304 +1662121621159011328 +1662121621204012288 +1662121621246013184 +1662121621291014144 +1662121621330014976 +1662121621372015872 +1662121621414016768 +1662121621462017792 +1662121621507018752 +1662121621555019776 +1662121621594020608 +1662121621645021696 +1662121621687022592 +1662121621729023488 +1662121621774024448 +1662121621816025344 +1662121621861026304 +1662121621912027392 +1662121621957028352 +1662121622005029376 +1662121622050030336 +1662121622095031296 +1662121622137032192 +1662121622182033152 +1662121622227034112 +1662121622272035072 +1662121622323036160 +1662121622374037248 +1662121622413038080 +1662121622458039040 +1662121622503040000 +1662121622548040960 +1662121622593041920 +1662121622638042880 +1662121622686043904 +1662121622731044864 +1662121622773045760 +1662121622818046720 +1662121622863047680 +1662121622908048640 +1662121622953049600 +1662121623001050624 +1662121623049051648 +1662121623097052672 +1662121623148053760 +1662121623193054720 +1662121623238055680 +1662121623295056896 +1662121623340057856 +1662121623385058816 +1662121623427059712 +1662121623472060672 +1662121623514061568 +1662121623559062528 +1662121623604063488 +1662121623658064640 +1662121623700065536 +1662121623742066432 +1662121623784067328 +1662121623829068288 +1662121623877069312 +1662121623919070208 +1662121623961071104 +1662121624006072064 +1662121624051073024 +1662121624093073920 +1662121624135074816 +1662121624180075776 +1662121624225076736 +1662121624279077888 +1662121624324078848 +1662121624369079808 +1662121624411080704 +1662121624456081664 +1662121624498082560 +1662121624543083520 +1662121624594084608 +1662121624642085632 +1662121624687086592 +1662121624735087616 +1662121624780088576 +1662121624828089600 +1662121624879090688 +1662121624924091648 +1662121624966092544 +1662121625020093696 +1662121625065094656 +1662121625107095552 +1662121625152096512 +1662121625197097472 +1662121625239098368 +1662121625284099328 +1662121625335100416 +1662121625380101376 +1662121625425102336 +1662121625467103232 +1662121625512104192 +1662121625560105216 +1662121625608106240 +1662121625653107200 +1662121625698108160 +1662121625752109312 +1662121625797110272 +1662121625839111168 +1662121625887112192 +1662121625929113088 +1662121625977114112 +1662121626016114944 +1662121626058115840 +1662121626100116736 +1662121626148117760 +1662121626193118720 +1662121626241119744 +1662121626283120640 +1662121626325121536 +1662121626370122496 +1662121626412123392 +1662121626457124352 +1662121626502125312 +1662121626544126208 +1662121626589127168 +1662121626631128064 +1662121626673128960 +1662121626715129856 +1662121626760130816 +1662121626808131840 +1662121626859132928 +1662121626904133888 +1662121626952134912 +1662121626997135872 +1662121627042136832 +1662121627090137856 +1662121627135138816 +1662121627177139712 +1662121627228140800 +1662121627276141824 +1662121627318142720 +1662121627360143616 +1662121627405144576 +1662121627447145472 +1662121627498146560 +1662121627549147648 +1662121627597148672 +1662121627639149568 +1662121627690150656 +1662121627732151552 +1662121627774152448 +1662121627816153344 +1662121627858154240 +1662121627900155136 +1662121627942156032 +1662121627984156928 +1662121628029157888 +1662121628071158784 +1662121628119159808 +1662121628173160960 +1662121628212161792 +1662121628254162688 +1662121628299163648 +1662121628350164736 +1662121628398165760 +1662121628440166656 +1662121628488167680 +1662121628533168640 +1662121628581169664 +1662121628623170560 +1662121628671171584 +1662121628722172672 +1662121628770173696 +1662121628818174720 +1662121628860175616 +1662121628908176640 +1662121628953177600 +1662121629001178624 +1662121629049179648 +1662121629094180608 +1662121629145181696 +1662121629196182784 +1662121629244183808 +1662121629289184768 +1662121629331185664 +1662121629376186624 +1662121629424187648 +1662121629472188672 +1662121629517189632 +1662121629571190784 +1662121629616191744 +1662121629661192704 +1662121629703193600 +1662121629739194368 +1662121629787195392 +1662121629838196480 +1662121629883197440 +1662121629931198464 +1662121629973199360 +1662121630015200256 +1662121630057201152 +1662121630102202112 +1662121630153203200 +1662121630195204096 +1662121630237204992 +1662121630282205952 +1662121630324206848 +1662121630369207808 +1662121630423208960 +1662121630474210048 +1662121630525211136 +1662121630582212352 +1662121630621213184 +1662121630660214016 +1662121630702214912 +1662121630750215936 +1662121630792216832 +1662121630843217920 +1662121630885218816 +1662121630933219840 +1662121630975220736 +1662121631026221824 +1662121631068222720 +1662121631119223808 +1662121631167224832 +1662121631212225792 +1662121631254226688 +1662121631305227776 +1662121631347228672 +1662121631389229568 +1662121631431230464 +1662121631482231552 +1662121631530232576 +1662121631575233536 +1662121631620234496 +1662121631662235392 +1662121631707236352 +1662121631752237312 +1662121631800238336 +1662121631854239488 +1662121631896240384 +1662121631938241280 +1662121631983242240 +1662121632022243072 +1662121632064243968 +1662121632109244928 +1662121632154245888 +1662121632196246784 +1662121632244247808 +1662121632289248768 +1662121632334249728 +1662121632382250752 +1662121632424251648 +1662121632466252544 +1662121632508253440 +1662121632553254400 +1662121632598255360 +1662121632649256448 +1662121632697257472 +1662121632751258624 +1662121632793259520 +1662121632838260480 +1662121632883261440 +1662121632925262336 +1662121632976263424 +1662121633018264320 +1662121633066265344 +1662121633111266304 +1662121633159267328 +1662121633204268288 +1662121633246269184 +1662121633291270144 +1662121633339271168 +1662121633390272256 +1662121633435273216 +1662121633477274112 +1662121633519275008 +1662121633564275968 +1662121633609276928 +1662121633651277824 +1662121633696278784 +1662121633738279680 +1662121633786280704 +1662121633828281600 +1662121633876282624 +1662121633921283584 +1662121633963284480 +1662121634008285440 +1662121634050286336 +1662121634098287360 +1662121634143288320 +1662121634185289216 +1662121634233290240 +1662121634281291264 +1662121634320292096 +1662121634368293120 +1662121634422294272 +1662121634467295232 +1662121634515296256 +1662121634554297088 +1662121634602298112 +1662121634644299008 +1662121634692300032 +1662121634746301184 +1662121634797302272 +1662121634842303232 +1662121634884304128 +1662121634929305088 +1662121634980306176 +1662121635022307072 +1662121635073308160 +1662121635124309248 +1662121635169310208 +1662121635211311104 +1662121635262312192 +1662121635307313152 +1662121635349314048 +1662121635391314944 +1662121635436315904 +1662121635484316928 +1662121635526317824 +1662121635574318848 +1662121635622319872 +1662121635670320896 +1662121635724322048 +1662121635769323008 +1662121635811323904 +1662121635853324800 +1662121635901325824 +1662121635946326784 +1662121635991327744 +1662121636033328640 +1662121636078329600 +1662121636123330560 +1662121636174331648 +1662121636219332608 +1662121636267333632 +1662121636309334528 +1662121636351335424 +1662121636396336384 +1662121636438337280 +1662121636480338176 +1662121636525339136 +1662121636567340032 +1662121636609340928 +1662121636657341952 +1662121636702342912 +1662121636744343808 +1662121636789344768 +1662121636840345856 +1662121636894347008 +1662121636942348032 +1662121636987348992 +1662121637029349888 +1662121637074350848 +1662121637125351936 +1662121637170352896 +1662121637212353792 +1662121637254354688 +1662121637302355712 +1662121637350356736 +1662121637398357760 +1662121637443358720 +1662121637485359616 +1662121637533360640 +1662121637587361792 +1662121637632362752 +1662121637677363712 +1662121637719364608 +1662121637761365504 +1662121637803366400 +1662121637848367360 +1662121637887368192 +1662121637929369088 +1662121637974370048 +1662121638019371008 +1662121638061371904 +1662121638103372800 +1662121638145373696 +1662121638190374656 +1662121638232375552 +1662121638277376512 +1662121638319377408 +1662121638361378304 +1662121638406379264 +1662121638448380160 +1662121638490381056 +1662121638532381952 +1662121638574382848 +1662121638616383744 +1662121638655384576 +1662121638703385600 +1662121638748386560 +1662121638799387648 +1662121638841388544 +1662121638895389696 +1662121638937390592 +1662121638979391488 +1662121639024392448 +1662121639063393280 +1662121639105394176 +1662121639159395328 +1662121639204396288 +1662121639249397248 +1662121639300398336 +1662121639342399232 +1662121639387400192 +1662121639432401152 +1662121639477402112 +1662121639519403008 +1662121639564403968 +1662121639609404928 +1662121639651405824 +1662121639699406848 +1662121639750407936 +1662121639792408832 +1662121639834409728 +1662121639876410624 +1662121639924411648 +1662121639969412608 +1662121640011413504 +1662121640062414592 +1662121640113415680 +1662121640155416576 +1662121640197417472 +1662121640239418368 +1662121640284419328 +1662121640326420224 +1662121640371421184 +1662121640419422208 +1662121640464423168 +1662121640506424064 +1662121640554425088 +1662121640590425856 +1662121640644427008 +1662121640692428032 +1662121640737428992 +1662121640785430016 +1662121640824430848 +1662121640866431744 +1662121640911432704 +1662121640959433728 +1662121641004434688 +1662121641049435648 +1662121641091436544 +1662121641142437632 +1662121641193438720 +1662121641238439680 +1662121641283440640 +1662121641337441792 +1662121641379442688 +1662121641421443584 +1662121641463444480 +1662121641505445376 +1662121641550446336 +1662121641601447424 +1662121641643448320 +1662121641694449408 +1662121641739450368 +1662121641778451200 +1662121641823452160 +1662121641868453120 +1662121641907453952 +1662121641952454912 +1662121641997455872 +1662121642042456832 +1662121642090457856 +1662121642132458752 +1662121642174459648 +1662121642219460608 +1662121642264461568 +1662121642312462592 +1662121642354463488 +1662121642399464448 +1662121642441465344 +1662121642483466240 +1662121642528467200 +1662121642570468096 +1662121642612468992 +1662121642660470016 +1662121642705470976 +1662121642747471872 +1662121642801473024 +1662121642843473920 +1662121642891474944 +1662121642939475968 +1662121642981476864 +1662121643023477760 +1662121643065478656 +1662121643107479552 +1662121643149480448 +1662121643191481344 +1662121643233482240 +1662121643275483136 +1662121643317484032 +1662121643362484992 +1662121643410486016 +1662121643455486976 +1662121643503488000 +1662121643542488832 +1662121643587489792 +1662121643629490688 +1662121643674491648 +1662121643719492608 +1662121643764493568 +1662121643806494464 +1662121643845495296 +1662121643887496192 +1662121643932497152 +1662121643983498240 +1662121644034499328 +1662121644079500288 +1662121644121501184 +1662121644160502016 +1662121644208503040 +1662121644250503936 +1662121644295504896 +1662121644337505792 +1662121644385506816 +1662121644433507840 +1662121644478508800 +1662121644526509824 +1662121644568510720 +1662121644613511680 +1662121644658512640 +1662121644706513664 +1662121644748514560 +1662121644799515648 +1662121644853516800 +1662121644898517760 +1662121644940518656 +1662121644988519680 +1662121645033520640 +1662121645078521600 +1662121645120522496 +1662121645162523392 +1662121645210524416 +1662121645252525312 +1662121645300526336 +1662121645342527232 +1662121645384528128 +1662121645426529024 +1662121645468529920 +1662121645510530816 +1662121645561531904 +1662121645603532800 +1662121645645533696 +1662121645690534656 +1662121645735535616 +1662121645780536576 +1662121645825537536 +1662121645870538496 +1662121645912539392 +1662121645957540352 +1662121646005541376 +1662121646053542400 +1662121646107543552 +1662121646149544448 +1662121646197545472 +1662121646239546368 +1662121646281547264 +1662121646329548288 +1662121646371549184 +1662121646419550208 +1662121646470551296 +1662121646521552384 +1662121646566553344 +1662121646611554304 +1662121646653555200 +1662121646698556160 +1662121646737556992 +1662121646779557888 +1662121646824558848 +1662121646869559808 +1662121646911560704 +1662121646956561664 +1662121646998562560 +1662121647040563456 +1662121647085564416 +1662121647127565312 +1662121647172566272 +1662121647214567168 +1662121647262568192 +1662121647304569088 +1662121647352570112 +1662121647400571136 +1662121647451572224 +1662121647496573184 +1662121647547574272 +1662121647589575168 +1662121647634576128 +1662121647676577024 +1662121647727578112 +1662121647784579328 +1662121647832580352 +1662121647874581248 +1662121647931582464 +1662121647973583360 +1662121648015584256 +1662121648069585408 +1662121648114586368 +1662121648156587264 +1662121648198588160 +1662121648240589056 +1662121648288590080 +1662121648336591104 +1662121648393592320 +1662121648435593216 +1662121648477594112 +1662121648519595008 +1662121648573596160 +1662121648627597312 +1662121648678598400 +1662121648723599360 +1662121648768600320 +1662121648813601280 +1662121648852602112 +1662121648894603008 +1662121648939603968 +1662121648981604864 +1662121649023605760 +1662121649080606976 +1662121649125607936 +1662121649167608832 +1662121649209609728 +1662121649251610624 +1662121649302611712 +1662121649341612544 +1662121649392613632 +1662121649437614592 +1662121649479615488 +1662121649521616384 +1662121649569617408 +1662121649614618368 +1662121649653619200 +1662121649692620032 +1662121649740621056 +1662121649785622016 +1662121649830622976 +1662121649875623936 +1662121649920624896 +1662121649971625984 +1662121650013626880 +1662121650058627840 +1662121650106628864 +1662121650148629760 +1662121650193630720 +1662121650241631744 +1662121650286632704 +1662121650331633664 +1662121650376634624 +1662121650424635648 +1662121650466636544 +1662121650517637632 +1662121650559638528 +1662121650601639424 +1662121650646640384 +1662121650688641280 +1662121650730642176 +1662121650772643072 +1662121650823644160 +1662121650868645120 +1662121650910646016 +1662121650952646912 +1662121651000647936 +1662121651042648832 +1662121651087649792 +1662121651129650688 +1662121651171651584 +1662121651213652480 +1662121651255653376 +1662121651300654336 +1662121651345655296 +1662121651384656128 +1662121651429657088 +1662121651477658112 +1662121651525659136 +1662121651573660160 +1662121651618661120 +1662121651669662208 +1662121651714663168 +1662121651765664256 +1662121651816665344 +1662121651864666368 +1662121651909667328 +1662121651951668224 +1662121652002669312 +1662121652050670336 +1662121652101671424 +1662121652143672320 +1662121652188673280 +1662121652236674304 +1662121652284675328 +1662121652335676416 +1662121652377677312 +1662121652425678336 +1662121652479679488 +1662121652521680384 +1662121652560681216 +1662121652608682240 +1662121652665683456 +1662121652707684352 +1662121652749685248 +1662121652791686144 +1662121652839687168 +1662121652881688064 +1662121652923688960 +1662121652971689984 +1662121653013690880 +1662121653055691776 +1662121653100692736 +1662121653142693632 +1662121653184694528 +1662121653229695488 +1662121653271696384 +1662121653319697408 +1662121653358698240 +1662121653403699200 +1662121653445700096 +1662121653487700992 +1662121653532701952 +1662121653577702912 +1662121653625703936 +1662121653670704896 +1662121653712705792 +1662121653754706688 +1662121653799707648 +1662121653841708544 +1662121653883709440 +1662121653934710528 +1662121653979711488 +1662121654024712448 +1662121654066713344 +1662121654108714240 +1662121654162715392 +1662121654210716416 +1662121654252717312 +1662121654300718336 +1662121654342719232 +1662121654387720192 +1662121654432721152 +1662121654471721984 +1662121654519723008 +1662121654564723968 +1662121654606724864 +1662121654657725952 +1662121654696726784 +1662121654738727680 +1662121654789728768 +1662121654831729664 +1662121654876730624 +1662121654918731520 +1662121654963732480 +1662121655002733312 +1662121655044734208 +1662121655086735104 +1662121655131736064 +1662121655176737024 +1662121655221737984 +1662121655278739200 +1662121655323740160 +1662121655365741056 +1662121655410742016 +1662121655455742976 +1662121655500743936 +1662121655539744768 +1662121655596745984 +1662121655638746880 +1662121655680747776 +1662121655722748672 +1662121655764749568 +1662121655806750464 +1662121655848751360 +1662121655893752320 +1662121655935753216 +1662121655977754112 +1662121656028755200 +1662121656073756160 +1662121656124757248 +1662121656172758272 +1662121656214759168 +1662121656262760192 +1662121656307761152 +1662121656355762176 +1662121656403763200 +1662121656445764096 +1662121656493765120 +1662121656544766208 +1662121656589767168 +1662121656631768064 +1662121656670768896 +1662121656715769856 +1662121656757770752 +1662121656805771776 +1662121656859772928 +1662121656901773824 +1662121656949774848 +1662121656991775744 +1662121657033776640 +1662121657075777536 +1662121657123778560 +1662121657168779520 +1662121657210780416 +1662121657258781440 +1662121657312782592 +1662121657360783616 +1662121657405784576 +1662121657453785600 +1662121657501786624 +1662121657546787584 +1662121657591788544 +1662121657636789504 +1662121657681790464 +1662121657723791360 +1662121657768792320 +1662121657813793280 +1662121657852794112 +1662121657897795072 +1662121657939795968 +1662121657984796928 +1662121658026797824 +1662121658068798720 +1662121658113799680 +1662121658158800640 +1662121658200801536 +1662121658254802688 +1662121658302803712 +1662121658350804736 +1662121658404805888 +1662121658446806784 +1662121658491807744 +1662121658536808704 +1662121658575809536 +1662121658626810624 +1662121658668811520 +1662121658716812544 +1662121658758813440 +1662121658809814528 +1662121658851815424 +1662121658905816576 +1662121658947817472 +1662121658989818368 +1662121659031819264 +1662121659076820224 +1662121659121821184 +1662121659166822144 +1662121659208823040 +1662121659253824000 +1662121659307825152 +1662121659361826304 +1662121659406827264 +1662121659454828288 +1662121659502829312 +1662121659547830272 +1662121659589831168 +1662121659640832256 +1662121659685833216 +1662121659739834368 +1662121659787835392 +1662121659835836416 +1662121659880837376 +1662121659925838336 +1662121659970839296 +1662121660012840192 +1662121660063841280 +1662121660108842240 +1662121660150843136 +1662121660195844096 +1662121660240845056 +1662121660288846080 +1662121660339847168 +1662121660387848192 +1662121660429849088 +1662121660474850048 +1662121660528851200 +1662121660570852096 +1662121660615853056 +1662121660657853952 +1662121660702854912 +1662121660747855872 +1662121660798856960 +1662121660840857856 +1662121660882858752 +1662121660924859648 +1662121660972860672 +1662121661020861696 +1662121661062862592 +1662121661104863488 +1662121661152864512 +1662121661197865472 +1662121661239866368 +1662121661284867328 +1662121661329868288 +1662121661374869248 +1662121661422870272 +1662121661470871296 +1662121661512872192 +1662121661557873152 +1662121661605874176 +1662121661650875136 +1662121661698876160 +1662121661740877056 +1662121661782877952 +1662121661833879040 +1662121661887880192 +1662121661929881088 +1662121661974882048 +1662121662013882880 +1662121662055883776 +1662121662103884800 +1662121662148885760 +1662121662190886656 +1662121662232887552 +1662121662283888640 +1662121662328889600 +1662121662370890496 +1662121662418891520 +1662121662463892480 +1662121662511893504 +1662121662556894464 +1662121662604895488 +1662121662649896448 +1662121662688897280 +1662121662736898304 +1662121662778899200 +1662121662823900160 +1662121662868901120 +1662121662913902080 +1662121662958903040 +1662121663006904064 +1662121663051905024 +1662121663102906112 +1662121663147907072 +1662121663195908096 +1662121663243909120 +1662121663282909952 +1662121663324910848 +1662121663366911744 +1662121663414912768 +1662121663459913728 +1662121663504914688 +1662121663549915648 +1662121663597916672 +1662121663639917568 +1662121663681918464 +1662121663723919360 +1662121663765920256 +1662121663810921216 +1662121663855922176 +1662121663903923200 +1662121663948924160 +1662121663993925120 +1662121664035926016 +1662121664089927168 +1662121664134928128 +1662121664182929152 +1662121664224930048 +1662121664272931072 +1662121664320932096 +1662121664365933056 +1662121664413934080 +1662121664461935104 +1662121664512936192 +1662121664554937088 +1662121664596937984 +1662121664647939072 +1662121664701940224 +1662121664752941312 +1662121664809942528 +1662121664854943488 +1662121664899944448 +1662121664941945344 +1662121664983946240 +1662121665037947392 +1662121665079948288 +1662121665121949184 +1662121665163950080 +1662121665214951168 +1662121665262952192 +1662121665307953152 +1662121665355954176 +1662121665400955136 +1662121665445956096 +1662121665502957312 +1662121665547958272 +1662121665592959232 +1662121665640960256 +1662121665685961216 +1662121665730962176 +1662121665772963072 +1662121665817964032 +1662121665856964864 +1662121665904965888 +1662121665946966784 +1662121665988967680 +1662121666030968576 +1662121666078969600 +1662121666120970496 +1662121666162971392 +1662121666210972416 +1662121666255973376 +1662121666297974272 +1662121666345975296 +1662121666390976256 +1662121666432977152 +1662121666474978048 +1662121666519979008 +1662121666567980032 +1662121666612980992 +1662121666666982144 +1662121666705982976 +1662121666756984064 +1662121666801985024 +1662121666858986240 +1662121666900987136 +1662121666942988032 +1662121666987988992 +1662121667041990144 +1662121667089991168 +1662121667137992192 +1662121667185993216 +1662121667230994176 +1662121667275995136 +1662121667320996096 +1662121667362996992 +1662121667410998016 +1662121667455998976 +1662121667500999936 +1662121667546000896 +1662121667594001920 +1662121667642002944 +1662121667687003904 +1662121667729004800 +1662121667771005696 +1662121667816006656 +1662121667861007616 +1662121667903008512 +1662121667957009664 +1662121667999010560 +1662121668041011456 +1662121668089012480 +1662121668134013440 +1662121668179014400 +1662121668224015360 +1662121668278016512 +1662121668323017472 +1662121668374018560 +1662121668413019392 +1662121668458020352 +1662121668500021248 +1662121668539022080 +1662121668581022976 +1662121668626023936 +1662121668668024832 +1662121668710025728 +1662121668752026624 +1662121668797027584 +1662121668842028544 +1662121668884029440 +1662121668926030336 +1662121668974031360 +1662121669019032320 +1662121669061033216 +1662121669103034112 +1662121669154035200 +1662121669199036160 +1662121669241037056 +1662121669283037952 +1662121669325038848 +1662121669367039744 +1662121669409040640 +1662121669454041600 +1662121669511042816 +1662121669556043776 +1662121669595044608 +1662121669634045440 +1662121669673046272 +1662121669715047168 +1662121669760048128 +1662121669802049024 +1662121669856050176 +1662121669901051136 +1662121669943052032 +1662121669988052992 +1662121670036054016 +1662121670081054976 +1662121670123055872 +1662121670165056768 +1662121670219057920 +1662121670267058944 +1662121670315059968 +1662121670360060928 +1662121670411062016 +1662121670456062976 +1662121670507064064 +1662121670561065216 +1662121670606066176 +1662121670654067200 +1662121670699068160 +1662121670753069312 +1662121670789070080 +1662121670831070976 +1662121670873071872 +1662121670921072896 +1662121670963073792 +1662121671005074688 +1662121671047075584 +1662121671089076480 +1662121671137077504 +1662121671179078400 +1662121671221079296 +1662121671263080192 +1662121671317081344 +1662121671359082240 +1662121671401083136 +1662121671443084032 +1662121671485084928 +1662121671536086016 +1662121671578086912 +1662121671620087808 +1662121671671088896 +1662121671713089792 +1662121671758090752 +1662121671800091648 +1662121671842092544 +1662121671893093632 +1662121671935094528 +1662121671977095424 +1662121672025096448 +1662121672073097472 +1662121672115098368 +1662121672157099264 +1662121672208100352 +1662121672259101440 +1662121672304102400 +1662121672349103360 +1662121672394104320 +1662121672436105216 +1662121672484106240 +1662121672526107136 +1662121672574108160 +1662121672616109056 +1662121672664110080 +1662121672709111040 +1662121672754112000 +1662121672799112960 +1662121672841113856 +1662121672886114816 +1662121672934115840 +1662121672985116928 +1662121673027117824 +1662121673066118656 +1662121673111119616 +1662121673159120640 +1662121673204121600 +1662121673243122432 +1662121673288123392 +1662121673339124480 +1662121673387125504 +1662121673435126528 +1662121673489127680 +1662121673537128704 +1662121673582129664 +1662121673639130880 +1662121673681131776 +1662121673726132736 +1662121673768133632 +1662121673819134720 +1662121673861135616 +1662121673906136576 +1662121673963137792 +1662121674002138624 +1662121674050139648 +1662121674092140544 +1662121674137141504 +1662121674182142464 +1662121674230143488 +1662121674275144448 +1662121674323145472 +1662121674365146368 +1662121674413147392 +1662121674458148352 +1662121674500149248 +1662121674542150144 +1662121674587151104 +1662121674629152000 +1662121674674152960 +1662121674719153920 +1662121674767154944 +1662121674818156032 +1662121674863156992 +1662121674917158144 +1662121674959159040 +1662121675007160064 +1662121675046160896 +1662121675094161920 +1662121675136162816 +1662121675178163712 +1662121675226164736 +1662121675268165632 +1662121675313166592 +1662121675355167488 +1662121675400168448 +1662121675445169408 +1662121675493170432 +1662121675535171328 +1662121675580172288 +1662121675625173248 +1662121675667174144 +1662121675709175040 +1662121675751175936 +1662121675799176960 +1662121675847177984 +1662121675892178944 +1662121675937179904 +1662121675979180800 +1662121676021181696 +1662121676066182656 +1662121676108183552 +1662121676153184512 +1662121676207185664 +1662121676249186560 +1662121676294187520 +1662121676339188480 +1662121676387189504 +1662121676432190464 +1662121676474191360 +1662121676519192320 +1662121676567193344 +1662121676621194496 +1662121676666195456 +1662121676708196352 +1662121676756197376 +1662121676798198272 +1662121676852199424 +1662121676903200512 +1662121676948201472 +1662121676993202432 +1662121677035203328 +1662121677083204352 +1662121677134205440 +1662121677188206592 +1662121677236207616 +1662121677278208512 +1662121677317209344 +1662121677365210368 +1662121677407211264 +1662121677449212160 +1662121677491213056 +1662121677533213952 +1662121677575214848 +1662121677617215744 +1662121677659216640 +1662121677701217536 +1662121677743218432 +1662121677785219328 +1662121677827220224 +1662121677869221120 +1662121677914222080 +1662121677956222976 +1662121678004224000 +1662121678055225088 +1662121678094225920 +1662121678136226816 +1662121678187227904 +1662121678229228800 +1662121678274229760 +1662121678319230720 +1662121678367231744 +1662121678412232704 +1662121678469233920 +1662121678520235008 +1662121678565235968 +1662121678607236864 +1662121678649237760 +1662121678691238656 +1662121678733239552 +1662121678775240448 +1662121678817241344 +1662121678862242304 +1662121678907243264 +1662121678952244224 +1662121679009245440 +1662121679051246336 +1662121679093247232 +1662121679138248192 +1662121679186249216 +1662121679228250112 +1662121679273251072 +1662121679321252096 +1662121679372253184 +1662121679420254208 +1662121679462255104 +1662121679504256000 +1662121679549256960 +1662121679594257920 +1662121679639258880 +1662121679684259840 +1662121679729260800 +1662121679768261632 +1662121679810262528 +1662121679861263616 +1662121679903264512 +1662121679948265472 +1662121679996266496 +1662121680035267328 +1662121680080268288 +1662121680125269248 +1662121680167270144 +1662121680218271232 +1662121680263272192 +1662121680305273088 +1662121680347273984 +1662121680392274944 +1662121680437275904 +1662121680479276800 +1662121680530277888 +1662121680578278912 +1662121680629280000 +1662121680671280896 +1662121680713281792 +1662121680761282816 +1662121680803283712 +1662121680851284736 +1662121680896285696 +1662121680935286528 +1662121680974287360 +1662121681016288256 +1662121681064289280 +1662121681109290240 +1662121681157291264 +1662121681208292352 +1662121681250293248 +1662121681295294208 +1662121681340295168 +1662121681391296256 +1662121681436297216 +1662121681484298240 +1662121681535299328 +1662121681577300224 +1662121681622301184 +1662121681673302272 +1662121681724303360 +1662121681772304384 +1662121681817305344 +1662121681862306304 +1662121681910307328 +1662121681958308352 +1662121682000309248 +1662121682048310272 +1662121682090311168 +1662121682132312064 +1662121682180313088 +1662121682225314048 +1662121682270315008 +1662121682321316096 +1662121682369317120 +1662121682417318144 +1662121682459319040 +1662121682504320000 +1662121682546320896 +1662121682597321984 +1662121682639322880 +1662121682684323840 +1662121682735324928 +1662121682789326080 +1662121682831326976 +1662121682873327872 +1662121682921328896 +1662121682966329856 +1662121683014330880 +1662121683062331904 +1662121683107332864 +1662121683161334016 +1662121683203334912 +1662121683248335872 +1662121683296336896 +1662121683341337856 +1662121683386338816 +1662121683434339840 +1662121683482340864 +1662121683527341824 +1662121683575342848 +1662121683623343872 +1662121683668344832 +1662121683713345792 +1662121683761346816 +1662121683806347776 +1662121683848348672 +1662121683899349760 +1662121683941350656 +1662121683983351552 +1662121684025352448 +1662121684067353344 +1662121684109354240 +1662121684157355264 +1662121684202356224 +1662121684250357248 +1662121684298358272 +1662121684346359296 +1662121684391360256 +1662121684433361152 +1662121684475362048 +1662121684517362944 +1662121684562363904 +1662121684616365056 +1662121684661366016 +1662121684703366912 +1662121684754368000 +1662121684799368960 +1662121684850370048 +1662121684898371072 +1662121684940371968 +1662121684997373184 +1662121685036374016 +1662121685081374976 +1662121685123375872 +1662121685171376896 +1662121685228378112 +1662121685282379264 +1662121685330380288 +1662121685375381248 +1662121685420382208 +1662121685468383232 +1662121685510384128 +1662121685561385216 +1662121685609386240 +1662121685651387136 +1662121685693388032 +1662121685738388992 +1662121685783389952 +1662121685834391040 +1662121685897392384 +1662121685948393472 +1662121685993394432 +1662121686044395520 +1662121686086396416 +1662121686131397376 +1662121686176398336 +1662121686215399168 +1662121686260400128 +1662121686305401088 +1662121686353402112 +1662121686404403200 +1662121686449404160 +1662121686491405056 +1662121686533405952 +1662121686575406848 +1662121686626407936 +1662121686668408832 +1662121686716409856 +1662121686767410944 +1662121686812411904 +1662121686854412800 +1662121686899413760 +1662121686941414656 +1662121686992415744 +1662121687040416768 +1662121687085417728 +1662121687133418752 +1662121687175419648 +1662121687217420544 +1662121687265421568 +1662121687307422464 +1662121687352423424 +1662121687397424384 +1662121687445425408 +1662121687490426368 +1662121687532427264 +1662121687574428160 +1662121687619429120 +1662121687664430080 +1662121687709431040 +1662121687751431936 +1662121687793432832 +1662121687832433664 +1662121687880434688 +1662121687928435712 +1662121687970436608 +1662121688018437632 +1662121688069438720 +1662121688126439936 +1662121688171440896 +1662121688216441856 +1662121688258442752 +1662121688303443712 +1662121688345444608 +1662121688387445504 +1662121688429446400 +1662121688474447360 +1662121688522448384 +1662121688570449408 +1662121688609450240 +1662121688651451136 +1662121688705452288 +1662121688747453184 +1662121688795454208 +1662121688840455168 +1662121688885456128 +1662121688924456960 +1662121688975458048 +1662121689017458944 +1662121689059459840 +1662121689101460736 +1662121689149461760 +1662121689194462720 +1662121689239463680 +1662121689287464704 +1662121689329465600 +1662121689380466688 +1662121689422467584 +1662121689467468544 +1662121689509469440 +1662121689554470400 +1662121689602471424 +1662121689644472320 +1662121689686473216 +1662121689734474240 +1662121689773475072 +1662121689812475904 +1662121689857476864 +1662121689908477952 +1662121689950478848 +1662121689995479808 +1662121690046480896 +1662121690094481920 +1662121690139482880 +1662121690178483712 +1662121690220484608 +1662121690268485632 +1662121690313486592 +1662121690361487616 +1662121690403488512 +1662121690454489600 +1662121690496490496 +1662121690538491392 +1662121690583492352 +1662121690625493248 +1662121690673494272 +1662121690721495296 +1662121690766496256 +1662121690805497088 +1662121690850498048 +1662121690892498944 +1662121690934499840 +1662121690976500736 +1662121691027501824 +1662121691072502784 +1662121691114503680 +1662121691156504576 +1662121691201505536 +1662121691246506496 +1662121691297507584 +1662121691342508544 +1662121691384509440 +1662121691429510400 +1662121691471511296 +1662121691522512384 +1662121691564513280 +1662121691612514304 +1662121691660515328 +1662121691705516288 +1662121691747517184 +1662121691792518144 +1662121691834519040 +1662121691885520128 +1662121691927521024 +1662121691969521920 +1662121692023523072 +1662121692068524032 +1662121692125525248 +1662121692182526464 +1662121692224527360 +1662121692266528256 +1662121692311529216 +1662121692359530240 +1662121692407531264 +1662121692449532160 +1662121692491533056 +1662121692545534208 +1662121692593535232 +1662121692644536320 +1662121692686537216 +1662121692731538176 +1662121692779539200 +1662121692818540032 +1662121692866541056 +1662121692911542016 +1662121692956542976 +1662121692998543872 +1662121693046544896 +1662121693097545984 +1662121693139546880 +1662121693184547840 +1662121693229548800 +1662121693277549824 +1662121693322550784 +1662121693364551680 +1662121693409552640 +1662121693457553664 +1662121693502554624 +1662121693547555584 +1662121693589556480 +1662121693634557440 +1662121693673558272 +1662121693718559232 +1662121693763560192 +1662121693805561088 +1662121693847561984 +1662121693895563008 +1662121693937563904 +1662121693982564864 +1662121694033565952 +1662121694081566976 +1662121694132568064 +1662121694177569024 +1662121694219569920 +1662121694267570944 +1662121694312571904 +1662121694360572928 +1662121694408573952 +1662121694462575104 +1662121694507576064 +1662121694549576960 +1662121694594577920 +1662121694636578816 +1662121694678579712 +1662121694729580800 +1662121694771581696 +1662121694822582784 +1662121694864583680 +1662121694909584640 +1662121694951585536 +1662121695002586624 +1662121695047587584 +1662121695089588480 +1662121695137589504 +1662121695185590528 +1662121695227591424 +1662121695269592320 +1662121695311593216 +1662121695353594112 +1662121695398595072 +1662121695449596160 +1662121695491597056 +1662121695548598272 +1662121695593599232 +1662121695638600192 +1662121695683601152 +1662121695725602048 +1662121695767602944 +1662121695809603840 +1662121695854604800 +1662121695896605696 +1662121695947606784 +1662121695998607872 +1662121696046608896 +1662121696091609856 +1662121696151611136 +1662121696202612224 +1662121696250613248 +1662121696298614272 +1662121696340615168 +1662121696385616128 +1662121696433617152 +1662121696478618112 +1662121696526619136 +1662121696571620096 +1662121696616621056 +1662121696661622016 +1662121696709623040 +1662121696757624064 +1662121696802625024 +1662121696847625984 +1662121696889626880 +1662121696943628032 +1662121696985628928 +1662121697036630016 +1662121697084631040 +1662121697123631872 +1662121697171632896 +1662121697219633920 +1662121697267634944 +1662121697312635904 +1662121697354636800 +1662121697399637760 +1662121697441638656 +1662121697489639680 +1662121697534640640 +1662121697582641664 +1662121697633642752 +1662121697678643712 +1662121697732644864 +1662121697780645888 +1662121697831646976 +1662121697873647872 +1662121697915648768 +1662121697960649728 +1662121698005650688 +1662121698047651584 +1662121698098652672 +1662121698143653632 +1662121698191654656 +1662121698242655744 +1662121698287656704 +1662121698329657600 +1662121698371658496 +1662121698413659392 +1662121698458660352 +1662121698506661376 +1662121698554662400 +1662121698602663424 +1662121698647664384 +1662121698689665280 +1662121698737666304 +1662121698782667264 +1662121698827668224 +1662121698866669056 +1662121698914670080 +1662121698959671040 +1662121699004672000 +1662121699049672960 +1662121699094673920 +1662121699136674816 +1662121699181675776 +1662121699226676736 +1662121699268677632 +1662121699310678528 +1662121699358679552 +1662121699400680448 +1662121699445681408 +1662121699487682304 +1662121699532683264 +1662121699577684224 +1662121699622685184 +1662121699667686144 +1662121699709687040 +1662121699763688192 +1662121699814689280 +1662121699856690176 +1662121699898691072 +1662121699946692096 +1662121700003693312 +1662121700048694272 +1662121700096695296 +1662121700138696192 +1662121700177697024 +1662121700219697920 +1662121700267698944 +1662121700312699904 +1662121700357700864 +1662121700408701952 +1662121700453702912 +1662121700495703808 +1662121700546704896 +1662121700597705984 +1662121700642706944 +1662121700684707840 +1662121700729708800 +1662121700774709760 +1662121700816710656 +1662121700864711680 +1662121700906712576 +1662121700960713728 +1662121701011714816 +1662121701053715712 +1662121701095716608 +1662121701140717568 +1662121701191718656 +1662121701233719552 +1662121701278720512 +1662121701326721536 +1662121701371722496 +1662121701413723392 +1662121701461724416 +1662121701503725312 +1662121701545726208 +1662121701584727040 +1662121701629728000 +1662121701677729024 +1662121701722729984 +1662121701770731008 +1662121701812731904 +1662121701857732864 +1662121701902733824 diff --git a/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt b/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt new file mode 100644 index 0000000000..23ef73aa69 --- /dev/null +++ b/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt @@ -0,0 +1,2934 @@ +1662064490014331136 +1662064490059332096 +1662064490101332992 +1662064490140333824 +1662064490188334848 +1662064490233335808 +1662064490275336704 +1662064490323337728 +1662064490371338752 +1662064490419339776 +1662064490461340672 +1662064490506341632 +1662064490548342528 +1662064490590343424 +1662064490632344320 +1662064490671345152 +1662064490710345984 +1662064490749346816 +1662064490794347776 +1662064490836348672 +1662064490878349568 +1662064490920350464 +1662064490962351360 +1662064491007352320 +1662064491049353216 +1662064491088354048 +1662064491130354944 +1662064491175355904 +1662064491223356928 +1662064491265357824 +1662064491307358720 +1662064491352359680 +1662064491397360640 +1662064491439361536 +1662064491481362432 +1662064491523363328 +1662064491562364160 +1662064491601364992 +1662064491643365888 +1662064491685366784 +1662064491727367680 +1662064491778368768 +1662064491820369664 +1662064491862370560 +1662064491904371456 +1662064491946372352 +1662064491985373184 +1662064492030374144 +1662064492072375040 +1662064492117376000 +1662064492159376896 +1662064492201377792 +1662064492246378752 +1662064492288379648 +1662064492330380544 +1662064492372381440 +1662064492411382272 +1662064492456383232 +1662064492501384192 +1662064492543385088 +1662064492588386048 +1662064492630386944 +1662064492669387776 +1662064492714388736 +1662064492756389632 +1662064492801390592 +1662064492846391552 +1662064492885392384 +1662064492927393280 +1662064492975394304 +1662064493017395200 +1662064493065396224 +1662064493107397120 +1662064493149398016 +1662064493188398848 +1662064493236399872 +1662064493284400896 +1662064493329401856 +1662064493374402816 +1662064493419403776 +1662064493464404736 +1662064493506405632 +1662064493554406656 +1662064493596407552 +1662064493638408448 +1662064493680409344 +1662064493722410240 +1662064493767411200 +1662064493815412224 +1662064493857413120 +1662064493899414016 +1662064493938414848 +1662064493983415808 +1662064494028416768 +1662064494073417728 +1662064494115418624 +1662064494160419584 +1662064494205420544 +1662064494244421376 +1662064494289422336 +1662064494331423232 +1662064494379424256 +1662064494418425088 +1662064494463426048 +1662064494505426944 +1662064494547427840 +1662064494589428736 +1662064494631429632 +1662064494670430464 +1662064494721431552 +1662064494766432512 +1662064494811433472 +1662064494853434368 +1662064494895435264 +1662064494937436160 +1662064494976436992 +1662064495018437888 +1662064495063438848 +1662064495108439808 +1662064495147440640 +1662064495189441536 +1662064495231442432 +1662064495273443328 +1662064495321444352 +1662064495366445312 +1662064495408446208 +1662064495450447104 +1662064495486447872 +1662064495528448768 +1662064495570449664 +1662064495615450624 +1662064495654451456 +1662064495699452416 +1662064495738453248 +1662064495783454208 +1662064495819454976 +1662064495861455872 +1662064495903456768 +1662064495945457664 +1662064495987458560 +1662064496026459392 +1662064496071460352 +1662064496116461312 +1662064496161462272 +1662064496200463104 +1662064496242464000 +1662064496284464896 +1662064496326465792 +1662064496365466624 +1662064496407467520 +1662064496452468480 +1662064496494469376 +1662064496536470272 +1662064496578471168 +1662064496623472128 +1662064496668473088 +1662064496707473920 +1662064496752474880 +1662064496794475776 +1662064496833476608 +1662064496875477504 +1662064496917478400 +1662064496959479296 +1662064497004480256 +1662064497046481152 +1662064497091482112 +1662064497133483008 +1662064497175483904 +1662064497217484800 +1662064497256485632 +1662064497295486464 +1662064497334487296 +1662064497379488256 +1662064497424489216 +1662064497463490048 +1662064497505490944 +1662064497550491904 +1662064497589492736 +1662064497631493632 +1662064497676494592 +1662064497727495680 +1662064497769496576 +1662064497811497472 +1662064497853498368 +1662064497892499200 +1662064497934500096 +1662064497973500928 +1662064498012501760 +1662064498057502720 +1662064498102503680 +1662064498147504640 +1662064498189505536 +1662064498234506496 +1662064498276507392 +1662064498318508288 +1662064498363509248 +1662064498408510208 +1662064498450511104 +1662064498492512000 +1662064498534512896 +1662064498579513856 +1662064498615514624 +1662064498654515456 +1662064498696516352 +1662064498741517312 +1662064498777518080 +1662064498813518848 +1662064498855519744 +1662064498903520768 +1662064498948521728 +1662064498993522688 +1662064499035523584 +1662064499080524544 +1662064499122525440 +1662064499161526272 +1662064499206527232 +1662064499242528000 +1662064499284528896 +1662064499323529728 +1662064499365530624 +1662064499404531456 +1662064499446532352 +1662064499494533376 +1662064499542534400 +1662064499590535424 +1662064499629536256 +1662064499671537152 +1662064499716538112 +1662064499761539072 +1662064499800539904 +1662064499839540736 +1662064499884541696 +1662064499923542528 +1662064499968543488 +1662064500016544512 +1662064500064545536 +1662064500109546496 +1662064500148547328 +1662064500190548224 +1662064500235549184 +1662064500277550080 +1662064500322551040 +1662064500367552000 +1662064500409552896 +1662064500451553792 +1662064500496554752 +1662064500541555712 +1662064500583556608 +1662064500625557504 +1662064500670558464 +1662064500712559360 +1662064500757560320 +1662064500799561216 +1662064500841562112 +1662064500883563008 +1662064500925563904 +1662064500970564864 +1662064501015565824 +1662064501060566784 +1662064501102567680 +1662064501144568576 +1662064501192569600 +1662064501234570496 +1662064501276571392 +1662064501315572224 +1662064501354573056 +1662064501405574144 +1662064501447575040 +1662064501489575936 +1662064501534576896 +1662064501579577856 +1662064501621578752 +1662064501666579712 +1662064501714580736 +1662064501756581632 +1662064501798582528 +1662064501843583488 +1662064501885584384 +1662064501924585216 +1662064501969586176 +1662064502011587072 +1662064502053587968 +1662064502098588928 +1662064502143589888 +1662064502191590912 +1662064502236591872 +1662064502281592832 +1662064502320593664 +1662064502362594560 +1662064502398595328 +1662064502440596224 +1662064502485597184 +1662064502524598016 +1662064502566598912 +1662064502608599808 +1662064502653600768 +1662064502695601664 +1662064502737602560 +1662064502782603520 +1662064502827604480 +1662064502872605440 +1662064502917606400 +1662064502962607360 +1662064503007608320 +1662064503052609280 +1662064503100610304 +1662064503139611136 +1662064503178611968 +1662064503223612928 +1662064503268613888 +1662064503313614848 +1662064503355615744 +1662064503397616640 +1662064503442617600 +1662064503484618496 +1662064503526619392 +1662064503568620288 +1662064503610621184 +1662064503658622208 +1662064503703623168 +1662064503745624064 +1662064503790625024 +1662064503832625920 +1662064503874626816 +1662064503916627712 +1662064503958628608 +1662064504000629504 +1662064504042630400 +1662064504084631296 +1662064504126632192 +1662064504162632960 +1662064504204633856 +1662064504249634816 +1662064504294635776 +1662064504339636736 +1662064504381637632 +1662064504429638656 +1662064504468639488 +1662064504510640384 +1662064504558641408 +1662064504597642240 +1662064504645643264 +1662064504687644160 +1662064504729645056 +1662064504771645952 +1662064504813646848 +1662064504852647680 +1662064504897648640 +1662064504936649472 +1662064504975650304 +1662064505017651200 +1662064505059652096 +1662064505101652992 +1662064505143653888 +1662064505191654912 +1662064505236655872 +1662064505278656768 +1662064505320657664 +1662064505362658560 +1662064505407659520 +1662064505449660416 +1662064505497661440 +1662064505539662336 +1662064505578663168 +1662064505623664128 +1662064505668665088 +1662064505716666112 +1662064505758667008 +1662064505809668096 +1662064505848668928 +1662064505890669824 +1662064505938670848 +1662064505980671744 +1662064506022672640 +1662064506064673536 +1662064506106674432 +1662064506151675392 +1662064506196676352 +1662064506244677376 +1662064506289678336 +1662064506334679296 +1662064506376680192 +1662064506418681088 +1662064506454681856 +1662064506499682816 +1662064506544683776 +1662064506586684672 +1662064506631685632 +1662064506673686528 +1662064506715687424 +1662064506757688320 +1662064506796689152 +1662064506838690048 +1662064506880690944 +1662064506922691840 +1662064506970692864 +1662064507012693760 +1662064507057694720 +1662064507099695616 +1662064507141696512 +1662064507180697344 +1662064507219698176 +1662064507270699264 +1662064507315700224 +1662064507357701120 +1662064507405702144 +1662064507447703040 +1662064507486703872 +1662064507528704768 +1662064507570705664 +1662064507612706560 +1662064507654707456 +1662064507702708480 +1662064507747709440 +1662064507789710336 +1662064507834711296 +1662064507879712256 +1662064507930713344 +1662064507975714304 +1662064508014715136 +1662064508062716160 +1662064508107717120 +1662064508152718080 +1662064508194718976 +1662064508236719872 +1662064508281720832 +1662064508329721856 +1662064508362722560 +1662064508407723520 +1662064508455724544 +1662064508497725440 +1662064508539726336 +1662064508584727296 +1662064508623728128 +1662064508665729024 +1662064508710729984 +1662064508761731072 +1662064508806732032 +1662064508854733056 +1662064508899734016 +1662064508941734912 +1662064508983735808 +1662064509025736704 +1662064509070737664 +1662064509115738624 +1662064509151739392 +1662064509193740288 +1662064509235741184 +1662064509280742144 +1662064509325743104 +1662064509364743936 +1662064509406744832 +1662064509448745728 +1662064509490746624 +1662064509532747520 +1662064509574748416 +1662064509616749312 +1662064509661750272 +1662064509706751232 +1662064509751752192 +1662064509793753088 +1662064509835753984 +1662064509877754880 +1662064509922755840 +1662064509967756800 +1662064510009757696 +1662064510051758592 +1662064510099759616 +1662064510141760512 +1662064510183761408 +1662064510228762368 +1662064510273763328 +1662064510321764352 +1662064510363765248 +1662064510405766144 +1662064510453767168 +1662064510495768064 +1662064510540769024 +1662064510582769920 +1662064510621770752 +1662064510660771584 +1662064510702772480 +1662064510747773440 +1662064510789774336 +1662064510831775232 +1662064510870776064 +1662064510915777024 +1662064510957777920 +1662064510999778816 +1662064511041779712 +1662064511083780608 +1662064511122781440 +1662064511164782336 +1662064511206783232 +1662064511254784256 +1662064511296785152 +1662064511338786048 +1662064511383787008 +1662064511425787904 +1662064511473788928 +1662064511515789824 +1662064511557790720 +1662064511602791680 +1662064511644792576 +1662064511686793472 +1662064511725794304 +1662064511770795264 +1662064511809796096 +1662064511851796992 +1662064511896797952 +1662064511938798848 +1662064511980799744 +1662064512028800768 +1662064512070801664 +1662064512109802496 +1662064512151803392 +1662064512193804288 +1662064512235805184 +1662064512271805952 +1662064512322807040 +1662064512364807936 +1662064512406808832 +1662064512445809664 +1662064512484810496 +1662064512523811328 +1662064512568812288 +1662064512607813120 +1662064512646813952 +1662064512691814912 +1662064512733815808 +1662064512778816768 +1662064512820817664 +1662064512859818496 +1662064512904819456 +1662064512952820480 +1662064512997821440 +1662064513039822336 +1662064513081823232 +1662064513123824128 +1662064513165825024 +1662064513207825920 +1662064513252826880 +1662064513294827776 +1662064513339828736 +1662064513381829632 +1662064513423830528 +1662064513465831424 +1662064513507832320 +1662064513546833152 +1662064513588834048 +1662064513627834880 +1662064513672835840 +1662064513714836736 +1662064513756837632 +1662064513795838464 +1662064513834839296 +1662064513873840128 +1662064513915841024 +1662064513960841984 +1662064514008843008 +1662064514050843904 +1662064514095844864 +1662064514137845760 +1662064514179846656 +1662064514221847552 +1662064514266848512 +1662064514311849472 +1662064514350850304 +1662064514383851008 +1662064514425851904 +1662064514467852800 +1662064514512853760 +1662064514554854656 +1662064514596855552 +1662064514641856512 +1662064514683857408 +1662064514725858304 +1662064514767859200 +1662064514812860160 +1662064514854861056 +1662064514899862016 +1662064514944862976 +1662064514986863872 +1662064515028864768 +1662064515070865664 +1662064515112866560 +1662064515154867456 +1662064515205868544 +1662064515250869504 +1662064515295870464 +1662064515343871488 +1662064515388872448 +1662064515427873280 +1662064515472874240 +1662064515517875200 +1662064515556876032 +1662064515598876928 +1662064515637877760 +1662064515685878784 +1662064515727879680 +1662064515769880576 +1662064515817881600 +1662064515859882496 +1662064515898883328 +1662064515937884160 +1662064515985885184 +1662064516024886016 +1662064516063886848 +1662064516105887744 +1662064516144888576 +1662064516189889536 +1662064516228890368 +1662064516270891264 +1662064516315892224 +1662064516360893184 +1662064516402894080 +1662064516441894912 +1662064516483895808 +1662064516522896640 +1662064516558897408 +1662064516600898304 +1662064516639899136 +1662064516687900160 +1662064516729901056 +1662064516774902016 +1662064516819902976 +1662064516858903808 +1662064516900904704 +1662064516942905600 +1662064516984906496 +1662064517029907456 +1662064517071908352 +1662064517116909312 +1662064517158910208 +1662064517200911104 +1662064517254912256 +1662064517296913152 +1662064517338914048 +1662064517380914944 +1662064517419915776 +1662064517467916800 +1662064517512917760 +1662064517554918656 +1662064517605919744 +1662064517650920704 +1662064517692921600 +1662064517737922560 +1662064517779923456 +1662064517824924416 +1662064517863925248 +1662064517902926080 +1662064517947927040 +1662064517989927936 +1662064518028928768 +1662064518073929728 +1662064518118930688 +1662064518160931584 +1662064518199932416 +1662064518241933312 +1662064518280934144 +1662064518322935040 +1662064518361935872 +1662064518406936832 +1662064518448937728 +1662064518490938624 +1662064518532939520 +1662064518577940480 +1662064518622941440 +1662064518667942400 +1662064518709943296 +1662064518751944192 +1662064518793945088 +1662064518832945920 +1662064518874946816 +1662064518916947712 +1662064518964948736 +1662064519009949696 +1662064519048950528 +1662064519084951296 +1662064519126952192 +1662064519168953088 +1662064519210953984 +1662064519252954880 +1662064519288955648 +1662064519333956608 +1662064519378957568 +1662064519420958464 +1662064519462959360 +1662064519507960320 +1662064519546961152 +1662064519591962112 +1662064519639963136 +1662064519678963968 +1662064519717964800 +1662064519759965696 +1662064519804966656 +1662064519849967616 +1662064519888968448 +1662064519930969344 +1662064519975970304 +1662064520017971200 +1662064520062972160 +1662064520104973056 +1662064520149974016 +1662064520194974976 +1662064520239975936 +1662064520281976832 +1662064520323977728 +1662064520368978688 +1662064520416979712 +1662064520464980736 +1662064520506981632 +1662064520548982528 +1662064520593983488 +1662064520641984512 +1662064520683985408 +1662064520725986304 +1662064520767987200 +1662064520812988160 +1662064520854989056 +1662064520896989952 +1662064520938990848 +1662064520977991680 +1662064521022992640 +1662064521064993536 +1662064521106994432 +1662064521148995328 +1662064521187996160 +1662064521226996992 +1662064521268997888 +1662064521316998912 +1662064521361999872 +1662064521407000832 +1662064521449001728 +1662064521491002624 +1662064521536003584 +1662064521578004480 +1662064521620005376 +1662064521662006272 +1662064521707007232 +1662064521746008064 +1662064521788008960 +1662064521827009792 +1662064521869010688 +1662064521911011584 +1662064521950012416 +1662064521992013312 +1662064522034014208 +1662064522076015104 +1662064522118016000 +1662064522163016960 +1662064522205017856 +1662064522247018752 +1662064522286019584 +1662064522328020480 +1662064522370021376 +1662064522412022272 +1662064522457023232 +1662064522499024128 +1662064522538024960 +1662064522580025856 +1662064522625026816 +1662064522667027712 +1662064522709028608 +1662064522754029568 +1662064522793030400 +1662064522835031296 +1662064522877032192 +1662064522919033088 +1662064522961033984 +1662064523003034880 +1662064523045035776 +1662064523093036800 +1662064523138037760 +1662064523180038656 +1662064523225039616 +1662064523267040512 +1662064523312041472 +1662064523354042368 +1662064523396043264 +1662064523438044160 +1662064523480045056 +1662064523522045952 +1662064523561046784 +1662064523600047616 +1662064523645048576 +1662064523687049472 +1662064523735050496 +1662064523777051392 +1662064523819052288 +1662064523861053184 +1662064523903054080 +1662064523954055168 +1662064523996056064 +1662064524035056896 +1662064524083057920 +1662064524128058880 +1662064524170059776 +1662064524212060672 +1662064524254061568 +1662064524302062592 +1662064524344063488 +1662064524389064448 +1662064524431065344 +1662064524470066176 +1662064524512067072 +1662064524557068032 +1662064524596068864 +1662064524638069760 +1662064524677070592 +1662064524722071552 +1662064524761072384 +1662064524806073344 +1662064524851074304 +1662064524896075264 +1662064524932076032 +1662064524971076864 +1662064525013077760 +1662064525058078720 +1662064525106079744 +1662064525151080704 +1662064525196081664 +1662064525238082560 +1662064525280083456 +1662064525328084480 +1662064525367085312 +1662064525412086272 +1662064525454087168 +1662064525499088128 +1662064525544089088 +1662064525586089984 +1662064525628090880 +1662064525664091648 +1662064525712092672 +1662064525754093568 +1662064525802094592 +1662064525847095552 +1662064525889096448 +1662064525931097344 +1662064525982098432 +1662064526024099328 +1662064526066100224 +1662064526105101056 +1662064526147101952 +1662064526189102848 +1662064526231103744 +1662064526276104704 +1662064526324105728 +1662064526366106624 +1662064526405107456 +1662064526450108416 +1662064526492109312 +1662064526534110208 +1662064526579111168 +1662064526624112128 +1662064526666113024 +1662064526708113920 +1662064526753114880 +1662064526798115840 +1662064526840116736 +1662064526885117696 +1662064526927118592 +1662064526969119488 +1662064527020120576 +1662064527062121472 +1662064527104122368 +1662064527149123328 +1662064527185124096 +1662064527227124992 +1662064527269125888 +1662064527311126784 +1662064527353127680 +1662064527389128448 +1662064527431129344 +1662064527470130176 +1662064527512131072 +1662064527557132032 +1662064527602132992 +1662064527644133888 +1662064527692134912 +1662064527731135744 +1662064527776136704 +1662064527815137536 +1662064527863138560 +1662064527905139456 +1662064527950140416 +1662064527992141312 +1662064528037142272 +1662064528079143168 +1662064528124144128 +1662064528172145152 +1662064528214146048 +1662064528262147072 +1662064528304147968 +1662064528349148928 +1662064528391149824 +1662064528430150656 +1662064528472151552 +1662064528514152448 +1662064528556153344 +1662064528592154112 +1662064528628154880 +1662064528667155712 +1662064528712156672 +1662064528754157568 +1662064528796158464 +1662064528838159360 +1662064528883160320 +1662064528922161152 +1662064528964162048 +1662064529009163008 +1662064529048163840 +1662064529093164800 +1662064529138165760 +1662064529183166720 +1662064529225167616 +1662064529267168512 +1662064529309169408 +1662064529354170368 +1662064529396171264 +1662064529438172160 +1662064529480173056 +1662064529525174016 +1662064529564174848 +1662064529609175808 +1662064529654176768 +1662064529693177600 +1662064529738178560 +1662064529780179456 +1662064529822180352 +1662064529867181312 +1662064529915182336 +1662064529957183232 +1662064530002184192 +1662064530047185152 +1662064530092186112 +1662064530134187008 +1662064530182188032 +1662064530227188992 +1662064530269189888 +1662064530308190720 +1662064530350191616 +1662064530395192576 +1662064530437193472 +1662064530482194432 +1662064530521195264 +1662064530566196224 +1662064530611197184 +1662064530653198080 +1662064530695198976 +1662064530740199936 +1662064530788200960 +1662064530833201920 +1662064530872202752 +1662064530920203776 +1662064530962204672 +1662064531007205632 +1662064531049206528 +1662064531097207552 +1662064531142208512 +1662064531184209408 +1662064531223210240 +1662064531265211136 +1662064531310212096 +1662064531352212992 +1662064531394213888 +1662064531436214784 +1662064531478215680 +1662064531517216512 +1662064531556217344 +1662064531601218304 +1662064531646219264 +1662064531685220096 +1662064531727220992 +1662064531769221888 +1662064531808222720 +1662064531847223552 +1662064531892224512 +1662064531934225408 +1662064531982226432 +1662064532027227392 +1662064532069228288 +1662064532111229184 +1662064532159230208 +1662064532201231104 +1662064532246232064 +1662064532291233024 +1662064532330233856 +1662064532372234752 +1662064532417235712 +1662064532462236672 +1662064532504237568 +1662064532543238400 +1662064532585239296 +1662064532627240192 +1662064532672241152 +1662064532714242048 +1662064532756242944 +1662064532795243776 +1662064532837244672 +1662064532882245632 +1662064532927246592 +1662064532966247424 +1662064533008248320 +1662064533047249152 +1662064533089250048 +1662064533131250944 +1662064533173251840 +1662064533215252736 +1662064533257253632 +1662064533302254592 +1662064533344255488 +1662064533386256384 +1662064533428257280 +1662064533470258176 +1662064533512259072 +1662064533551259904 +1662064533593260800 +1662064533638261760 +1662064533680262656 +1662064533722263552 +1662064533767264512 +1662064533809265408 +1662064533851266304 +1662064533893267200 +1662064533935268096 +1662064533977268992 +1662064534022269952 +1662064534067270912 +1662064534109271808 +1662064534154272768 +1662064534193273600 +1662064534238274560 +1662064534280275456 +1662064534322276352 +1662064534367277312 +1662064534409278208 +1662064534451279104 +1662064534499280128 +1662064534544281088 +1662064534589282048 +1662064534634283008 +1662064534673283840 +1662064534712284672 +1662064534754285568 +1662064534799286528 +1662064534844287488 +1662064534892288512 +1662064534937289472 +1662064534979290368 +1662064535021291264 +1662064535060292096 +1662064535105293056 +1662064535156294144 +1662064535201295104 +1662064535249296128 +1662064535291297024 +1662064535336297984 +1662064535375298816 +1662064535417299712 +1662064535459300608 +1662064535501301504 +1662064535543302400 +1662064535585303296 +1662064535627304192 +1662064535669305088 +1662064535714306048 +1662064535753306880 +1662064535795307776 +1662064535837308672 +1662064535879309568 +1662064535921310464 +1662064535969311488 +1662064536014312448 +1662064536056313344 +1662064536104314368 +1662064536143315200 +1662064536185316096 +1662064536230317056 +1662064536275318016 +1662064536323319040 +1662064536365319936 +1662064536410320896 +1662064536452321792 +1662064536497322752 +1662064536545323776 +1662064536593324800 +1662064536635325696 +1662064536677326592 +1662064536719327488 +1662064536761328384 +1662064536806329344 +1662064536854330368 +1662064536905331456 +1662064536950332416 +1662064536992333312 +1662064537034334208 +1662064537079335168 +1662064537124336128 +1662064537163336960 +1662064537202337792 +1662064537244338688 +1662064537289339648 +1662064537331340544 +1662064537376341504 +1662064537421342464 +1662064537463343360 +1662064537505344256 +1662064537553345280 +1662064537595346176 +1662064537640347136 +1662064537688348160 +1662064537733349120 +1662064537775350016 +1662064537817350912 +1662064537856351744 +1662064537898352640 +1662064537940353536 +1662064537988354560 +1662064538033355520 +1662064538078356480 +1662064538123357440 +1662064538171358464 +1662064538213359360 +1662064538258360320 +1662064538297361152 +1662064538339362048 +1662064538384363008 +1662064538429363968 +1662064538471364864 +1662064538513365760 +1662064538555366656 +1662064538597367552 +1662064538639368448 +1662064538684369408 +1662064538726370304 +1662064538771371264 +1662064538810372096 +1662064538852372992 +1662064538891373824 +1662064538939374848 +1662064538984375808 +1662064539026376704 +1662064539071377664 +1662064539113378560 +1662064539158379520 +1662064539200380416 +1662064539242381312 +1662064539281382144 +1662064539326383104 +1662064539368384000 +1662064539410384896 +1662064539455385856 +1662064539497386752 +1662064539539387648 +1662064539581388544 +1662064539629389568 +1662064539671390464 +1662064539719391488 +1662064539764392448 +1662064539803393280 +1662064539845394176 +1662064539896395264 +1662064539938396160 +1662064539977396992 +1662064540022397952 +1662064540061398784 +1662064540103399680 +1662064540151400704 +1662064540187401472 +1662064540226402304 +1662064540271403264 +1662064540319404288 +1662064540361405184 +1662064540403406080 +1662064540445406976 +1662064540481407744 +1662064540523408640 +1662064540562409472 +1662064540607410432 +1662064540649411328 +1662064540694412288 +1662064540736413184 +1662064540781414144 +1662064540826415104 +1662064540868416000 +1662064540910416896 +1662064540949417728 +1662064540994418688 +1662064541039419648 +1662064541078420480 +1662064541117421312 +1662064541159422208 +1662064541198423040 +1662064541240423936 +1662064541282424832 +1662064541324425728 +1662064541366426624 +1662064541405427456 +1662064541444428288 +1662064541489429248 +1662064541534430208 +1662064541576431104 +1662064541621432064 +1662064541666433024 +1662064541705433856 +1662064541744434688 +1662064541789435648 +1662064541828436480 +1662064541870437376 +1662064541915438336 +1662064541957439232 +1662064541999440128 +1662064542044441088 +1662064542086441984 +1662064542131442944 +1662064542173443840 +1662064542215444736 +1662064542263445760 +1662064542308446720 +1662064542350447616 +1662064542395448576 +1662064542440449536 +1662064542482450432 +1662064542524451328 +1662064542569452288 +1662064542614453248 +1662064542659454208 +1662064542701455104 +1662064542743456000 +1662064542782456832 +1662064542827457792 +1662064542875458816 +1662064542920459776 +1662064542959460608 +1662064543004461568 +1662064543049462528 +1662064543091463424 +1662064543139464448 +1662064543184465408 +1662064543235466496 +1662064543280467456 +1662064543325468416 +1662064543367469312 +1662064543412470272 +1662064543454471168 +1662064543496472064 +1662064543541473024 +1662064543580473856 +1662064543625474816 +1662064543667475712 +1662064543706476544 +1662064543742477312 +1662064543784478208 +1662064543823479040 +1662064543877480192 +1662064543928481280 +1662064543973482240 +1662064544018483200 +1662064544057484032 +1662064544099484928 +1662064544144485888 +1662064544186486784 +1662064544228487680 +1662064544267488512 +1662064544309489408 +1662064544354490368 +1662064544396491264 +1662064544438492160 +1662064544477492992 +1662064544519493888 +1662064544564494848 +1662064544609495808 +1662064544651496704 +1662064544693497600 +1662064544735498496 +1662064544777499392 +1662064544819500288 +1662064544864501248 +1662064544909502208 +1662064544954503168 +1662064544993504000 +1662064545035504896 +1662064545080505856 +1662064545122506752 +1662064545164507648 +1662064545209508608 +1662064545257509632 +1662064545299510528 +1662064545344511488 +1662064545389512448 +1662064545431513344 +1662064545476514304 +1662064545518515200 +1662064545563516160 +1662064545617517312 +1662064545659518208 +1662064545707519232 +1662064545749520128 +1662064545794521088 +1662064545836521984 +1662064545881522944 +1662064545926523904 +1662064545971524864 +1662064546016525824 +1662064546061526784 +1662064546106527744 +1662064546148528640 +1662064546193529600 +1662064546232530432 +1662064546274531328 +1662064546316532224 +1662064546361533184 +1662064546406534144 +1662064546445534976 +1662064546484535808 +1662064546529536768 +1662064546574537728 +1662064546619538688 +1662064546658539520 +1662064546700540416 +1662064546739541248 +1662064546784542208 +1662064546826543104 +1662064546871544064 +1662064546913544960 +1662064546955545856 +1662064546997546752 +1662064547042547712 +1662064547087548672 +1662064547132549632 +1662064547177550592 +1662064547219551488 +1662064547264552448 +1662064547306553344 +1662064547348554240 +1662064547390555136 +1662064547432556032 +1662064547474556928 +1662064547522557952 +1662064547564558848 +1662064547606559744 +1662064547651560704 +1662064547699561728 +1662064547738562560 +1662064547780563456 +1662064547816564224 +1662064547855565056 +1662064547900566016 +1662064547942566912 +1662064547987567872 +1662064548029568768 +1662064548074569728 +1662064548116570624 +1662064548158571520 +1662064548197572352 +1662064548242573312 +1662064548284574208 +1662064548329575168 +1662064548368576000 +1662064548407576832 +1662064548452577792 +1662064548500578816 +1662064548545579776 +1662064548590580736 +1662064548629581568 +1662064548671582464 +1662064548713583360 +1662064548758584320 +1662064548803585280 +1662064548845586176 +1662064548884587008 +1662064548929587968 +1662064548974588928 +1662064549016589824 +1662064549061590784 +1662064549100591616 +1662064549148592640 +1662064549199593728 +1662064549241594624 +1662064549286595584 +1662064549328596480 +1662064549373597440 +1662064549418598400 +1662064549463599360 +1662064549505600256 +1662064549550601216 +1662064549592602112 +1662064549634603008 +1662064549676603904 +1662064549724604928 +1662064549766605824 +1662064549805606656 +1662064549847607552 +1662064549886608384 +1662064549931609344 +1662064549976610304 +1662064550021611264 +1662064550063612160 +1662064550108613120 +1662064550147613952 +1662064550189614848 +1662064550231615744 +1662064550276616704 +1662064550318617600 +1662064550357618432 +1662064550399619328 +1662064550444620288 +1662064550486621184 +1662064550528622080 +1662064550567622912 +1662064550609623808 +1662064550657624832 +1662064550702625792 +1662064550744626688 +1662064550786627584 +1662064550822628352 +1662064550861629184 +1662064550906630144 +1662064550951631104 +1662064550987631872 +1662064551029632768 +1662064551071633664 +1662064551116634624 +1662064551158635520 +1662064551200636416 +1662064551239637248 +1662064551281638144 +1662064551323639040 +1662064551365639936 +1662064551404640768 +1662064551449641728 +1662064551494642688 +1662064551539643648 +1662064551581644544 +1662064551623645440 +1662064551662646272 +1662064551707647232 +1662064551749648128 +1662064551794649088 +1662064551839650048 +1662064551881650944 +1662064551926651904 +1662064551971652864 +1662064552010653696 +1662064552049654528 +1662064552088655360 +1662064552133656320 +1662064552178657280 +1662064552220658176 +1662064552262659072 +1662064552310660096 +1662064552352660992 +1662064552394661888 +1662064552436662784 +1662064552478663680 +1662064552532664832 +1662064552577665792 +1662064552619666688 +1662064552661667584 +1662064552709668608 +1662064552757669632 +1662064552802670592 +1662064552844671488 +1662064552886672384 +1662064552928673280 +1662064552970674176 +1662064553018675200 +1662064553060676096 +1662064553093676800 +1662064553141677824 +1662064553180678656 +1662064553228679680 +1662064553273680640 +1662064553315681536 +1662064553354682368 +1662064553396683264 +1662064553438684160 +1662064553480685056 +1662064553525686016 +1662064553567686912 +1662064553612687872 +1662064553654688768 +1662064553699689728 +1662064553741690624 +1662064553780691456 +1662064553822692352 +1662064553864693248 +1662064553906694144 +1662064553948695040 +1662064553990695936 +1662064554035696896 +1662064554074697728 +1662064554116698624 +1662064554155699456 +1662064554200700416 +1662064554245701376 +1662064554287702272 +1662064554332703232 +1662064554371704064 +1662064554413704960 +1662064554452705792 +1662064554494706688 +1662064554536707584 +1662064554578708480 +1662064554620709376 +1662064554665710336 +1662064554707711232 +1662064554752712192 +1662064554797713152 +1662064554836713984 +1662064554878714880 +1662064554920715776 +1662064554962716672 +1662064555007717632 +1662064555049718528 +1662064555088719360 +1662064555130720256 +1662064555172721152 +1662064555214722048 +1662064555256722944 +1662064555301723904 +1662064555346724864 +1662064555391725824 +1662064555433726720 +1662064555475727616 +1662064555514728448 +1662064555571729664 +1662064555613730560 +1662064555655731456 +1662064555703732480 +1662064555748733440 +1662064555790734336 +1662064555832735232 +1662064555874736128 +1662064555919737088 +1662064555961737984 +1662064556006738944 +1662064556048739840 +1662064556093740800 +1662064556132741632 +1662064556174742528 +1662064556219743488 +1662064556264744448 +1662064556309745408 +1662064556357746432 +1662064556405747456 +1662064556450748416 +1662064556489749248 +1662064556534750208 +1662064556582751232 +1662064556627752192 +1662064556669753088 +1662064556711753984 +1662064556756754944 +1662064556798755840 +1662064556843756800 +1662064556885757696 +1662064556933758720 +1662064556969759488 +1662064557008760320 +1662064557047761152 +1662064557089762048 +1662064557131762944 +1662064557173763840 +1662064557212764672 +1662064557260765696 +1662064557305766656 +1662064557347767552 +1662064557383768320 +1662064557422769152 +1662064557467770112 +1662064557515771136 +1662064557557772032 +1662064557599772928 +1662064557638773760 +1662064557683774720 +1662064557728775680 +1662064557773776640 +1662064557818777600 +1662064557860778496 +1662064557902779392 +1662064557941780224 +1662064557983781120 +1662064558028782080 +1662064558067782912 +1662064558109783808 +1662064558148784640 +1662064558190785536 +1662064558232786432 +1662064558277787392 +1662064558322788352 +1662064558364789248 +1662064558409790208 +1662064558457791232 +1662064558499792128 +1662064558538792960 +1662064558583793920 +1662064558631794944 +1662064558673795840 +1662064558715796736 +1662064558757797632 +1662064558799798528 +1662064558847799552 +1662064558886800384 +1662064558928801280 +1662064558973802240 +1662064559018803200 +1662064559063804160 +1662064559108805120 +1662064559147805952 +1662064559189806848 +1662064559234807808 +1662064559276808704 +1662064559312809472 +1662064559354810368 +1662064559399811328 +1662064559441812224 +1662064559489813248 +1662064559534814208 +1662064559576815104 +1662064559618816000 +1662064559663816960 +1662064559705817856 +1662064559744818688 +1662064559786819584 +1662064559828820480 +1662064559867821312 +1662064559915822336 +1662064559957823232 +1662064559999824128 +1662064560044825088 +1662064560089826048 +1662064560134827008 +1662064560176827904 +1662064560218828800 +1662064560260829696 +1662064560299830528 +1662064560338831360 +1662064560377832192 +1662064560416833024 +1662064560458833920 +1662064560503834880 +1662064560545835776 +1662064560587836672 +1662064560632837632 +1662064560671838464 +1662064560716839424 +1662064560761840384 +1662064560803841280 +1662064560848842240 +1662064560893843200 +1662064560932844032 +1662064560968844800 +1662064561010845696 +1662064561055846656 +1662064561094847488 +1662064561136848384 +1662064561184849408 +1662064561220850176 +1662064561265851136 +1662064561310852096 +1662064561352852992 +1662064561397853952 +1662064561436854784 +1662064561478855680 +1662064561523856640 +1662064561568857600 +1662064561607858432 +1662064561652859392 +1662064561691860224 +1662064561733861120 +1662064561775862016 +1662064561817862912 +1662064561859863808 +1662064561901864704 +1662064561943865600 +1662064561988866560 +1662064562033867520 +1662064562075868416 +1662064562120869376 +1662064562162870272 +1662064562201871104 +1662064562243872000 +1662064562285872896 +1662064562327873792 +1662064562372874752 +1662064562417875712 +1662064562462876672 +1662064562510877696 +1662064562552878592 +1662064562594879488 +1662064562636880384 +1662064562681881344 +1662064562726882304 +1662064562768883200 +1662064562816884224 +1662064562861885184 +1662064562903886080 +1662064562948887040 +1662064562996888064 +1662064563038888960 +1662064563080889856 +1662064563122890752 +1662064563164891648 +1662064563209892608 +1662064563248893440 +1662064563290894336 +1662064563332895232 +1662064563374896128 +1662064563416897024 +1662064563461897984 +1662064563503898880 +1662064563545899776 +1662064563590900736 +1662064563632901632 +1662064563674902528 +1662064563719903488 +1662064563767904512 +1662064563806905344 +1662064563848906240 +1662064563887907072 +1662064563929907968 +1662064563971908864 +1662064564010909696 +1662064564052910592 +1662064564097911552 +1662064564139912448 +1662064564184913408 +1662064564226914304 +1662064564271915264 +1662064564313916160 +1662064564352916992 +1662064564397917952 +1662064564439918848 +1662064564484919808 +1662064564529920768 +1662064564571921664 +1662064564616922624 +1662064564658923520 +1662064564703924480 +1662064564745925376 +1662064564790926336 +1662064564832927232 +1662064564871928064 +1662064564913928960 +1662064564958929920 +1662064565000930816 +1662064565039931648 +1662064565081932544 +1662064565126933504 +1662064565171934464 +1662064565210935296 +1662064565255936256 +1662064565297937152 +1662064565339938048 +1662064565381938944 +1662064565426939904 +1662064565468940800 +1662064565510941696 +1662064565552942592 +1662064565594943488 +1662064565639944448 +1662064565681945344 +1662064565723946240 +1662064565768947200 +1662064565807948032 +1662064565849948928 +1662064565891949824 +1662064565933950720 +1662064565978951680 +1662064566020952576 +1662064566062953472 +1662064566104954368 +1662064566143955200 +1662064566188956160 +1662064566230957056 +1662064566263957760 +1662064566308958720 +1662064566353959680 +1662064566398960640 +1662064566440961536 +1662064566482962432 +1662064566527963392 +1662064566569964288 +1662064566617965312 +1662064566659966208 +1662064566701967104 +1662064566743968000 +1662064566785968896 +1662064566827969792 +1662064566872970752 +1662064566914971648 +1662064566959972608 +1662064567004973568 +1662064567046974464 +1662064567088975360 +1662064567133976320 +1662064567172977152 +1662064567214978048 +1662064567259979008 +1662064567298979840 +1662064567343980800 +1662064567388981760 +1662064567430982656 +1662064567472983552 +1662064567511984384 +1662064567556985344 +1662064567592986112 +1662064567634987008 +1662064567682988032 +1662064567721988864 +1662064567757989632 +1662064567799990528 +1662064567838991360 +1662064567880992256 +1662064567925993216 +1662064567964994048 +1662064568006994944 +1662064568051995904 +1662064568090996736 +1662064568132997632 +1662064568177998592 +1662064568222999552 +1662064568256000256 +1662064568301001216 +1662064568343002112 +1662064568385003008 +1662064568424003840 +1662064568466004736 +1662064568511005696 +1662064568553006592 +1662064568598007552 +1662064568640008448 +1662064568685009408 +1662064568724010240 +1662064568766011136 +1662064568811012096 +1662064568853012992 +1662064568898013952 +1662064568943014912 +1662064568988015872 +1662064569027016704 +1662064569069017600 +1662064569108018432 +1662064569150019328 +1662064569195020288 +1662064569234021120 +1662064569279022080 +1662064569324023040 +1662064569366023936 +1662064569411024896 +1662064569453025792 +1662064569498026752 +1662064569543027712 +1662064569582028544 +1662064569630029568 +1662064569672030464 +1662064569717031424 +1662064569759032320 +1662064569801033216 +1662064569837033984 +1662064569879034880 +1662064569927035904 +1662064569969036800 +1662064570011037696 +1662064570056038656 +1662064570101039616 +1662064570146040576 +1662064570188041472 +1662064570230042368 +1662064570275043328 +1662064570317044224 +1662064570359045120 +1662064570398045952 +1662064570443046912 +1662064570485047808 +1662064570527048704 +1662064570569049600 +1662064570614050560 +1662064570659051520 +1662064570701052416 +1662064570740053248 +1662064570782054144 +1662064570827055104 +1662064570869056000 +1662064570914056960 +1662064570959057920 +1662064571001058816 +1662064571043059712 +1662064571079060480 +1662064571124061440 +1662064571169062400 +1662064571211063296 +1662064571253064192 +1662064571298065152 +1662064571343066112 +1662064571394067200 +1662064571433068032 +1662064571478068992 +1662064571520069888 +1662064571565070848 +1662064571610071808 +1662064571652072704 +1662064571694073600 +1662064571736074496 +1662064571784075520 +1662064571829076480 +1662064571877077504 +1662064571919078400 +1662064571970079488 +1662064572012080384 +1662064572060081408 +1662064572102082304 +1662064572144083200 +1662064572186084096 +1662064572225084928 +1662064572267085824 +1662064572309086720 +1662064572357087744 +1662064572399088640 +1662064572444089600 +1662064572492090624 +1662064572540091648 +1662064572588092672 +1662064572630093568 +1662064572669094400 +1662064572714095360 +1662064572759096320 +1662064572801097216 +1662064572840098048 +1662064572882098944 +1662064572921099776 +1662064572966100736 +1662064573008101632 +1662064573050102528 +1662064573092103424 +1662064573134104320 +1662064573176105216 +1662064573215106048 +1662064573257106944 +1662064573299107840 +1662064573341108736 +1662064573383109632 +1662064573422110464 +1662064573464111360 +1662064573509112320 +1662064573545113088 +1662064573587113984 +1662064573629114880 +1662064573671115776 +1662064573710116608 +1662064573752117504 +1662064573794118400 +1662064573836119296 +1662064573878120192 +1662064573917121024 +1662064573959121920 +1662064574004122880 +1662064574049123840 +1662064574088124672 +1662064574133125632 +1662064574175126528 +1662064574220127488 +1662064574265128448 +1662064574304129280 +1662064574343130112 +1662064574388131072 +1662064574430131968 +1662064574475132928 +1662064574520133888 +1662064574556134656 +1662064574595135488 +1662064574637136384 +1662064574679137280 +1662064574721138176 +1662064574769139200 +1662064574811140096 +1662064574856141056 +1662064574898141952 +1662064574934142720 +1662064574970143488 +1662064575015144448 +1662064575057145344 +1662064575099146240 +1662064575144147200 +1662064575189148160 +1662064575231149056 +1662064575273149952 +1662064575318150912 +1662064575363151872 +1662064575408152832 +1662064575450153728 +1662064575489154560 +1662064575531155456 +1662064575579156480 +1662064575624157440 +1662064575663158272 +1662064575711159296 +1662064575756160256 +1662064575801161216 +1662064575840162048 +1662064575882162944 +1662064575924163840 +1662064575963164672 +1662064576008165632 +1662064576050166528 +1662064576095167488 +1662064576137168384 +1662064576182169344 +1662064576224170240 +1662064576263171072 +1662064576302171904 +1662064576347172864 +1662064576392173824 +1662064576434174720 +1662064576476175616 +1662064576518176512 +1662064576560177408 +1662064576608178432 +1662064576650179328 +1662064576701180416 +1662064576743181312 +1662064576782182144 +1662064576824183040 +1662064576866183936 +1662064576908184832 +1662064576950185728 +1662064576995186688 +1662064577034187520 +1662064577079188480 +1662064577118189312 +1662064577163190272 +1662064577205191168 +1662064577247192064 +1662064577289192960 +1662064577331193856 +1662064577373194752 +1662064577415195648 +1662064577460196608 +1662064577505197568 +1662064577547198464 +1662064577592199424 +1662064577634200320 +1662064577676201216 +1662064577718202112 +1662064577757202944 +1662064577799203840 +1662064577841204736 +1662064577886205696 +1662064577928206592 +1662064577973207552 +1662064578012208384 +1662064578051209216 +1662064578090210048 +1662064578132210944 +1662064578174211840 +1662064578219212800 +1662064578258213632 +1662064578306214656 +1662064578348215552 +1662064578393216512 +1662064578441217536 +1662064578489218560 +1662064578534219520 +1662064578576220416 +1662064578615221248 +1662064578657222144 +1662064578699223040 +1662064578741223936 +1662064578786224896 +1662064578828225792 +1662064578867226624 +1662064578912227584 +1662064578954228480 +1662064578996229376 +1662064579041230336 +1662064579080231168 +1662064579122232064 +1662064579161232896 +1662064579203233792 +1662064579248234752 +1662064579287235584 +1662064579329236480 +1662064579374237440 +1662064579422238464 +1662064579470239488 +1662064579515240448 +1662064579557241344 +1662064579599242240 +1662064579638243072 +1662064579680243968 +1662064579728244992 +1662064579773245952 +1662064579815246848 +1662064579860247808 +1662064579902248704 +1662064579944249600 +1662064579986250496 +1662064580028251392 +1662064580067252224 +1662064580112253184 +1662064580151254016 +1662064580190254848 +1662064580229255680 +1662064580271256576 +1662064580310257408 +1662064580352258304 +1662064580394259200 +1662064580442260224 +1662064580484261120 +1662064580526262016 +1662064580568262912 +1662064580610263808 +1662064580655264768 +1662064580697265664 +1662064580739266560 +1662064580781267456 +1662064580823268352 +1662064580868269312 +1662064580916270336 +1662064580955271168 +1662064581000272128 +1662064581045273088 +1662064581087273984 +1662064581135275008 +1662064581177275904 +1662064581222276864 +1662064581267277824 +1662064581312278784 +1662064581357279744 +1662064581399280640 +1662064581441281536 +1662064581489282560 +1662064581531283456 +1662064581564284160 +1662064581606285056 +1662064581651286016 +1662064581690286848 +1662064581732287744 +1662064581777288704 +1662064581816289536 +1662064581861290496 +1662064581903291392 +1662064581945292288 +1662064581987293184 +1662064582032294144 +1662064582068294912 +1662064582113295872 +1662064582152296704 +1662064582194297600 +1662064582239298560 +1662064582278299392 +1662064582320300288 +1662064582365301248 +1662064582404302080 +1662064582446302976 +1662064582485303808 +1662064582536304896 +1662064582578305792 +1662064582620306688 +1662064582665307648 +1662064582707308544 +1662064582752309504 +1662064582794310400 +1662064582839311360 +1662064582881312256 +1662064582923313152 +1662064582965314048 +1662064583007314944 +1662064583058316032 +1662064583100316928 +1662064583145317888 +1662064583187318784 +1662064583229319680 +1662064583274320640 +1662064583319321600 +1662064583364322560 +1662064583409323520 +1662064583454324480 +1662064583499325440 +1662064583544326400 +1662064583589327360 +1662064583631328256 +1662064583676329216 +1662064583715330048 +1662064583760331008 +1662064583802331904 +1662064583847332864 +1662064583886333696 +1662064583928334592 +1662064583973335552 +1662064584018336512 +1662064584063337472 +1662064584102338304 +1662064584141339136 +1662064584183340032 +1662064584222340864 +1662064584264341760 +1662064584309342720 +1662064584351343616 +1662064584393344512 +1662064584435345408 +1662064584477346304 +1662064584519347200 +1662064584561348096 +1662064584600348928 +1662064584645349888 +1662064584690350848 +1662064584729351680 +1662064584774352640 +1662064584816353536 +1662064584861354496 +1662064584903355392 +1662064584945356288 +1662064584990357248 +1662064585032358144 +1662064585074359040 +1662064585116359936 +1662064585164360960 +1662064585206361856 +1662064585248362752 +1662064585293363712 +1662064585332364544 +1662064585377365504 +1662064585419366400 +1662064585464367360 +1662064585509368320 +1662064585557369344 +1662064585599370240 +1662064585641371136 +1662064585686372096 +1662064585731373056 +1662064585779374080 +1662064585824375040 +1662064585866375936 +1662064585914376960 +1662064585953377792 +1662064586001378816 +1662064586043379712 +1662064586088380672 +1662064586133381632 +1662064586175382528 +1662064586217383424 +1662064586262384384 +1662064586307385344 +1662064586352386304 +1662064586394387200 +1662064586442388224 +1662064586484389120 +1662064586526390016 +1662064586574391040 +1662064586619392000 +1662064586664392960 +1662064586706393856 +1662064586748394752 +1662064586790395648 +1662064586835396608 +1662064586874397440 +1662064586919398400 +1662064586964399360 +1662064587006400256 +1662064587048401152 +1662064587093402112 +1662064587135403008 +1662064587180403968 +1662064587225404928 +1662064587267405824 +1662064587312406784 +1662064587357407744 +1662064587396408576 +1662064587441409536 +1662064587483410432 +1662064587531411456 +1662064587576412416 +1662064587621413376 +1662064587666414336 +1662064587708415232 +1662064587750416128 +1662064587798417152 +1662064587840418048 +1662064587882418944 +1662064587921419776 +1662064587963420672 +1662064588005421568 +1662064588041422336 +1662064588083423232 +1662064588122424064 +1662064588173425152 +1662064588212425984 +1662064588257426944 +1662064588299427840 +1662064588341428736 +1662064588386429696 +1662064588431430656 +1662064588476431616 +1662064588521432576 +1662064588563433472 +1662064588608434432 +1662064588647435264 +1662064588689436160 +1662064588734437120 +1662064588776438016 +1662064588815438848 +1662064588860439808 +1662064588902440704 +1662064588938441472 +1662064588983442432 +1662064589025443328 +1662064589067444224 +1662064589112445184 +1662064589154446080 +1662064589196446976 +1662064589244448000 +1662064589280448768 +1662064589322449664 +1662064589364450560 +1662064589406451456 +1662064589445452288 +1662064589487453184 +1662064589532454144 +1662064589571454976 +1662064589613455872 +1662064589658456832 +1662064589697457664 +1662064589742458624 +1662064589781459456 +1662064589823460352 +1662064589865461248 +1662064589907462144 +1662064589949463040 +1662064589994464000 +1662064590036464896 +1662064590081465856 +1662064590123466752 +1662064590168467712 +1662064590210468608 +1662064590255469568 +1662064590300470528 +1662064590348471552 +1662064590390472448 +1662064590435473408 +1662064590477474304 +1662064590516475136 +1662064590552475904 +1662064590594476800 +1662064590639477760 +1662064590687478784 +1662064590723479552 +1662064590762480384 +1662064590810481408 +1662064590849482240 +1662064590894483200 +1662064590939484160 +1662064590981485056 +1662064591023485952 +1662064591065486848 +1662064591107487744 +1662064591158488832 +1662064591206489856 +1662064591254490880 +1662064591296491776 +1662064591344492800 +1662064591389493760 +1662064591431494656 +1662064591479495680 +1662064591524496640 +1662064591569497600 +1662064591611498496 +1662064591650499328 +1662064591689500160 +1662064591734501120 +1662064591776502016 +1662064591821502976 +1662064591863503872 +1662064591905504768 +1662064591950505728 +1662064591992506624 +1662064592037507584 +1662064592079508480 +1662064592124509440 +1662064592163510272 +1662064592202511104 +1662064592247512064 +1662064592289512960 +1662064592328513792 +1662064592370514688 +1662064592412515584 +1662064592451516416 +1662064592490517248 +1662064592532518144 +1662064592577519104 +1662064592622520064 +1662064592661520896 +1662064592706521856 +1662064592748522752 +1662064592790523648 +1662064592829524480 +1662064592871525376 +1662064592913526272 +1662064592955527168 +1662064593000528128 +1662064593045529088 +1662064593087529984 +1662064593129530880 +1662064593168531712 +1662064593210532608 +1662064593252533504 +1662064593297534464 +1662064593342535424 +1662064593384536320 +1662064593429537280 +1662064593468538112 +1662064593510539008 +1662064593555539968 +1662064593600540928 +1662064593648541952 +1662064593687542784 +1662064593732543744 +1662064593771544576 +1662064593816545536 +1662064593861546496 +1662064593903547392 +1662064593942548224 +1662064593984549120 +1662064594026550016 +1662064594071550976 +1662064594113551872 +1662064594161552896 +1662064594206553856 +1662064594248554752 +1662064594287555584 +1662064594326556416 +1662064594371557376 +1662064594416558336 +1662064594452559104 +1662064594494560000 +1662064594533560832 +1662064594578561792 +1662064594623562752 +1662064594665563648 +1662064594704564480 +1662064594746565376 +1662064594788566272 +1662064594830567168 +1662064594869568000 +1662064594908568832 +1662064594950569728 +1662064594995570688 +1662064595037571584 +1662064595076572416 +1662064595115573248 +1662064595157574144 +1662064595199575040 +1662064595244576000 +1662064595286576896 +1662064595331577856 +1662064595373578752 +1662064595415579648 +1662064595460580608 +1662064595502581504 +1662064595550582528 +1662064595592583424 +1662064595637584384 +1662064595676585216 +1662064595718586112 +1662064595757586944 +1662064595802587904 +1662064595847588864 +1662064595886589696 +1662064595925590528 +1662064595967591424 +1662064596012592384 +1662064596057593344 +1662064596099594240 +1662064596141595136 +1662064596183596032 +1662064596228596992 +1662064596273597952 +1662064596312598784 +1662064596357599744 +1662064596402600704 +1662064596441601536 +1662064596483602432 +1662064596525603328 +1662064596567604224 +1662064596606605056 +1662064596648605952 +1662064596687606784 +1662064596729607680 +1662064596771608576 +1662064596816609536 +1662064596858610432 +1662064596900611328 +1662064596939612160 +1662064596975612928 +1662064597020613888 +1662064597068614912 +1662064597110615808 +1662064597155616768 +1662064597197617664 +1662064597239618560 +1662064597284619520 +1662064597326620416 +1662064597368621312 +1662064597410622208 +1662064597452623104 +1662064597497624064 +1662064597542625024 +1662064597584625920 +1662064597626626816 +1662064597668627712 +1662064597707628544 +1662064597749629440 +1662064597788630272 +1662064597836631296 +1662064597878632192 +1662064597920633088 +1662064597962633984 +1662064598010635008 +1662064598052635904 +1662064598097636864 +1662064598139637760 +1662064598175638528 +1662064598220639488 +1662064598259640320 +1662064598301641216 +1662064598346642176 +1662064598391643136 +1662064598433644032 +1662064598481645056 +1662064598520645888 +1662064598559646720 +1662064598601647616 +1662064598643648512 +1662064598685649408 +1662064598727650304 +1662064598772651264 +1662064598814652160 +1662064598859653120 +1662064598901654016 +1662064598943654912 +1662064598985655808 +1662064599027656704 +1662064599069657600 +1662064599114658560 +1662064599156659456 +1662064599201660416 +1662064599243661312 +1662064599288662272 +1662064599330663168 +1662064599372664064 +1662064599420665088 +1662064599465666048 +1662064599510667008 +1662064599552667904 +1662064599591668736 +1662064599639669760 +1662064599681670656 +1662064599723671552 +1662064599771672576 +1662064599810673408 +1662064599852674304 +1662064599900675328 +1662064599939676160 +1662064599981677056 +1662064600026678016 +1662064600071678976 +1662064600113679872 +1662064600158680832 +1662064600200681728 +1662064600245682688 +1662064600287683584 +1662064600329684480 +1662064600371685376 +1662064600416686336 +1662064600458687232 +1662064600497688064 +1662064600539688960 +1662064600581689856 +1662064600623690752 +1662064600668691712 +1662064600713692672 +1662064600761693696 +1662064600806694656 +1662064600851695616 +1662064600899696640 +1662064600947697664 +1662064600989698560 +1662064601031699456 +1662064601079700480 +1662064601124701440 +1662064601172702464 +1662064601217703424 +1662064601262704384 +1662064601307705344 +1662064601349706240 +1662064601388707072 +1662064601424707840 +1662064601466708736 +1662064601511709696 +1662064601550710528 +1662064601595711488 +1662064601640712448 +1662064601685713408 +1662064601727714304 +1662064601769715200 +1662064601811716096 +1662064601853716992 +1662064601901718016 +1662064601943718912 +1662064601988719872 +1662064602036720896 +1662064602078721792 +1662064602120722688 +1662064602168723712 +1662064602210724608 +1662064602249725440 +1662064602294726400 +1662064602333727232 +1662064602375728128 +1662064602414728960 +1662064602456729856 +1662064602495730688 +1662064602546731776 +1662064602591732736 +1662064602633733632 +1662064602675734528 +1662064602714735360 +1662064602762736384 +1662064602807737344 +1662064602846738176 +1662064602888739072 +1662064602930739968 +1662064602972740864 +1662064603017741824 +1662064603056742656 +1662064603095743488 +1662064603140744448 +1662064603182745344 +1662064603218746112 +1662064603269747200 +1662064603308748032 +1662064603347748864 +1662064603389749760 +1662064603434750720 +1662064603479751680 +1662064603521752576 +1662064603563753472 +1662064603605754368 +1662064603650755328 +1662064603689756160 +1662064603740757248 +1662064603782758144 +1662064603827759104 +1662064603869760000 +1662064603914760960 +1662064603950761728 +1662064603992762624 +1662064604034763520 +1662064604076764416 +1662064604118765312 +1662064604160766208 +1662064604208767232 +1662064604247768064 +1662064604289768960 +1662064604337769984 +1662064604379770880 +1662064604421771776 +1662064604463772672 +1662064604508773632 +1662064604550774528 +1662064604595775488 +1662064604640776448 +1662064604682777344 +1662064604724778240 +1662064604769779200 +1662064604814780160 +1662064604853780992 +1662064604901782016 +1662064604943782912 +1662064604985783808 +1662064605027784704 +1662064605072785664 +1662064605114786560 +1662064605156787456 +1662064605198788352 +1662064605240789248 +1662064605282790144 +1662064605324791040 +1662064605366791936 +1662064605411792896 +1662064605462793984 +1662064605510795008 +1662064605552795904 +1662064605591796736 +1662064605630797568 +1662064605672798464 +1662064605714799360 +1662064605765800448 +1662064605810801408 +1662064605852802304 +1662064605897803264 +1662064605936804096 +1662064605978804992 +1662064606020805888 +1662064606065806848 +1662064606110807808 +1662064606155808768 +1662064606197809664 +1662064606242810624 +1662064606287811584 +1662064606329812480 +1662064606368813312 +1662064606413814272 +1662064606452815104 +1662064606491815936 +1662064606533816832 +1662064606578817792 +1662064606620818688 +1662064606668819712 +1662064606710820608 +1662064606752821504 +1662064606794822400 +1662064606836823296 +1662064606881824256 +1662064606923825152 +1662064606968826112 +1662064607010827008 +1662064607055827968 +1662064607100828928 +1662064607142829824 +1662064607187830784 +1662064607229831680 +1662064607271832576 +1662064607316833536 +1662064607358834432 +1662064607406835456 +1662064607448836352 +1662064607493837312 +1662064607535838208 +1662064607577839104 +1662064607619840000 +1662064607664840960 +1662064607709841920 +1662064607751842816 +1662064607790843648 +1662064607829844480 +1662064607871845376 +1662064607910846208 +1662064607958847232 +1662064608003848192 +1662064608048849152 +1662064608090850048 +1662064608135851008 +1662064608177851904 +1662064608219852800 +1662064608267853824 +1662064608312854784 +1662064608354855680 +1662064608396856576 +1662064608441857536 +1662064608486858496 +1662064608528859392 +1662064608570860288 +1662064608615861248 +1662064608657862144 +1662064608699863040 +1662064608744864000 +1662064608786864896 +1662064608828865792 +1662064608870866688 +1662064608915867648 +1662064608957868544 +1662064608999869440 +1662064609038870272 +1662064609083871232 +1662064609128872192 +1662064609170873088 +1662064609212873984 +1662064609254874880 +1662064609299875840 +1662064609341876736 +1662064609386877696 +1662064609428878592 +1662064609470879488 +1662064609515880448 +1662064609560881408 +1662064609605882368 +1662064609653883392 +1662064609698884352 +1662064609740885248 +1662064609785886208 +1662064609827887104 +1662064609869888000 +1662064609917889024 +1662064609956889856 +1662064610001890816 +1662064610043891712 +1662064610082892544 +1662064610124893440 +1662064610166894336 +1662064610208895232 +1662064610250896128 +1662064610292897024 +1662064610334897920 +1662064610376898816 +1662064610418899712 +1662064610463900672 +1662064610505901568 +1662064610547902464 +1662064610589903360 +1662064610634904320 +1662064610676905216 +1662064610715906048 +1662064610760907008 +1662064610805907968 +1662064610850908928 +1662064610889909760 +1662064610931910656 +1662064610976911616 +1662064611021912576 +1662064611066913536 +1662064611111914496 +1662064611153915392 +1662064611198916352 +1662064611240917248 +1662064611282918144 +1662064611321918976 +1662064611363919872 +1662064611402920704 +1662064611447921664 +1662064611495922688 +1662064611537923584 +1662064611579924480 +1662064611627925504 +1662064611666926336 +1662064611708927232 +1662064611753928192 +1662064611795929088 +1662064611843930112 +1662064611885931008 +1662064611924931840 +1662064611969932800 +1662064612017933824 +1662064612059934720 +1662064612104935680 +1662064612149936640 +1662064612194937600 +1662064612233938432 +1662064612278939392 +1662064612326940416 +1662064612371941376 +1662064612410942208 +1662064612452943104 +1662064612491943936 +1662064612530944768 +1662064612569945600 +1662064612614946560 +1662064612659947520 +1662064612704948480 +1662064612749949440 +1662064612788950272 +1662064612833951232 +1662064612875952128 +1662064612917953024 +1662064612956953856 +1662064613001954816 +1662064613040955648 +1662064613085956608 +1662064613130957568 +1662064613178958592 +1662064613220959488 +1662064613262960384 +1662064613304961280 +1662064613346962176 +1662064613385963008 +1662064613430963968 +1662064613469964800 +1662064613511965696 +1662064613553966592 +1662064613595967488 +1662064613634968320 +1662064613673969152 +1662064613715970048 +1662064613757970944 +1662064613805971968 +1662064613847972864 +1662064613886973696 +1662064613925974528 +1662064613976975616 +1662064614015976448 +1662064614057977344 +1662064614102978304 +1662064614144979200 +1662064614186980096 +1662064614228980992 +1662064614267981824 +1662064614318982912 +1662064614360983808 +1662064614405984768 +1662064614447985664 +1662064614489986560 +1662064614531987456 +1662064614570988288 +1662064614609989120 +1662064614654990080 +1662064614696990976 +1662064614741991936 +1662064614783992832 +1662064614828993792 +1662064614870994688 +1662064614915995648 +1662064614960996608 +1662064615002997504 +1662064615044998400 +1662064615086999296 +1662064615132000256 +1662064615177001216 +1662064615219002112 +1662064615261003008 +1662064615303003904 +1662064615345004800 +1662064615384005632 +1662064615423006464 +1662064615462007296 +1662064615498008064 +1662064615546009088 +1662064615588009984 +1662064615630010880 +1662064615675011840 +1662064615714012672 +1662064615756013568 +1662064615798014464 diff --git a/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt b/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt new file mode 100644 index 0000000000..51983432b0 --- /dev/null +++ b/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt @@ -0,0 +1,2076 @@ +1662125073430662912 +1662125073472663808 +1662125073511664640 +1662125073553665536 +1662125073598666496 +1662125073643667456 +1662125073688668416 +1662125073733669376 +1662125073781670400 +1662125073823671296 +1662125073865672192 +1662125073907673088 +1662125073952674048 +1662125073997675008 +1662125074042675968 +1662125074087676928 +1662125074132677888 +1662125074174678784 +1662125074216679680 +1662125074258680576 +1662125074303681536 +1662125074345682432 +1662125074387683328 +1662125074429684224 +1662125074474685184 +1662125074519686144 +1662125074564687104 +1662125074606688000 +1662125074651688960 +1662125074696689920 +1662125074741690880 +1662125074789691904 +1662125074831692800 +1662125074879693824 +1662125074918694656 +1662125074960695552 +1662125074999696384 +1662125075044697344 +1662125075086698240 +1662125075131699200 +1662125075176700160 +1662125075224701184 +1662125075269702144 +1662125075308702976 +1662125075347703808 +1662125075389704704 +1662125075440705792 +1662125075482706688 +1662125075524707584 +1662125075569708544 +1662125075617709568 +1662125075659710464 +1662125075701711360 +1662125075746712320 +1662125075788713216 +1662125075830714112 +1662125075872715008 +1662125075917715968 +1662125075956716800 +1662125076001717760 +1662125076046718720 +1662125076091719680 +1662125076139720704 +1662125076181721600 +1662125076223722496 +1662125076265723392 +1662125076307724288 +1662125076358725376 +1662125076400726272 +1662125076445727232 +1662125076490728192 +1662125076538729216 +1662125076580730112 +1662125076625731072 +1662125076670732032 +1662125076712732928 +1662125076754733824 +1662125076796734720 +1662125076847735808 +1662125076889736704 +1662125076934737664 +1662125076976738560 +1662125077024739584 +1662125077072740608 +1662125077114741504 +1662125077156742400 +1662125077195743232 +1662125077237744128 +1662125077279745024 +1662125077327746048 +1662125077366746880 +1662125077411747840 +1662125077453748736 +1662125077498749696 +1662125077540750592 +1662125077582751488 +1662125077627752448 +1662125077669753344 +1662125077711754240 +1662125077753755136 +1662125077795756032 +1662125077837756928 +1662125077879757824 +1662125077924758784 +1662125077969759744 +1662125078011760640 +1662125078056761600 +1662125078098762496 +1662125078143763456 +1662125078188764416 +1662125078227765248 +1662125078272766208 +1662125078314767104 +1662125078359768064 +1662125078401768960 +1662125078446769920 +1662125078494770944 +1662125078539771904 +1662125078587772928 +1662125078635773952 +1662125078677774848 +1662125078725775872 +1662125078767776768 +1662125078809777664 +1662125078848778496 +1662125078896779520 +1662125078938780416 +1662125078986781440 +1662125079025782272 +1662125079070783232 +1662125079112784128 +1662125079157785088 +1662125079199785984 +1662125079244786944 +1662125079289787904 +1662125079331788800 +1662125079373789696 +1662125079412790528 +1662125079457791488 +1662125079502792448 +1662125079541793280 +1662125079589794304 +1662125079625795072 +1662125079676796160 +1662125079715796992 +1662125079760797952 +1662125079802798848 +1662125079847799808 +1662125079892800768 +1662125079934801664 +1662125079976802560 +1662125080024803584 +1662125080066804480 +1662125080114805504 +1662125080162806528 +1662125080204807424 +1662125080246808320 +1662125080291809280 +1662125080336810240 +1662125080381811200 +1662125080423812096 +1662125080468813056 +1662125080510813952 +1662125080552814848 +1662125080597815808 +1662125080639816704 +1662125080684817664 +1662125080729818624 +1662125080771819520 +1662125080819820544 +1662125080861821440 +1662125080900822272 +1662125080948823296 +1662125080990824192 +1662125081032825088 +1662125081080826112 +1662125081122827008 +1662125081164827904 +1662125081206828800 +1662125081248829696 +1662125081296830720 +1662125081338831616 +1662125081380832512 +1662125081425833472 +1662125081467834368 +1662125081515835392 +1662125081557836288 +1662125081605837312 +1662125081653838336 +1662125081698839296 +1662125081743840256 +1662125081788841216 +1662125081833842176 +1662125081872843008 +1662125081923844096 +1662125081965844992 +1662125082010845952 +1662125082055846912 +1662125082097847808 +1662125082136848640 +1662125082178849536 +1662125082217850368 +1662125082256851200 +1662125082298852096 +1662125082346853120 +1662125082388854016 +1662125082433854976 +1662125082475855872 +1662125082520856832 +1662125082565857792 +1662125082610858752 +1662125082652859648 +1662125082697860608 +1662125082742861568 +1662125082781862400 +1662125082820863232 +1662125082859864064 +1662125082901864960 +1662125082943865856 +1662125082982866688 +1662125083024867584 +1662125083066868480 +1662125083111869440 +1662125083159870464 +1662125083207871488 +1662125083249872384 +1662125083294873344 +1662125083336874240 +1662125083378875136 +1662125083420876032 +1662125083462876928 +1662125083510877952 +1662125083555878912 +1662125083597879808 +1662125083639880704 +1662125083684881664 +1662125083726882560 +1662125083774883584 +1662125083813884416 +1662125083855885312 +1662125083900886272 +1662125083942887168 +1662125083984888064 +1662125084026888960 +1662125084068889856 +1662125084113890816 +1662125084155891712 +1662125084200892672 +1662125084242893568 +1662125084284894464 +1662125084326895360 +1662125084371896320 +1662125084416897280 +1662125084464898304 +1662125084509899264 +1662125084557900288 +1662125084605901312 +1662125084653902336 +1662125084695903232 +1662125084737904128 +1662125084776904960 +1662125084818905856 +1662125084857906688 +1662125084899907584 +1662125084944908544 +1662125084989909504 +1662125085031910400 +1662125085076911360 +1662125085127912448 +1662125085169913344 +1662125085214914304 +1662125085259915264 +1662125085301916160 +1662125085346917120 +1662125085388918016 +1662125085439919104 +1662125085481920000 +1662125085523920896 +1662125085565921792 +1662125085604922624 +1662125085649923584 +1662125085694924544 +1662125085739925504 +1662125085781926400 +1662125085826927360 +1662125085868928256 +1662125085913929216 +1662125085955930112 +1662125086000931072 +1662125086045932032 +1662125086087932928 +1662125086126933760 +1662125086168934656 +1662125086210935552 +1662125086249936384 +1662125086291937280 +1662125086333938176 +1662125086378939136 +1662125086423940096 +1662125086468941056 +1662125086519942144 +1662125086558942976 +1662125086603943936 +1662125086648944896 +1662125086693945856 +1662125086744946944 +1662125086783947776 +1662125086825948672 +1662125086870949632 +1662125086909950464 +1662125086951951360 +1662125086993952256 +1662125087038953216 +1662125087083954176 +1662125087125955072 +1662125087170956032 +1662125087215956992 +1662125087257957888 +1662125087299958784 +1662125087341959680 +1662125087386960640 +1662125087428961536 +1662125087473962496 +1662125087515963392 +1662125087557964288 +1662125087599965184 +1662125087644966144 +1662125087686967040 +1662125087731968000 +1662125087773968896 +1662125087812969728 +1662125087857970688 +1662125087896971520 +1662125087938972416 +1662125087977973248 +1662125088016974080 +1662125088061975040 +1662125088100975872 +1662125088151976960 +1662125088196977920 +1662125088241978880 +1662125088283979776 +1662125088334980864 +1662125088376981760 +1662125088418982656 +1662125088466983680 +1662125088511984640 +1662125088553985536 +1662125088601986560 +1662125088643987456 +1662125088685988352 +1662125088727989248 +1662125088766990080 +1662125088811991040 +1662125088856992000 +1662125088898992896 +1662125088943993856 +1662125088982994688 +1662125089018995456 +1662125089063996416 +1662125089108997376 +1662125089150998272 +1662125089189999104 +1662125089232000000 +1662125089277000960 +1662125089322001920 +1662125089373003008 +1662125089415003904 +1662125089457004800 +1662125089499005696 +1662125089550006784 +1662125089598007808 +1662125089640008704 +1662125089682009600 +1662125089727010560 +1662125089772011520 +1662125089814012416 +1662125089856013312 +1662125089898014208 +1662125089946015232 +1662125089991016192 +1662125090033017088 +1662125090075017984 +1662125090123019008 +1662125090165019904 +1662125090204020736 +1662125090243021568 +1662125090282022400 +1662125090327023360 +1662125090366024192 +1662125090402024960 +1662125090447025920 +1662125090489026816 +1662125090528027648 +1662125090573028608 +1662125090618029568 +1662125090660030464 +1662125090705031424 +1662125090747032320 +1662125090789033216 +1662125090834034176 +1662125090879035136 +1662125090930036224 +1662125090975037184 +1662125091020038144 +1662125091065039104 +1662125091110040064 +1662125091155041024 +1662125091197041920 +1662125091239042816 +1662125091284043776 +1662125091326044672 +1662125091368045568 +1662125091419046656 +1662125091461047552 +1662125091506048512 +1662125091548049408 +1662125091593050368 +1662125091635051264 +1662125091677052160 +1662125091719053056 +1662125091761053952 +1662125091806054912 +1662125091845055744 +1662125091887056640 +1662125091929057536 +1662125091977058560 +1662125092022059520 +1662125092067060480 +1662125092106061312 +1662125092148062208 +1662125092193063168 +1662125092235064064 +1662125092277064960 +1662125092319065856 +1662125092361066752 +1662125092406067712 +1662125092451068672 +1662125092496069632 +1662125092535070464 +1662125092580071424 +1662125092622072320 +1662125092667073280 +1662125092709074176 +1662125092751075072 +1662125092796076032 +1662125092838076928 +1662125092883077888 +1662125092925078784 +1662125092967079680 +1662125093012080640 +1662125093054081536 +1662125093102082560 +1662125093141083392 +1662125093183084288 +1662125093219085056 +1662125093261085952 +1662125093303086848 +1662125093348087808 +1662125093393088768 +1662125093435089664 +1662125093477090560 +1662125093522091520 +1662125093564092416 +1662125093606093312 +1662125093648094208 +1662125093690095104 +1662125093732096000 +1662125093771096832 +1662125093816097792 +1662125093858098688 +1662125093900099584 +1662125093942100480 +1662125093981101312 +1662125094023102208 +1662125094065103104 +1662125094110104064 +1662125094152104960 +1662125094194105856 +1662125094239106816 +1662125094284107776 +1662125094329108736 +1662125094377109760 +1662125094422110720 +1662125094467111680 +1662125094506112512 +1662125094548113408 +1662125094590114304 +1662125094638115328 +1662125094680116224 +1662125094722117120 +1662125094770118144 +1662125094815119104 +1662125094860120064 +1662125094908121088 +1662125094950121984 +1662125094995122944 +1662125095040123904 +1662125095085124864 +1662125095127125760 +1662125095169126656 +1662125095214127616 +1662125095253128448 +1662125095298129408 +1662125095340130304 +1662125095382131200 +1662125095424132096 +1662125095475133184 +1662125095517134080 +1662125095568135168 +1662125095613136128 +1662125095649136896 +1662125095685137664 +1662125095727138560 +1662125095772139520 +1662125095817140480 +1662125095856141312 +1662125095901142272 +1662125095940143104 +1662125095985144064 +1662125096024144896 +1662125096069145856 +1662125096114146816 +1662125096159147776 +1662125096201148672 +1662125096246149632 +1662125096291150592 +1662125096336151552 +1662125096381152512 +1662125096423153408 +1662125096465154304 +1662125096510155264 +1662125096555156224 +1662125096600157184 +1662125096648158208 +1662125096693159168 +1662125096732160000 +1662125096780161024 +1662125096819161856 +1662125096870162944 +1662125096909163776 +1662125096951164672 +1662125096993165568 +1662125097035166464 +1662125097080167424 +1662125097125168384 +1662125097170169344 +1662125097212170240 +1662125097251171072 +1662125097296172032 +1662125097338172928 +1662125097383173888 +1662125097428174848 +1662125097467175680 +1662125097512176640 +1662125097554177536 +1662125097596178432 +1662125097638179328 +1662125097680180224 +1662125097722181120 +1662125097764182016 +1662125097806182912 +1662125097848183808 +1662125097899184896 +1662125097944185856 +1662125097992186880 +1662125098034187776 +1662125098076188672 +1662125098118189568 +1662125098160190464 +1662125098205191424 +1662125098247192320 +1662125098289193216 +1662125098328194048 +1662125098373195008 +1662125098415195904 +1662125098457196800 +1662125098502197760 +1662125098544198656 +1662125098586199552 +1662125098637200640 +1662125098682201600 +1662125098724202496 +1662125098772203520 +1662125098814204416 +1662125098850205184 +1662125098892206080 +1662125098937207040 +1662125098985208064 +1662125099027208960 +1662125099072209920 +1662125099114210816 +1662125099153211648 +1662125099195212544 +1662125099240213504 +1662125099282214400 +1662125099330215424 +1662125099378216448 +1662125099423217408 +1662125099468218368 +1662125099510219264 +1662125099555220224 +1662125099600221184 +1662125099645222144 +1662125099687223040 +1662125099732224000 +1662125099774224896 +1662125099816225792 +1662125099861226752 +1662125099906227712 +1662125099951228672 +1662125099996229632 +1662125100041230592 +1662125100083231488 +1662125100122232320 +1662125100161233152 +1662125100209234176 +1662125100251235072 +1662125100296236032 +1662125100338236928 +1662125100383237888 +1662125100428238848 +1662125100470239744 +1662125100515240704 +1662125100551241472 +1662125100596242432 +1662125100635243264 +1662125100680244224 +1662125100722245120 +1662125100764246016 +1662125100806246912 +1662125100845247744 +1662125100890248704 +1662125100932249600 +1662125100977250560 +1662125101016251392 +1662125101061252352 +1662125101103253248 +1662125101145254144 +1662125101187255040 +1662125101229255936 +1662125101271256832 +1662125101316257792 +1662125101364258816 +1662125101412259840 +1662125101457260800 +1662125101499261696 +1662125101541262592 +1662125101580263424 +1662125101625264384 +1662125101673265408 +1662125101715266304 +1662125101760267264 +1662125101802268160 +1662125101844269056 +1662125101892270080 +1662125101934270976 +1662125101979271936 +1662125102027272960 +1662125102072273920 +1662125102114274816 +1662125102162275840 +1662125102204276736 +1662125102240277504 +1662125102279278336 +1662125102318279168 +1662125102363280128 +1662125102405281024 +1662125102441281792 +1662125102480282624 +1662125102522283520 +1662125102567284480 +1662125102612285440 +1662125102654286336 +1662125102696287232 +1662125102735288064 +1662125102777288960 +1662125102828290048 +1662125102870290944 +1662125102918291968 +1662125102963292928 +1662125103008293888 +1662125103050294784 +1662125103092295680 +1662125103137296640 +1662125103179297536 +1662125103221298432 +1662125103269299456 +1662125103308300288 +1662125103356301312 +1662125103401302272 +1662125103446303232 +1662125103485304064 +1662125103524304896 +1662125103563305728 +1662125103602306560 +1662125103644307456 +1662125103686308352 +1662125103728309248 +1662125103770310144 +1662125103812311040 +1662125103854311936 +1662125103896312832 +1662125103938313728 +1662125103980314624 +1662125104022315520 +1662125104064316416 +1662125104109317376 +1662125104151318272 +1662125104196319232 +1662125104241320192 +1662125104286321152 +1662125104328322048 +1662125104370322944 +1662125104412323840 +1662125104457324800 +1662125104496325632 +1662125104541326592 +1662125104592327680 +1662125104637328640 +1662125104682329600 +1662125104724330496 +1662125104769331456 +1662125104814332416 +1662125104859333376 +1662125104901334272 +1662125104952335360 +1662125104994336256 +1662125105036337152 +1662125105078338048 +1662125105126339072 +1662125105168339968 +1662125105210340864 +1662125105252341760 +1662125105294342656 +1662125105336343552 +1662125105381344512 +1662125105423345408 +1662125105468346368 +1662125105510347264 +1662125105552348160 +1662125105603349248 +1662125105648350208 +1662125105690351104 +1662125105729351936 +1662125105774352896 +1662125105819353856 +1662125105861354752 +1662125105906355712 +1662125105957356800 +1662125106002357760 +1662125106044358656 +1662125106089359616 +1662125106137360640 +1662125106176361472 +1662125106218362368 +1662125106260363264 +1662125106305364224 +1662125106350365184 +1662125106395366144 +1662125106440367104 +1662125106485368064 +1662125106527368960 +1662125106566369792 +1662125106611370752 +1662125106656371712 +1662125106701372672 +1662125106743373568 +1662125106791374592 +1662125106833375488 +1662125106878376448 +1662125106917377280 +1662125106959378176 +1662125107004379136 +1662125107046380032 +1662125107085380864 +1662125107133381888 +1662125107172382720 +1662125107208383488 +1662125107253384448 +1662125107298385408 +1662125107346386432 +1662125107388387328 +1662125107430388224 +1662125107472389120 +1662125107514390016 +1662125107553390848 +1662125107595391744 +1662125107637392640 +1662125107679393536 +1662125107718394368 +1662125107760395264 +1662125107802396160 +1662125107850397184 +1662125107895398144 +1662125107937399040 +1662125107982400000 +1662125108027400960 +1662125108069401856 +1662125108111402752 +1662125108156403712 +1662125108198404608 +1662125108240405504 +1662125108285406464 +1662125108333407488 +1662125108378408448 +1662125108423409408 +1662125108468410368 +1662125108507411200 +1662125108549412096 +1662125108588412928 +1662125108633413888 +1662125108672414720 +1662125108723415808 +1662125108765416704 +1662125108804417536 +1662125108849418496 +1662125108888419328 +1662125108933420288 +1662125108978421248 +1662125109017422080 +1662125109059422976 +1662125109101423872 +1662125109140424704 +1662125109185425664 +1662125109227426560 +1662125109269427456 +1662125109314428416 +1662125109359429376 +1662125109395430144 +1662125109437431040 +1662125109479431936 +1662125109521432832 +1662125109560433664 +1662125109602434560 +1662125109641435392 +1662125109689436416 +1662125109731437312 +1662125109776438272 +1662125109821439232 +1662125109860440064 +1662125109902440960 +1662125109944441856 +1662125109989442816 +1662125110028443648 +1662125110073444608 +1662125110121445632 +1662125110160446464 +1662125110202447360 +1662125110244448256 +1662125110286449152 +1662125110331450112 +1662125110370450944 +1662125110412451840 +1662125110457452800 +1662125110499453696 +1662125110544454656 +1662125110589455616 +1662125110631456512 +1662125110673457408 +1662125110715458304 +1662125110760459264 +1662125110808460288 +1662125110850461184 +1662125110889462016 +1662125110937463040 +1662125110988464128 +1662125111030465024 +1662125111078466048 +1662125111120466944 +1662125111162467840 +1662125111201468672 +1662125111243469568 +1662125111288470528 +1662125111330471424 +1662125111375472384 +1662125111414473216 +1662125111459474176 +1662125111501475072 +1662125111543475968 +1662125111585476864 +1662125111627477760 +1662125111672478720 +1662125111714479616 +1662125111759480576 +1662125111801481472 +1662125111843482368 +1662125111888483328 +1662125111930484224 +1662125111972485120 +1662125112017486080 +1662125112062487040 +1662125112107488000 +1662125112155489024 +1662125112197489920 +1662125112236490752 +1662125112278491648 +1662125112323492608 +1662125112368493568 +1662125112410494464 +1662125112452495360 +1662125112500496384 +1662125112539497216 +1662125112581498112 +1662125112623499008 +1662125112665499904 +1662125112704500736 +1662125112755501824 +1662125112794502656 +1662125112836503552 +1662125112881504512 +1662125112929505536 +1662125112977506560 +1662125113019507456 +1662125113064508416 +1662125113106509312 +1662125113151510272 +1662125113196511232 +1662125113238512128 +1662125113283513088 +1662125113322513920 +1662125113367514880 +1662125113415515904 +1662125113454516736 +1662125113496517632 +1662125113538518528 +1662125113583519488 +1662125113628520448 +1662125113670521344 +1662125113718522368 +1662125113763523328 +1662125113811524352 +1662125113853525248 +1662125113895526144 +1662125113940527104 +1662125113982528000 +1662125114021528832 +1662125114060529664 +1662125114099530496 +1662125114141531392 +1662125114183532288 +1662125114222533120 +1662125114267534080 +1662125114312535040 +1662125114357536000 +1662125114399536896 +1662125114441537792 +1662125114483538688 +1662125114531539712 +1662125114582540800 +1662125114624541696 +1662125114666542592 +1662125114708543488 +1662125114750544384 +1662125114792545280 +1662125114834546176 +1662125114876547072 +1662125114924548096 +1662125114969549056 +1662125115020550144 +1662125115065551104 +1662125115104551936 +1662125115146552832 +1662125115188553728 +1662125115233554688 +1662125115278555648 +1662125115323556608 +1662125115368557568 +1662125115410558464 +1662125115455559424 +1662125115497560320 +1662125115542561280 +1662125115581562112 +1662125115620562944 +1662125115662563840 +1662125115701564672 +1662125115746565632 +1662125115788566528 +1662125115833567488 +1662125115878568448 +1662125115923569408 +1662125115965570304 +1662125116007571200 +1662125116049572096 +1662125116094573056 +1662125116130573824 +1662125116175574784 +1662125116220575744 +1662125116268576768 +1662125116310577664 +1662125116349578496 +1662125116391579392 +1662125116436580352 +1662125116481581312 +1662125116526582272 +1662125116571583232 +1662125116607584000 +1662125116649584896 +1662125116691585792 +1662125116736586752 +1662125116781587712 +1662125116823588608 +1662125116862589440 +1662125116904590336 +1662125116943591168 +1662125116982592000 +1662125117027592960 +1662125117072593920 +1662125117117594880 +1662125117156595712 +1662125117201596672 +1662125117237597440 +1662125117276598272 +1662125117321599232 +1662125117363600128 +1662125117405601024 +1662125117447601920 +1662125117492602880 +1662125117537603840 +1662125117579604736 +1662125117618605568 +1662125117663606528 +1662125117705607424 +1662125117744608256 +1662125117789609216 +1662125117828610048 +1662125117870610944 +1662125117918611968 +1662125117963612928 +1662125118005613824 +1662125118047614720 +1662125118089615616 +1662125118131616512 +1662125118173617408 +1662125118215618304 +1662125118260619264 +1662125118299620096 +1662125118341620992 +1662125118386621952 +1662125118425622784 +1662125118470623744 +1662125118509624576 +1662125118554625536 +1662125118599626496 +1662125118641627392 +1662125118683628288 +1662125118725629184 +1662125118767630080 +1662125118809630976 +1662125118854631936 +1662125118896632832 +1662125118941633792 +1662125118980634624 +1662125119022635520 +1662125119070636544 +1662125119115637504 +1662125119154638336 +1662125119196639232 +1662125119238640128 +1662125119277640960 +1662125119322641920 +1662125119370642944 +1662125119415643904 +1662125119460644864 +1662125119505645824 +1662125119547646720 +1662125119580647424 +1662125119625648384 +1662125119670649344 +1662125119712650240 +1662125119754651136 +1662125119802652160 +1662125119844653056 +1662125119886653952 +1662125119928654848 +1662125119970655744 +1662125120012656640 +1662125120057657600 +1662125120102658560 +1662125120150659584 +1662125120195660544 +1662125120240661504 +1662125120282662400 +1662125120324663296 +1662125120369664256 +1662125120417665280 +1662125120459666176 +1662125120507667200 +1662125120555668224 +1662125120597669120 +1662125120639670016 +1662125120681670912 +1662125120723671808 +1662125120765672704 +1662125120804673536 +1662125120846674432 +1662125120885675264 +1662125120927676160 +1662125120969677056 +1662125121011677952 +1662125121053678848 +1662125121095679744 +1662125121137680640 +1662125121185681664 +1662125121230682624 +1662125121269683456 +1662125121311684352 +1662125121353685248 +1662125121398686208 +1662125121437687040 +1662125121488688128 +1662125121530689024 +1662125121575689984 +1662125121617690880 +1662125121662691840 +1662125121704692736 +1662125121749693696 +1662125121791694592 +1662125121833695488 +1662125121875696384 +1662125121920697344 +1662125121962698240 +1662125122007699200 +1662125122049700096 +1662125122091700992 +1662125122133701888 +1662125122175702784 +1662125122217703680 +1662125122259704576 +1662125122301705472 +1662125122340706304 +1662125122385707264 +1662125122430708224 +1662125122469709056 +1662125122511709952 +1662125122556710912 +1662125122601711872 +1662125122643712768 +1662125122685713664 +1662125122736714752 +1662125122778715648 +1662125122820716544 +1662125122868717568 +1662125122910718464 +1662125122952719360 +1662125122991720192 +1662125123033721088 +1662125123075721984 +1662125123120722944 +1662125123162723840 +1662125123201724672 +1662125123243725568 +1662125123285726464 +1662125123324727296 +1662125123366728192 +1662125123408729088 +1662125123453730048 +1662125123501731072 +1662125123543731968 +1662125123585732864 +1662125123627733760 +1662125123669734656 +1662125123717735680 +1662125123762736640 +1662125123804737536 +1662125123852738560 +1662125123891739392 +1662125123936740352 +1662125123975741184 +1662125124020742144 +1662125124059742976 +1662125124104743936 +1662125124146744832 +1662125124194745856 +1662125124239746816 +1662125124281747712 +1662125124329748736 +1662125124368749568 +1662125124410750464 +1662125124452751360 +1662125124494752256 +1662125124536753152 +1662125124578754048 +1662125124620754944 +1662125124665755904 +1662125124707756800 +1662125124746757632 +1662125124791758592 +1662125124833759488 +1662125124869760256 +1662125124911761152 +1662125124956762112 +1662125124998763008 +1662125125040763904 +1662125125085764864 +1662125125127765760 +1662125125172766720 +1662125125214767616 +1662125125262768640 +1662125125304769536 +1662125125346770432 +1662125125385771264 +1662125125427772160 +1662125125472773120 +1662125125514774016 +1662125125559774976 +1662125125601775872 +1662125125652776960 +1662125125700777984 +1662125125742778880 +1662125125790779904 +1662125125841780992 +1662125125883781888 +1662125125925782784 +1662125125976783872 +1662125126021784832 +1662125126066785792 +1662125126111786752 +1662125126153787648 +1662125126192788480 +1662125126231789312 +1662125126279790336 +1662125126321791232 +1662125126366792192 +1662125126408793088 +1662125126447793920 +1662125126495794944 +1662125126537795840 +1662125126582796800 +1662125126627797760 +1662125126669798656 +1662125126714799616 +1662125126753800448 +1662125126798801408 +1662125126831802112 +1662125126873803008 +1662125126915803904 +1662125126957804800 +1662125127002805760 +1662125127041806592 +1662125127089807616 +1662125127131808512 +1662125127170809344 +1662125127212810240 +1662125127254811136 +1662125127293811968 +1662125127335812864 +1662125127377813760 +1662125127419814656 +1662125127464815616 +1662125127503816448 +1662125127545817344 +1662125127584818176 +1662125127629819136 +1662125127677820160 +1662125127719821056 +1662125127761821952 +1662125127800822784 +1662125127842823680 +1662125127881824512 +1662125127926825472 +1662125127968826368 +1662125128007827200 +1662125128046828032 +1662125128088828928 +1662125128130829824 +1662125128175830784 +1662125128217831680 +1662125128259832576 +1662125128304833536 +1662125128340834304 +1662125128382835200 +1662125128424836096 +1662125128463836928 +1662125128508837888 +1662125128562839040 +1662125128610840064 +1662125128652840960 +1662125128697841920 +1662125128739842816 +1662125128781843712 +1662125128829844736 +1662125128871845632 +1662125128919846656 +1662125128958847488 +1662125129003848448 +1662125129045849344 +1662125129087850240 +1662125129126851072 +1662125129174852096 +1662125129219853056 +1662125129264854016 +1662125129306854912 +1662125129345855744 +1662125129390856704 +1662125129435857664 +1662125129480858624 +1662125129522859520 +1662125129567860480 +1662125129609861376 +1662125129651862272 +1662125129696863232 +1662125129738864128 +1662125129783865088 +1662125129825865984 +1662125129867866880 +1662125129912867840 +1662125129951868672 +1662125129993869568 +1662125130038870528 +1662125130083871488 +1662125130128872448 +1662125130167873280 +1662125130206874112 +1662125130248875008 +1662125130296876032 +1662125130338876928 +1662125130380877824 +1662125130422878720 +1662125130464879616 +1662125130506880512 +1662125130548881408 +1662125130593882368 +1662125130638883328 +1662125130680884224 +1662125130728885248 +1662125130767886080 +1662125130809886976 +1662125130854887936 +1662125130899888896 +1662125130941889792 +1662125130983890688 +1662125131025891584 +1662125131064892416 +1662125131109893376 +1662125131154894336 +1662125131196895232 +1662125131238896128 +1662125131283897088 +1662125131325897984 +1662125131367898880 +1662125131415899904 +1662125131457900800 +1662125131496901632 +1662125131541902592 +1662125131583903488 +1662125131625904384 +1662125131670905344 +1662125131712906240 +1662125131760907264 +1662125131805908224 +1662125131847909120 +1662125131892910080 +1662125131943911168 +1662125131988912128 +1662125132027912960 +1662125132066913792 +1662125132108914688 +1662125132153915648 +1662125132198916608 +1662125132243917568 +1662125132288918528 +1662125132330919424 +1662125132372920320 +1662125132417921280 +1662125132459922176 +1662125132504923136 +1662125132549924096 +1662125132594925056 +1662125132636925952 +1662125132675926784 +1662125132720927744 +1662125132759928576 +1662125132804929536 +1662125132849930496 +1662125132891931392 +1662125132933932288 +1662125132975933184 +1662125133020934144 +1662125133065935104 +1662125133107936000 +1662125133149936896 +1662125133191937792 +1662125133236938752 +1662125133278939648 +1662125133323940608 +1662125133365941504 +1662125133410942464 +1662125133452943360 +1662125133494944256 +1662125133536945152 +1662125133578946048 +1662125133626947072 +1662125133668947968 +1662125133710948864 +1662125133752949760 +1662125133791950592 +1662125133833951488 +1662125133878952448 +1662125133920953344 +1662125133962954240 +1662125134010955264 +1662125134055956224 +1662125134100957184 +1662125134148958208 +1662125134187959040 +1662125134229959936 +1662125134271960832 +1662125134313961728 +1662125134358962688 +1662125134403963648 +1662125134445964544 +1662125134490965504 +1662125134532966400 +1662125134577967360 +1662125134625968384 +1662125134670969344 +1662125134715970304 +1662125134757971200 +1662125134799972096 +1662125134847973120 +1662125134892974080 +1662125134937975040 +1662125134973975808 +1662125135018976768 +1662125135057977600 +1662125135102978560 +1662125135144979456 +1662125135192980480 +1662125135237981440 +1662125135279982336 +1662125135330983424 +1662125135378984448 +1662125135420985344 +1662125135465986304 +1662125135510987264 +1662125135549988096 +1662125135594989056 +1662125135639990016 +1662125135681990912 +1662125135726991872 +1662125135768992768 +1662125135807993600 +1662125135855994624 +1662125135903995648 +1662125135945996544 +1662125135987997440 +1662125136029998336 +1662125136071999232 +1662125136120000256 +1662125136165001216 +1662125136204002048 +1662125136243002880 +1662125136285003776 +1662125136330004736 +1662125136372005632 +1662125136414006528 +1662125136456007424 +1662125136501008384 +1662125136540009216 +1662125136585010176 +1662125136627011072 +1662125136663011840 +1662125136705012736 +1662125136750013696 +1662125136792014592 +1662125136834015488 +1662125136876016384 +1662125136921017344 +1662125136960018176 +1662125136999019008 +1662125137041019904 +1662125137083020800 +1662125137122021632 +1662125137164022528 +1662125137209023488 +1662125137251024384 +1662125137290025216 +1662125137329026048 +1662125137371026944 +1662125137416027904 +1662125137464028928 +1662125137509029888 +1662125137551030784 +1662125137593031680 +1662125137635032576 +1662125137677033472 +1662125137719034368 +1662125137770035456 +1662125137809036288 +1662125137851037184 +1662125137890038016 +1662125137932038912 +1662125137977039872 +1662125138016040704 +1662125138058041600 +1662125138100042496 +1662125138142043392 +1662125138181044224 +1662125138223045120 +1662125138268046080 +1662125138313047040 +1662125138358048000 +1662125138406049024 +1662125138457050112 +1662125138499051008 +1662125138547052032 +1662125138589052928 +1662125138634053888 +1662125138676054784 +1662125138721055744 +1662125138763056640 +1662125138811057664 +1662125138853058560 +1662125138895059456 +1662125138937060352 +1662125138979061248 +1662125139021062144 +1662125139063063040 +1662125139102063872 +1662125139144064768 +1662125139192065792 +1662125139237066752 +1662125139279067648 +1662125139318068480 +1662125139366069504 +1662125139408070400 +1662125139450071296 +1662125139492072192 +1662125139534073088 +1662125139585074176 +1662125139630075136 +1662125139675076096 +1662125139720077056 +1662125139762077952 +1662125139801078784 +1662125139843079680 +1662125139882080512 +1662125139924081408 +1662125139963082240 +1662125140005083136 +1662125140047084032 +1662125140089084928 +1662125140128085760 +1662125140173086720 +1662125140218087680 +1662125140263088640 +1662125140305089536 +1662125140347090432 +1662125140386091264 +1662125140428092160 +1662125140470093056 +1662125140518094080 +1662125140560094976 +1662125140602095872 +1662125140644096768 +1662125140689097728 +1662125140731098624 +1662125140779099648 +1662125140830100736 +1662125140872101632 +1662125140914102528 +1662125140959103488 +1662125141001104384 +1662125141040105216 +1662125141082106112 +1662125141124107008 +1662125141166107904 +1662125141211108864 +1662125141253109760 +1662125141298110720 +1662125141343111680 +1662125141382112512 +1662125141424113408 +1662125141466114304 +1662125141511115264 +1662125141553116160 +1662125141595117056 +1662125141640118016 +1662125141682118912 +1662125141724119808 +1662125141769120768 +1662125141817121792 +1662125141859122688 +1662125141904123648 +1662125141949124608 +1662125141994125568 +1662125142036126464 +1662125142075127296 +1662125142117128192 +1662125142159129088 +1662125142207130112 +1662125142252131072 +1662125142294131968 +1662125142336132864 +1662125142375133696 +1662125142420134656 +1662125142465135616 +1662125142507136512 +1662125142555137536 +1662125142600138496 +1662125142642139392 +1662125142681140224 +1662125142723141120 +1662125142765142016 +1662125142807142912 +1662125142849143808 +1662125142891144704 +1662125142936145664 +1662125142978146560 +1662125143026147584 +1662125143071148544 +1662125143113149440 +1662125143158150400 +1662125143197151232 +1662125143242152192 +1662125143290153216 +1662125143332154112 +1662125143377155072 +1662125143419155968 +1662125143473157120 +1662125143515158016 +1662125143560158976 +1662125143602159872 +1662125143641160704 +1662125143686161664 +1662125143725162496 +1662125143773163520 +1662125143818164480 +1662125143860165376 +1662125143911166464 +1662125143953167360 +1662125143992168192 +1662125144037169152 +1662125144085170176 +1662125144127171072 +1662125144172172032 +1662125144220173056 +1662125144268174080 +1662125144316175104 +1662125144355175936 +1662125144397176832 +1662125144442177792 +1662125144484178688 +1662125144526179584 +1662125144568180480 +1662125144610181376 +1662125144655182336 +1662125144703183360 +1662125144748184320 +1662125144793185280 +1662125144835186176 +1662125144883187200 +1662125144925188096 +1662125144970189056 +1662125145021190144 +1662125145072191232 +1662125145114192128 +1662125145156193024 +1662125145198193920 +1662125145240194816 +1662125145285195776 +1662125145333196800 +1662125145381197824 +1662125145426198784 +1662125145471199744 +1662125145513200640 +1662125145564201728 +1662125145600202496 +1662125145639203328 +1662125145684204288 +1662125145726205184 +1662125145762205952 +1662125145807206912 +1662125145849207808 +1662125145897208832 +1662125145939209728 +1662125145981210624 +1662125146029211648 +1662125146074212608 +1662125146119213568 +1662125146161214464 +1662125146203215360 +1662125146245216256 +1662125146290217216 +1662125146335218176 +1662125146380219136 +1662125146422220032 +1662125146464220928 +1662125146506221824 +1662125146545222656 +1662125146596223744 +1662125146638224640 +1662125146680225536 +1662125146722226432 +1662125146764227328 +1662125146809228288 +1662125146851229184 +1662125146893230080 +1662125146938231040 +1662125146977231872 +1662125147019232768 +1662125147061233664 +1662125147106234624 +1662125147151235584 +1662125147193236480 +1662125147235237376 +1662125147280238336 +1662125147325239296 +1662125147370240256 +1662125147415241216 +1662125147457242112 +1662125147499243008 +1662125147541243904 +1662125147583244800 +1662125147628245760 +1662125147673246720 +1662125147715247616 +1662125147757248512 +1662125147796249344 +1662125147841250304 +1662125147883251200 +1662125147931252224 +1662125147973253120 +1662125148012253952 +1662125148057254912 +1662125148099255808 +1662125148138256640 +1662125148186257664 +1662125148228258560 +1662125148270259456 +1662125148312260352 +1662125148354261248 +1662125148399262208 +1662125148441263104 +1662125148483264000 +1662125148528264960 +1662125148567265792 +1662125148618266880 +1662125148657267712 +1662125148702268672 +1662125148744269568 +1662125148786270464 +1662125148834271488 +1662125148879272448 +1662125148927273472 +1662125148975274496 +1662125149020275456 +1662125149062276352 +1662125149104277248 +1662125149146278144 +1662125149197279232 +1662125149242280192 +1662125149284281088 +1662125149329282048 +1662125149377283072 +1662125149419283968 +1662125149458284800 +1662125149494285568 +1662125149530286336 +1662125149572287232 +1662125149617288192 +1662125149659289088 +1662125149698289920 +1662125149743290880 +1662125149788291840 +1662125149830292736 +1662125149875293696 +1662125149920294656 +1662125149962295552 +1662125150007296512 +1662125150049297408 +1662125150091298304 +1662125150133299200 +1662125150184300288 +1662125150229301248 +1662125150271302144 +1662125150313303040 +1662125150358304000 +1662125150400304896 +1662125150445305856 +1662125150484306688 +1662125150526307584 +1662125150577308672 +1662125150622309632 +1662125150667310592 +1662125150709311488 +1662125150754312448 +1662125150796313344 +1662125150841314304 +1662125150883315200 +1662125150928316160 +1662125150973317120 +1662125151015318016 +1662125151054318848 +1662125151093319680 +1662125151135320576 +1662125151174321408 +1662125151213322240 +1662125151258323200 +1662125151300324096 +1662125151345325056 +1662125151393326080 +1662125151435326976 +1662125151477327872 +1662125151522328832 +1662125151561329664 +1662125151606330624 +1662125151651331584 +1662125151696332544 +1662125151738333440 +1662125151780334336 +1662125151825335296 +1662125151870336256 +1662125151912337152 +1662125151960338176 +1662125152002339072 +1662125152044339968 +1662125152086340864 +1662125152131341824 +1662125152173342720 +1662125152215343616 +1662125152254344448 +1662125152296345344 +1662125152344346368 +1662125152389347328 +1662125152428348160 +1662125152473349120 +1662125152518350080 +1662125152563351040 +1662125152611352064 +1662125152653352960 +1662125152698353920 +1662125152743354880 +1662125152782355712 +1662125152824356608 +1662125152869357568 +1662125152914358528 +1662125152956359424 +1662125152992360192 +1662125153031361024 +1662125153067361792 +1662125153109362688 +1662125153154363648 +1662125153199364608 +1662125153241365504 +1662125153283366400 +1662125153325367296 +1662125153367368192 +1662125153412369152 +1662125153454370048 +1662125153490370816 +1662125153535371776 +1662125153580372736 +1662125153622373632 +1662125153664374528 +1662125153706375424 +1662125153748376320 +1662125153790377216 +1662125153835378176 +1662125153874379008 +1662125153916379904 +1662125153958380800 +1662125154000381696 +1662125154045382656 +1662125154093383680 +1662125154135384576 +1662125154180385536 +1662125154228386560 +1662125154270387456 +1662125154312388352 +1662125154354389248 +1662125154402390272 +1662125154447391232 +1662125154492392192 +1662125154534393088 +1662125154576393984 +1662125154618394880 +1662125154660395776 +1662125154699396608 +1662125154741397504 +1662125154783398400 +1662125154831399424 +1662125154873400320 +1662125154915401216 +1662125154957402112 +1662125154996402944 +1662125155038403840 +1662125155080404736 +1662125155119405568 +1662125155167406592 +1662125155206407424 +1662125155245408256 +1662125155287409152 +1662125155332410112 +1662125155377411072 +1662125155419411968 +1662125155464412928 +1662125155503413760 +1662125155548414720 +1662125155593415680 +1662125155632416512 +1662125155671417344 +1662125155713418240 +1662125155755419136 +1662125155797420032 +1662125155842420992 +1662125155887421952 +1662125155929422848 +1662125155971423744 +1662125156013424640 +1662125156052425472 +1662125156094426368 +1662125156136427264 +1662125156181428224 +1662125156223429120 +1662125156265430016 +1662125156316431104 +1662125156355431936 +1662125156397432832 +1662125156436433664 +1662125156481434624 +1662125156523435520 +1662125156568436480 +1662125156610437376 +1662125156652438272 +1662125156697439232 +1662125156739440128 +1662125156778440960 +1662125156823441920 +1662125156865442816 +1662125156916443904 +1662125156958444800 +1662125157003445760 +1662125157051446784 +1662125157093447680 +1662125157138448640 +1662125157183449600 +1662125157228450560 +1662125157276451584 +1662125157321452544 +1662125157366453504 +1662125157414454528 +1662125157456455424 +1662125157498456320 +1662125157540457216 +1662125157582458112 +1662125157627459072 +1662125157672460032 +1662125157714460928 +1662125157759461888 +1662125157804462848 +1662125157846463744 +1662125157891464704 +1662125157933465600 +1662125157978466560 +1662125158026467584 +1662125158074468608 +1662125158116469504 +1662125158158470400 +1662125158200471296 +1662125158242472192 +1662125158284473088 +1662125158326473984 +1662125158368474880 +1662125158407475712 +1662125158449476608 +1662125158491477504 +1662125158536478464 +1662125158578479360 +1662125158626480384 +1662125158671481344 +1662125158713482240 +1662125158755483136 +1662125158800484096 +1662125158842484992 +1662125158890486016 +1662125158935486976 +1662125158980487936 +1662125159025488896 +1662125159067489792 +1662125159109490688 +1662125159151491584 +1662125159193492480 +1662125159235493376 +1662125159277494272 +1662125159319495168 +1662125159361496064 +1662125159406497024 +1662125159448497920 +1662125159490498816 +1662125159535499776 +1662125159583500800 +1662125159625501696 +1662125159667502592 +1662125159706503424 +1662125159742504192 +1662125159781505024 +1662125159823505920 +1662125159865506816 +1662125159913507840 +1662125159961508864 +1662125160003509760 +1662125160045510656 +1662125160090511616 +1662125160138512640 +1662125160180513536 +1662125160222514432 +1662125160261515264 +1662125160303516160 +1662125160348517120 +1662125160387517952 +1662125160432518912 +1662125160474519808 +1662125160519520768 +1662125160558521600 +1662125160597522432 +1662125160645523456 +1662125160687524352 +1662125160729525248 +1662125160771526144 +1662125160813527040 +1662125160855527936 +1662125160900528896 +1662125160942529792 +1662125160990530816 +1662125161038531840 +1662125161080532736 +1662125161128533760 +1662125161176534784 +1662125161218535680 +1662125161266536704 +1662125161314537728 +1662125161359538688 +1662125161401539584 +1662125161443540480 +1662125161491541504 +1662125161533542400 +1662125161578543360 +1662125161620544256 +1662125161662545152 +1662125161701545984 +1662125161749547008 +1662125161791547904 +1662125161833548800 +1662125161875549696 +1662125161923550720 +1662125161971551744 +1662125162013552640 +1662125162055553536 +1662125162100554496 +1662125162145555456 +1662125162187556352 +1662125162229557248 +1662125162271558144 +1662125162319559168 +1662125162355559936 +1662125162397560832 +1662125162442561792 +1662125162484562688 +1662125162532563712 +1662125162574564608 +1662125162616565504 +1662125162661566464 +1662125162703567360 +1662125162748568320 +1662125162793569280 +1662125162832570112 +1662125162877571072 +1662125162919571968 +1662125162961572864 +1662125163006573824 +1662125163048574720 +1662125163093575680 +1662125163138576640 +1662125163183577600 diff --git a/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt b/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt new file mode 100644 index 0000000000..7283c7fd50 --- /dev/null +++ b/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt @@ -0,0 +1,2489 @@ +1662120285510217728 +1662120285552218624 +1662120285594219520 +1662120285636220416 +1662120285681221376 +1662120285723222272 +1662120285768223232 +1662120285810224128 +1662120285858225152 +1662120285897225984 +1662120285936226816 +1662120285981227776 +1662120286023228672 +1662120286065229568 +1662120286107230464 +1662120286149231360 +1662120286191232256 +1662120286233233152 +1662120286281234176 +1662120286323235072 +1662120286371236096 +1662120286413236992 +1662120286455237888 +1662120286497238784 +1662120286539239680 +1662120286581240576 +1662120286620241408 +1662120286662242304 +1662120286701243136 +1662120286740243968 +1662120286782244864 +1662120286827245824 +1662120286875246848 +1662120286920247808 +1662120286968248832 +1662120287010249728 +1662120287052250624 +1662120287097251584 +1662120287139252480 +1662120287181253376 +1662120287220254208 +1662120287265255168 +1662120287307256064 +1662120287352257024 +1662120287397257984 +1662120287436258816 +1662120287475259648 +1662120287517260544 +1662120287559261440 +1662120287601262336 +1662120287646263296 +1662120287688264192 +1662120287733265152 +1662120287772265984 +1662120287814266880 +1662120287862267904 +1662120287907268864 +1662120287952269824 +1662120288000270848 +1662120288039271680 +1662120288087272704 +1662120288135273728 +1662120288177274624 +1662120288225275648 +1662120288267276544 +1662120288309277440 +1662120288354278400 +1662120288396279296 +1662120288438280192 +1662120288483281152 +1662120288528282112 +1662120288576283136 +1662120288624284160 +1662120288666285056 +1662120288708285952 +1662120288747286784 +1662120288792287744 +1662120288834288640 +1662120288873289472 +1662120288918290432 +1662120288963291392 +1662120289008292352 +1662120289050293248 +1662120289092294144 +1662120289131294976 +1662120289176295936 +1662120289218296832 +1662120289260297728 +1662120289311298816 +1662120289356299776 +1662120289398300672 +1662120289440301568 +1662120289485302528 +1662120289527303424 +1662120289569304320 +1662120289608305152 +1662120289653306112 +1662120289695307008 +1662120289734307840 +1662120289773308672 +1662120289812309504 +1662120289854310400 +1662120289896311296 +1662120289938312192 +1662120289983313152 +1662120290025314048 +1662120290067314944 +1662120290115315968 +1662120290157316864 +1662120290202317824 +1662120290247318784 +1662120290292319744 +1662120290340320768 +1662120290385321728 +1662120290430322688 +1662120290478323712 +1662120290526324736 +1662120290568325632 +1662120290613326592 +1662120290652327424 +1662120290694328320 +1662120290730329088 +1662120290772329984 +1662120290814330880 +1662120290853331712 +1662120290898332672 +1662120290937333504 +1662120290979334400 +1662120291021335296 +1662120291060336128 +1662120291108337152 +1662120291150338048 +1662120291195339008 +1662120291240339968 +1662120291291341056 +1662120291336342016 +1662120291381342976 +1662120291423343872 +1662120291477345024 +1662120291519345920 +1662120291567346944 +1662120291606347776 +1662120291648348672 +1662120291690349568 +1662120291735350528 +1662120291777351424 +1662120291825352448 +1662120291870353408 +1662120291912354304 +1662120291954355200 +1662120291996356096 +1662120292041357056 +1662120292080357888 +1662120292119358720 +1662120292167359744 +1662120292209360640 +1662120292251361536 +1662120292293362432 +1662120292335363328 +1662120292377364224 +1662120292419365120 +1662120292470366208 +1662120292512367104 +1662120292560368128 +1662120292602369024 +1662120292647369984 +1662120292692370944 +1662120292734371840 +1662120292776372736 +1662120292818373632 +1662120292860374528 +1662120292902375424 +1662120292947376384 +1662120292989377280 +1662120293031378176 +1662120293076379136 +1662120293118380032 +1662120293160380928 +1662120293202381824 +1662120293244382720 +1662120293289383680 +1662120293331384576 +1662120293376385536 +1662120293418386432 +1662120293463387392 +1662120293505388288 +1662120293547389184 +1662120293592390144 +1662120293634391040 +1662120293679392000 +1662120293724392960 +1662120293766393856 +1662120293811394816 +1662120293856395776 +1662120293895396608 +1662120293940397568 +1662120293988398592 +1662120294033399552 +1662120294078400512 +1662120294123401472 +1662120294168402432 +1662120294213403392 +1662120294249404160 +1662120294291405056 +1662120294330405888 +1662120294372406784 +1662120294420407808 +1662120294462408704 +1662120294507409664 +1662120294546410496 +1662120294588411392 +1662120294633412352 +1662120294684413440 +1662120294729414400 +1662120294774415360 +1662120294816416256 +1662120294861417216 +1662120294903418112 +1662120294951419136 +1662120294996420096 +1662120295044421120 +1662120295083421952 +1662120295128422912 +1662120295170423808 +1662120295218424832 +1662120295263425792 +1662120295305426688 +1662120295347427584 +1662120295389428480 +1662120295434429440 +1662120295476430336 +1662120295521431296 +1662120295566432256 +1662120295605433088 +1662120295647433984 +1662120295692434944 +1662120295734435840 +1662120295776436736 +1662120295818437632 +1662120295866438656 +1662120295911439616 +1662120295953440512 +1662120295995441408 +1662120296037442304 +1662120296082443264 +1662120296130444288 +1662120296169445120 +1662120296208445952 +1662120296250446848 +1662120296295447808 +1662120296337448704 +1662120296379449600 +1662120296421450496 +1662120296457451264 +1662120296499452160 +1662120296541453056 +1662120296589454080 +1662120296637455104 +1662120296682456064 +1662120296724456960 +1662120296766457856 +1662120296808458752 +1662120296850459648 +1662120296892460544 +1662120296937461504 +1662120296979462400 +1662120297021463296 +1662120297066464256 +1662120297111465216 +1662120297153466112 +1662120297201467136 +1662120297246468096 +1662120297288468992 +1662120297327469824 +1662120297372470784 +1662120297414471680 +1662120297459472640 +1662120297504473600 +1662120297552474624 +1662120297597475584 +1662120297639476480 +1662120297684477440 +1662120297726478336 +1662120297765479168 +1662120297804480000 +1662120297843480832 +1662120297885481728 +1662120297927482624 +1662120297972483584 +1662120298005484288 +1662120298053485312 +1662120298095486208 +1662120298137487104 +1662120298179488000 +1662120298227489024 +1662120298269489920 +1662120298311490816 +1662120298350491648 +1662120298395492608 +1662120298446493696 +1662120298491494656 +1662120298533495552 +1662120298575496448 +1662120298617497344 +1662120298662498304 +1662120298713499392 +1662120298755500288 +1662120298800501248 +1662120298842502144 +1662120298884503040 +1662120298926503936 +1662120298968504832 +1662120299010505728 +1662120299052506624 +1662120299094507520 +1662120299136508416 +1662120299178509312 +1662120299220510208 +1662120299262511104 +1662120299307512064 +1662120299352513024 +1662120299391513856 +1662120299433514752 +1662120299481515776 +1662120299523516672 +1662120299568517632 +1662120299613518592 +1662120299658519552 +1662120299700520448 +1662120299742521344 +1662120299787522304 +1662120299832523264 +1662120299874524160 +1662120299916525056 +1662120299961526016 +1662120300006526976 +1662120300048527872 +1662120300084528640 +1662120300126529536 +1662120300171530496 +1662120300216531456 +1662120300261532416 +1662120300303533312 +1662120300348534272 +1662120300390535168 +1662120300432536064 +1662120300474536960 +1662120300516537856 +1662120300564538880 +1662120300609539840 +1662120300651540736 +1662120300693541632 +1662120300735542528 +1662120300777543424 +1662120300822544384 +1662120300864545280 +1662120300915546368 +1662120300960547328 +1662120301002548224 +1662120301044549120 +1662120301086550016 +1662120301128550912 +1662120301176551936 +1662120301221552896 +1662120301260553728 +1662120301308554752 +1662120301353555712 +1662120301401556736 +1662120301443557632 +1662120301485558528 +1662120301527559424 +1662120301572560384 +1662120301614561280 +1662120301662562304 +1662120301704563200 +1662120301746564096 +1662120301785564928 +1662120301827565824 +1662120301869566720 +1662120301911567616 +1662120301950568448 +1662120301995569408 +1662120302037570304 +1662120302085571328 +1662120302130572288 +1662120302175573248 +1662120302220574208 +1662120302265575168 +1662120302307576064 +1662120302346576896 +1662120302391577856 +1662120302439578880 +1662120302484579840 +1662120302532580864 +1662120302574581760 +1662120302616582656 +1662120302658583552 +1662120302697584384 +1662120302742585344 +1662120302787586304 +1662120302829587200 +1662120302871588096 +1662120302916589056 +1662120302958589952 +1662120303000590848 +1662120303051591936 +1662120303099592960 +1662120303141593856 +1662120303183594752 +1662120303231595776 +1662120303279596800 +1662120303321597696 +1662120303360598528 +1662120303399599360 +1662120303450600448 +1662120303495601408 +1662120303537602304 +1662120303576603136 +1662120303618604032 +1662120303657604864 +1662120303702605824 +1662120303750606848 +1662120303792607744 +1662120303837608704 +1662120303879609600 +1662120303930610688 +1662120303975611648 +1662120304017612544 +1662120304059613440 +1662120304104614400 +1662120304149615360 +1662120304191616256 +1662120304236617216 +1662120304278618112 +1662120304320619008 +1662120304362619904 +1662120304401620736 +1662120304443621632 +1662120304485622528 +1662120304530623488 +1662120304578624512 +1662120304623625472 +1662120304665626368 +1662120304710627328 +1662120304755628288 +1662120304800629248 +1662120304848630272 +1662120304893631232 +1662120304938632192 +1662120304980633088 +1662120305022633984 +1662120305067634944 +1662120305112635904 +1662120305148636672 +1662120305196637696 +1662120305235638528 +1662120305274639360 +1662120305319640320 +1662120305364641280 +1662120305403642112 +1662120305445643008 +1662120305490643968 +1662120305535644928 +1662120305577645824 +1662120305619646720 +1662120305664647680 +1662120305703648512 +1662120305745649408 +1662120305790650368 +1662120305838651392 +1662120305883652352 +1662120305928653312 +1662120305970654208 +1662120306012655104 +1662120306054656000 +1662120306102657024 +1662120306150658048 +1662120306192658944 +1662120306237659904 +1662120306282660864 +1662120306324661760 +1662120306369662720 +1662120306417663744 +1662120306462664704 +1662120306507665664 +1662120306549666560 +1662120306591667456 +1662120306633668352 +1662120306678669312 +1662120306723670272 +1662120306765671168 +1662120306810672128 +1662120306855673088 +1662120306897673984 +1662120306939674880 +1662120306978675712 +1662120307017676544 +1662120307065677568 +1662120307104678400 +1662120307149679360 +1662120307191680256 +1662120307236681216 +1662120307281682176 +1662120307323683072 +1662120307365683968 +1662120307407684864 +1662120307449685760 +1662120307491686656 +1662120307527687424 +1662120307572688384 +1662120307614689280 +1662120307656690176 +1662120307707691264 +1662120307752692224 +1662120307794693120 +1662120307836694016 +1662120307878694912 +1662120307923695872 +1662120307971696896 +1662120308016697856 +1662120308058698752 +1662120308100699648 +1662120308142700544 +1662120308181701376 +1662120308226702336 +1662120308271703296 +1662120308313704192 +1662120308355705088 +1662120308403706112 +1662120308451707136 +1662120308496708096 +1662120308538708992 +1662120308580709888 +1662120308622710784 +1662120308661711616 +1662120308709712640 +1662120308751713536 +1662120308790714368 +1662120308835715328 +1662120308880716288 +1662120308922717184 +1662120308964718080 +1662120309003718912 +1662120309045719808 +1662120309090720768 +1662120309135721728 +1662120309177722624 +1662120309216723456 +1662120309258724352 +1662120309300725248 +1662120309345726208 +1662120309390727168 +1662120309435728128 +1662120309474728960 +1662120309516729856 +1662120309561730816 +1662120309603731712 +1662120309645732608 +1662120309690733568 +1662120309729734400 +1662120309777735424 +1662120309819736320 +1662120309864737280 +1662120309915738368 +1662120309957739264 +1662120310002740224 +1662120310044741120 +1662120310092742144 +1662120310134743040 +1662120310179744000 +1662120310224744960 +1662120310266745856 +1662120310311746816 +1662120310353747712 +1662120310395748608 +1662120310440749568 +1662120310482750464 +1662120310527751424 +1662120310572752384 +1662120310611753216 +1662120310662754304 +1662120310704755200 +1662120310746756096 +1662120310788756992 +1662120310839758080 +1662120310881758976 +1662120310923759872 +1662120310971760896 +1662120311016761856 +1662120311061762816 +1662120311109763840 +1662120311151764736 +1662120311190765568 +1662120311241766656 +1662120311283767552 +1662120311325768448 +1662120311367769344 +1662120311412770304 +1662120311454771200 +1662120311505772288 +1662120311547773184 +1662120311592774144 +1662120311634775040 +1662120311676775936 +1662120311721776896 +1662120311763777792 +1662120311808778752 +1662120311850779648 +1662120311892780544 +1662120311937781504 +1662120311982782464 +1662120312027783424 +1662120312063784192 +1662120312108785152 +1662120312150786048 +1662120312195787008 +1662120312234787840 +1662120312279788800 +1662120312327789824 +1662120312369790720 +1662120312411791616 +1662120312453792512 +1662120312495793408 +1662120312540794368 +1662120312588795392 +1662120312636796416 +1662120312678797312 +1662120312723798272 +1662120312765799168 +1662120312804800000 +1662120312849800960 +1662120312894801920 +1662120312939802880 +1662120312981803776 +1662120313026804736 +1662120313068805632 +1662120313110806528 +1662120313152807424 +1662120313197808384 +1662120313242809344 +1662120313284810240 +1662120313326811136 +1662120313371812096 +1662120313413812992 +1662120313455813888 +1662120313497814784 +1662120313545815808 +1662120313584816640 +1662120313626817536 +1662120313668818432 +1662120313713819392 +1662120313755820288 +1662120313797821184 +1662120313839822080 +1662120313884823040 +1662120313929824000 +1662120313977825024 +1662120314031826176 +1662120314073827072 +1662120314115827968 +1662120314160828928 +1662120314202829824 +1662120314247830784 +1662120314295831808 +1662120314340832768 +1662120314379833600 +1662120314421834496 +1662120314466835456 +1662120314508836352 +1662120314553837312 +1662120314598838272 +1662120314637839104 +1662120314682840064 +1662120314724840960 +1662120314772841984 +1662120314811842816 +1662120314856843776 +1662120314898844672 +1662120314940845568 +1662120314988846592 +1662120315033847552 +1662120315078848512 +1662120315123849472 +1662120315168850432 +1662120315210851328 +1662120315252852224 +1662120315294853120 +1662120315345854208 +1662120315390855168 +1662120315435856128 +1662120315489857280 +1662120315537858304 +1662120315582859264 +1662120315630860288 +1662120315675861248 +1662120315717862144 +1662120315762863104 +1662120315807864064 +1662120315849864960 +1662120315891865856 +1662120315933866752 +1662120315975867648 +1662120316017868544 +1662120316062869504 +1662120316104870400 +1662120316149871360 +1662120316191872256 +1662120316230873088 +1662120316275874048 +1662120316317874944 +1662120316362875904 +1662120316404876800 +1662120316449877760 +1662120316494878720 +1662120316539879680 +1662120316581880576 +1662120316620881408 +1662120316665882368 +1662120316704883200 +1662120316746884096 +1662120316791885056 +1662120316836886016 +1662120316878886912 +1662120316917887744 +1662120316962888704 +1662120317001889536 +1662120317049890560 +1662120317100891648 +1662120317142892544 +1662120317187893504 +1662120317232894464 +1662120317277895424 +1662120317322896384 +1662120317367897344 +1662120317409898240 +1662120317454899200 +1662120317496900096 +1662120317544901120 +1662120317586902016 +1662120317628902912 +1662120317673903872 +1662120317715904768 +1662120317757905664 +1662120317802906624 +1662120317844907520 +1662120317886908416 +1662120317934909440 +1662120317976910336 +1662120318018911232 +1662120318060912128 +1662120318102913024 +1662120318147913984 +1662120318192914944 +1662120318231915776 +1662120318270916608 +1662120318315917568 +1662120318357918464 +1662120318399919360 +1662120318447920384 +1662120318492921344 +1662120318534922240 +1662120318576923136 +1662120318618924032 +1662120318663924992 +1662120318708925952 +1662120318753926912 +1662120318798927872 +1662120318843928832 +1662120318891929856 +1662120318936930816 +1662120318978931712 +1662120319017932544 +1662120319062933504 +1662120319104934400 +1662120319149935360 +1662120319191936256 +1662120319236937216 +1662120319278938112 +1662120319323939072 +1662120319365939968 +1662120319413940992 +1662120319455941888 +1662120319500942848 +1662120319542943744 +1662120319587944704 +1662120319632945664 +1662120319680946688 +1662120319725947648 +1662120319770948608 +1662120319812949504 +1662120319854950400 +1662120319899951360 +1662120319941952256 +1662120319986953216 +1662120320028954112 +1662120320073955072 +1662120320115955968 +1662120320160956928 +1662120320202957824 +1662120320247958784 +1662120320295959808 +1662120320340960768 +1662120320379961600 +1662120320424962560 +1662120320469963520 +1662120320511964416 +1662120320556965376 +1662120320601966336 +1662120320646967296 +1662120320688968192 +1662120320727969024 +1662120320769969920 +1662120320814970880 +1662120320862971904 +1662120320904972800 +1662120320946973696 +1662120320988974592 +1662120321033975552 +1662120321075976448 +1662120321120977408 +1662120321162978304 +1662120321210979328 +1662120321255980288 +1662120321306981376 +1662120321348982272 +1662120321393983232 +1662120321438984192 +1662120321477985024 +1662120321522985984 +1662120321561986816 +1662120321603987712 +1662120321651988736 +1662120321693989632 +1662120321732990464 +1662120321780991488 +1662120321822992384 +1662120321858993152 +1662120321900994048 +1662120321942994944 +1662120321987995904 +1662120322026996736 +1662120322068997632 +1662120322110998528 +1662120322149999360 +1662120322195000320 +1662120322237001216 +1662120322285002240 +1662120322330003200 +1662120322372004096 +1662120322417005056 +1662120322459005952 +1662120322501006848 +1662120322543007744 +1662120322585008640 +1662120322624009472 +1662120322666010368 +1662120322708011264 +1662120322750012160 +1662120322789012992 +1662120322828013824 +1662120322882014976 +1662120322924015872 +1662120322975016960 +1662120323014017792 +1662120323056018688 +1662120323101019648 +1662120323146020608 +1662120323185021440 +1662120323227022336 +1662120323272023296 +1662120323317024256 +1662120323359025152 +1662120323401026048 +1662120323443026944 +1662120323488027904 +1662120323530028800 +1662120323575029760 +1662120323620030720 +1662120323668031744 +1662120323710032640 +1662120323749033472 +1662120323794034432 +1662120323836035328 +1662120323875036160 +1662120323920037120 +1662120323959037952 +1662120324004038912 +1662120324046039808 +1662120324091040768 +1662120324139041792 +1662120324178042624 +1662120324223043584 +1662120324265044480 +1662120324304045312 +1662120324343046144 +1662120324385047040 +1662120324427047936 +1662120324469048832 +1662120324517049856 +1662120324559050752 +1662120324601051648 +1662120324640052480 +1662120324682053376 +1662120324724054272 +1662120324766055168 +1662120324808056064 +1662120324853057024 +1662120324901058048 +1662120324943058944 +1662120324988059904 +1662120325036060928 +1662120325078061824 +1662120325120062720 +1662120325159063552 +1662120325204064512 +1662120325255065600 +1662120325300066560 +1662120325342067456 +1662120325384068352 +1662120325429069312 +1662120325468070144 +1662120325510071040 +1662120325549071872 +1662120325603073024 +1662120325642073856 +1662120325687074816 +1662120325726075648 +1662120325768076544 +1662120325810077440 +1662120325852078336 +1662120325894079232 +1662120325939080192 +1662120325984081152 +1662120326026082048 +1662120326074083072 +1662120326119084032 +1662120326164084992 +1662120326209085952 +1662120326257086976 +1662120326302087936 +1662120326344088832 +1662120326386089728 +1662120326428090624 +1662120326470091520 +1662120326512092416 +1662120326554093312 +1662120326596094208 +1662120326638095104 +1662120326683096064 +1662120326725096960 +1662120326767097856 +1662120326809098752 +1662120326857099776 +1662120326902100736 +1662120326947101696 +1662120326995102720 +1662120327040103680 +1662120327088104704 +1662120327133105664 +1662120327175106560 +1662120327220107520 +1662120327268108544 +1662120327310109440 +1662120327355110400 +1662120327394111232 +1662120327436112128 +1662120327490113280 +1662120327532114176 +1662120327574115072 +1662120327619116032 +1662120327661116928 +1662120327706117888 +1662120327748118784 +1662120327793119744 +1662120327832120576 +1662120327874121472 +1662120327919122432 +1662120327964123392 +1662120328009124352 +1662120328054125312 +1662120328099126272 +1662120328144127232 +1662120328189128192 +1662120328231129088 +1662120328273129984 +1662120328312130816 +1662120328354131712 +1662120328396132608 +1662120328441133568 +1662120328486134528 +1662120328531135488 +1662120328573136384 +1662120328612137216 +1662120328660138240 +1662120328705139200 +1662120328747140096 +1662120328795141120 +1662120328837142016 +1662120328879142912 +1662120328921143808 +1662120328963144704 +1662120329005145600 +1662120329047146496 +1662120329089147392 +1662120329137148416 +1662120329182149376 +1662120329227150336 +1662120329272151296 +1662120329317152256 +1662120329362153216 +1662120329410154240 +1662120329455155200 +1662120329497156096 +1662120329536156928 +1662120329581157888 +1662120329623158784 +1662120329668159744 +1662120329713160704 +1662120329758161664 +1662120329800162560 +1662120329842163456 +1662120329884164352 +1662120329926165248 +1662120329971166208 +1662120330010167040 +1662120330052167936 +1662120330100168960 +1662120330145169920 +1662120330190170880 +1662120330235171840 +1662120330277172736 +1662120330316173568 +1662120330364174592 +1662120330406175488 +1662120330448176384 +1662120330487177216 +1662120330526178048 +1662120330571179008 +1662120330613179904 +1662120330658180864 +1662120330703181824 +1662120330748182784 +1662120330793183744 +1662120330838184704 +1662120330877185536 +1662120330928186624 +1662120330967187456 +1662120331006188288 +1662120331051189248 +1662120331090190080 +1662120331132190976 +1662120331174191872 +1662120331219192832 +1662120331261193728 +1662120331306194688 +1662120331354195712 +1662120331393196544 +1662120331435197440 +1662120331477198336 +1662120331513199104 +1662120331561200128 +1662120331609201152 +1662120331648201984 +1662120331690202880 +1662120331735203840 +1662120331780204800 +1662120331825205760 +1662120331864206592 +1662120331906207488 +1662120331951208448 +1662120331996209408 +1662120332038210304 +1662120332080211200 +1662120332125212160 +1662120332164212992 +1662120332206213888 +1662120332251214848 +1662120332293215744 +1662120332335216640 +1662120332374217472 +1662120332416218368 +1662120332458219264 +1662120332500220160 +1662120332545221120 +1662120332584221952 +1662120332629222912 +1662120332674223872 +1662120332719224832 +1662120332761225728 +1662120332806226688 +1662120332848227584 +1662120332890228480 +1662120332932229376 +1662120332974230272 +1662120333019231232 +1662120333064232192 +1662120333106233088 +1662120333154234112 +1662120333199235072 +1662120333238235904 +1662120333286236928 +1662120333328237824 +1662120333367238656 +1662120333409239552 +1662120333448240384 +1662120333490241280 +1662120333529242112 +1662120333571243008 +1662120333610243840 +1662120333649244672 +1662120333691245568 +1662120333736246528 +1662120333781247488 +1662120333826248448 +1662120333868249344 +1662120333913250304 +1662120333958251264 +1662120334003252224 +1662120334048253184 +1662120334090254080 +1662120334132254976 +1662120334171255808 +1662120334213256704 +1662120334258257664 +1662120334303258624 +1662120334348259584 +1662120334393260544 +1662120334438261504 +1662120334480262400 +1662120334525263360 +1662120334570264320 +1662120334612265216 +1662120334657266176 +1662120334702267136 +1662120334744268032 +1662120334795269120 +1662120334837270016 +1662120334882270976 +1662120334918271744 +1662120334960272640 +1662120335002273536 +1662120335047274496 +1662120335095275520 +1662120335137276416 +1662120335185277440 +1662120335230278400 +1662120335272279296 +1662120335314280192 +1662120335362281216 +1662120335404282112 +1662120335449283072 +1662120335485283840 +1662120335530284800 +1662120335572285696 +1662120335614286592 +1662120335656287488 +1662120335701288448 +1662120335746289408 +1662120335788290304 +1662120335833291264 +1662120335878292224 +1662120335923293184 +1662120335962294016 +1662120336010295040 +1662120336052295936 +1662120336088296704 +1662120336127297536 +1662120336172298496 +1662120336214299392 +1662120336250300160 +1662120336292301056 +1662120336334301952 +1662120336376302848 +1662120336427303936 +1662120336475304960 +1662120336517305856 +1662120336562306816 +1662120336601307648 +1662120336637308416 +1662120336679309312 +1662120336724310272 +1662120336763311104 +1662120336799311872 +1662120336838312704 +1662120336883313664 +1662120336922314496 +1662120336970315520 +1662120337015316480 +1662120337057317376 +1662120337102318336 +1662120337141319168 +1662120337186320128 +1662120337231321088 +1662120337276322048 +1662120337324323072 +1662120337369324032 +1662120337414324992 +1662120337459325952 +1662120337504326912 +1662120337546327808 +1662120337591328768 +1662120337636329728 +1662120337675330560 +1662120337711331328 +1662120337756332288 +1662120337801333248 +1662120337843334144 +1662120337882334976 +1662120337924335872 +1662120337969336832 +1662120338014337792 +1662120338059338752 +1662120338104339712 +1662120338146340608 +1662120338191341568 +1662120338233342464 +1662120338275343360 +1662120338323344384 +1662120338368345344 +1662120338416346368 +1662120338461347328 +1662120338503348224 +1662120338548349184 +1662120338590350080 +1662120338632350976 +1662120338674351872 +1662120338713352704 +1662120338752353536 +1662120338797354496 +1662120338842355456 +1662120338890356480 +1662120338932357376 +1662120338974358272 +1662120339016359168 +1662120339055360000 +1662120339100360960 +1662120339145361920 +1662120339190362880 +1662120339241363968 +1662120339286364928 +1662120339334365952 +1662120339382366976 +1662120339427367936 +1662120339466368768 +1662120339502369536 +1662120339544370432 +1662120339586371328 +1662120339625372160 +1662120339667373056 +1662120339706373888 +1662120339748374784 +1662120339793375744 +1662120339832376576 +1662120339874377472 +1662120339916378368 +1662120339958379264 +1662120340000380160 +1662120340042381056 +1662120340084381952 +1662120340126382848 +1662120340171383808 +1662120340216384768 +1662120340258385664 +1662120340306386688 +1662120340351387648 +1662120340393388544 +1662120340432389376 +1662120340480390400 +1662120340522391296 +1662120340564392192 +1662120340609393152 +1662120340651394048 +1662120340696395008 +1662120340738395904 +1662120340780396800 +1662120340825397760 +1662120340873398784 +1662120340912399616 +1662120340957400576 +1662120341002401536 +1662120341044402432 +1662120341089403392 +1662120341131404288 +1662120341176405248 +1662120341215406080 +1662120341263407104 +1662120341305408000 +1662120341344408832 +1662120341383409664 +1662120341428410624 +1662120341470411520 +1662120341512412416 +1662120341560413440 +1662120341605414400 +1662120341650415360 +1662120341692416256 +1662120341734417152 +1662120341773417984 +1662120341815418880 +1662120341857419776 +1662120341899420672 +1662120341938421504 +1662120341980422400 +1662120342025423360 +1662120342067424256 +1662120342112425216 +1662120342160426240 +1662120342202427136 +1662120342244428032 +1662120342286428928 +1662120342328429824 +1662120342373430784 +1662120342418431744 +1662120342466432768 +1662120342514433792 +1662120342556434688 +1662120342595435520 +1662120342637436416 +1662120342676437248 +1662120342718438144 +1662120342760439040 +1662120342799439872 +1662120342838440704 +1662120342877441536 +1662120342925442560 +1662120342964443392 +1662120343009444352 +1662120343048445184 +1662120343090446080 +1662120343135447040 +1662120343177447936 +1662120343222448896 +1662120343264449792 +1662120343309450752 +1662120343351451648 +1662120343402452736 +1662120343447453696 +1662120343489454592 +1662120343534455552 +1662120343579456512 +1662120343618457344 +1662120343663458304 +1662120343711459328 +1662120343762460416 +1662120343801461248 +1662120343849462272 +1662120343891463168 +1662120343936464128 +1662120343978465024 +1662120344023465984 +1662120344062466816 +1662120344107467776 +1662120344146468608 +1662120344188469504 +1662120344230470400 +1662120344275471360 +1662120344314472192 +1662120344356473088 +1662120344401474048 +1662120344443474944 +1662120344491475968 +1662120344533476864 +1662120344581477888 +1662120344620478720 +1662120344665479680 +1662120344713480704 +1662120344758481664 +1662120344800482560 +1662120344842483456 +1662120344884484352 +1662120344926485248 +1662120344968486144 +1662120345010487040 +1662120345055488000 +1662120345100488960 +1662120345145489920 +1662120345187490816 +1662120345229491712 +1662120345268492544 +1662120345310493440 +1662120345358494464 +1662120345397495296 +1662120345439496192 +1662120345484497152 +1662120345526498048 +1662120345568498944 +1662120345613499904 +1662120345655500800 +1662120345697501696 +1662120345736502528 +1662120345781503488 +1662120345826504448 +1662120345874505472 +1662120345919506432 +1662120345961507328 +1662120346006508288 +1662120346051509248 +1662120346096510208 +1662120346138511104 +1662120346180512000 +1662120346219512832 +1662120346264513792 +1662120346309514752 +1662120346354515712 +1662120346399516672 +1662120346441517568 +1662120346486518528 +1662120346528519424 +1662120346573520384 +1662120346618521344 +1662120346660522240 +1662120346702523136 +1662120346744524032 +1662120346786524928 +1662120346828525824 +1662120346876526848 +1662120346915527680 +1662120346957528576 +1662120347005529600 +1662120347047530496 +1662120347086531328 +1662120347128532224 +1662120347170533120 +1662120347212534016 +1662120347257534976 +1662120347299535872 +1662120347344536832 +1662120347389537792 +1662120347431538688 +1662120347476539648 +1662120347518540544 +1662120347560541440 +1662120347608542464 +1662120347653543424 +1662120347695544320 +1662120347737545216 +1662120347779546112 +1662120347824547072 +1662120347863547904 +1662120347905548800 +1662120347947549696 +1662120347986550528 +1662120348031551488 +1662120348073552384 +1662120348118553344 +1662120348157554176 +1662120348202555136 +1662120348244556032 +1662120348289556992 +1662120348331557888 +1662120348376558848 +1662120348421559808 +1662120348460560640 +1662120348502561536 +1662120348544562432 +1662120348589563392 +1662120348637564416 +1662120348679565312 +1662120348718566144 +1662120348760567040 +1662120348802567936 +1662120348841568768 +1662120348880569600 +1662120348922570496 +1662120348964571392 +1662120349009572352 +1662120349057573376 +1662120349102574336 +1662120349144575232 +1662120349186576128 +1662120349231577088 +1662120349273577984 +1662120349318578944 +1662120349363579904 +1662120349402580736 +1662120349444581632 +1662120349489582592 +1662120349531583488 +1662120349573584384 +1662120349612585216 +1662120349651586048 +1662120349696587008 +1662120349738587904 +1662120349780588800 +1662120349822589696 +1662120349864590592 +1662120349906591488 +1662120349948592384 +1662120349990593280 +1662120350032594176 +1662120350077595136 +1662120350122596096 +1662120350164596992 +1662120350209597952 +1662120350251598848 +1662120350293599744 +1662120350338600704 +1662120350380601600 +1662120350425602560 +1662120350467603456 +1662120350509604352 +1662120350551605248 +1662120350596606208 +1662120350638607104 +1662120350683608064 +1662120350728609024 +1662120350770609920 +1662120350812610816 +1662120350857611776 +1662120350902612736 +1662120350944613632 +1662120350986614528 +1662120351028615424 +1662120351067616256 +1662120351109617152 +1662120351151618048 +1662120351193618944 +1662120351235619840 +1662120351280620800 +1662120351325621760 +1662120351367622656 +1662120351409623552 +1662120351451624448 +1662120351496625408 +1662120351547626496 +1662120351589627392 +1662120351637628416 +1662120351679629312 +1662120351721630208 +1662120351766631168 +1662120351811632128 +1662120351856633088 +1662120351898633984 +1662120351940634880 +1662120351985635840 +1662120352027636736 +1662120352069637632 +1662120352111638528 +1662120352153639424 +1662120352195640320 +1662120352240641280 +1662120352285642240 +1662120352324643072 +1662120352366643968 +1662120352408644864 +1662120352447645696 +1662120352489646592 +1662120352534647552 +1662120352573648384 +1662120352621649408 +1662120352663650304 +1662120352705651200 +1662120352750652160 +1662120352795653120 +1662120352837654016 +1662120352882654976 +1662120352924655872 +1662120352972656896 +1662120353011657728 +1662120353053658624 +1662120353098659584 +1662120353143660544 +1662120353185661440 +1662120353227662336 +1662120353272663296 +1662120353320664320 +1662120353365665280 +1662120353410666240 +1662120353452667136 +1662120353494668032 +1662120353539668992 +1662120353581669888 +1662120353632670976 +1662120353683672064 +1662120353725672960 +1662120353767673856 +1662120353812674816 +1662120353854675712 +1662120353902676736 +1662120353947677696 +1662120353992678656 +1662120354037679616 +1662120354079680512 +1662120354121681408 +1662120354166682368 +1662120354208683264 +1662120354250684160 +1662120354292685056 +1662120354334685952 +1662120354376686848 +1662120354418687744 +1662120354463688704 +1662120354505689600 +1662120354547690496 +1662120354592691456 +1662120354637692416 +1662120354682693376 +1662120354727694336 +1662120354775695360 +1662120354817696256 +1662120354859697152 +1662120354901698048 +1662120354940698880 +1662120354982699776 +1662120355024700672 +1662120355066701568 +1662120355114702592 +1662120355162703616 +1662120355210704640 +1662120355249705472 +1662120355297706496 +1662120355336707328 +1662120355378708224 +1662120355420709120 +1662120355459709952 +1662120355504710912 +1662120355555712000 +1662120355600712960 +1662120355648713984 +1662120355690714880 +1662120355732715776 +1662120355777716736 +1662120355819717632 +1662120355861718528 +1662120355903719424 +1662120355945720320 +1662120355987721216 +1662120356029722112 +1662120356077723136 +1662120356122724096 +1662120356161724928 +1662120356203725824 +1662120356245726720 +1662120356290727680 +1662120356338728704 +1662120356383729664 +1662120356428730624 +1662120356470731520 +1662120356518732544 +1662120356560733440 +1662120356605734400 +1662120356647735296 +1662120356689736192 +1662120356731737088 +1662120356773737984 +1662120356815738880 +1662120356857739776 +1662120356896740608 +1662120356944741632 +1662120356986742528 +1662120357025743360 +1662120357070744320 +1662120357109745152 +1662120357154746112 +1662120357196747008 +1662120357241747968 +1662120357277748736 +1662120357319749632 +1662120357361750528 +1662120357406751488 +1662120357454752512 +1662120357499753472 +1662120357541754368 +1662120357586755328 +1662120357625756160 +1662120357664756992 +1662120357712758016 +1662120357754758912 +1662120357793759744 +1662120357835760640 +1662120357880761600 +1662120357925762560 +1662120357973763584 +1662120358015764480 +1662120358060765440 +1662120358102766336 +1662120358147767296 +1662120358195768320 +1662120358237769216 +1662120358285770240 +1662120358327771136 +1662120358375772160 +1662120358417773056 +1662120358459773952 +1662120358501774848 +1662120358543775744 +1662120358591776768 +1662120358636777728 +1662120358678778624 +1662120358726779648 +1662120358771780608 +1662120358813781504 +1662120358852782336 +1662120358894783232 +1662120358933784064 +1662120358975784960 +1662120359020785920 +1662120359065786880 +1662120359107787776 +1662120359158788864 +1662120359200789760 +1662120359242790656 +1662120359284791552 +1662120359326792448 +1662120359368793344 +1662120359407794176 +1662120359452795136 +1662120359494796032 +1662120359539796992 +1662120359581797888 +1662120359623798784 +1662120359671799808 +1662120359713800704 +1662120359755801600 +1662120359803802624 +1662120359845803520 +1662120359887804416 +1662120359926805248 +1662120359971806208 +1662120360013807104 +1662120360064808192 +1662120360106809088 +1662120360148809984 +1662120360190810880 +1662120360232811776 +1662120360274812672 +1662120360316813568 +1662120360361814528 +1662120360403815424 +1662120360445816320 +1662120360487817216 +1662120360529818112 +1662120360571819008 +1662120360613819904 +1662120360658820864 +1662120360703821824 +1662120360748822784 +1662120360787823616 +1662120360829824512 +1662120360877825536 +1662120360919826432 +1662120360964827392 +1662120361009828352 +1662120361054829312 +1662120361105830400 +1662120361150831360 +1662120361189832192 +1662120361231833088 +1662120361276834048 +1662120361318834944 +1662120361360835840 +1662120361408836864 +1662120361450837760 +1662120361489838592 +1662120361531839488 +1662120361573840384 +1662120361615841280 +1662120361660842240 +1662120361702843136 +1662120361747844096 +1662120361786844928 +1662120361831845888 +1662120361876846848 +1662120361918847744 +1662120361963848704 +1662120362008849664 +1662120362053850624 +1662120362092851456 +1662120362137852416 +1662120362179853312 +1662120362224854272 +1662120362266855168 +1662120362308856064 +1662120362347856896 +1662120362389857792 +1662120362428858624 +1662120362470859520 +1662120362515860480 +1662120362554861312 +1662120362596862208 +1662120362641863168 +1662120362680864000 +1662120362725864960 +1662120362767865856 +1662120362815866880 +1662120362857867776 +1662120362905868800 +1662120362947869696 +1662120362995870720 +1662120363037871616 +1662120363082872576 +1662120363124873472 +1662120363166874368 +1662120363208875264 +1662120363247876096 +1662120363289876992 +1662120363331877888 +1662120363373878784 +1662120363415879680 +1662120363454880512 +1662120363499881472 +1662120363544882432 +1662120363589883392 +1662120363634884352 +1662120363676885248 +1662120363718886144 +1662120363760887040 +1662120363802887936 +1662120363847888896 +1662120363886889728 +1662120363928890624 +1662120363973891584 +1662120364018892544 +1662120364060893440 +1662120364102894336 +1662120364147895296 +1662120364192896256 +1662120364231897088 +1662120364273897984 +1662120364315898880 +1662120364360899840 +1662120364405900800 +1662120364447901696 +1662120364489902592 +1662120364531903488 +1662120364573904384 +1662120364618905344 +1662120364666906368 +1662120364708907264 +1662120364756908288 +1662120364798909184 +1662120364843910144 +1662120364888911104 +1662120364930912000 +1662120364975912960 +1662120365020913920 +1662120365065914880 +1662120365110915840 +1662120365158916864 +1662120365200917760 +1662120365242918656 +1662120365284919552 +1662120365323920384 +1662120365365921280 +1662120365407922176 +1662120365449923072 +1662120365488923904 +1662120365527924736 +1662120365566925568 +1662120365611926528 +1662120365653927424 +1662120365698928384 +1662120365743929344 +1662120365788930304 +1662120365830931200 +1662120365872932096 +1662120365917933056 +1662120365959933952 +1662120365998934784 +1662120366040935680 +1662120366082936576 +1662120366124937472 +1662120366166938368 +1662120366211939328 +1662120366253940224 +1662120366301941248 +1662120366343942144 +1662120366397943296 +1662120366442944256 +1662120366484945152 +1662120366529946112 +1662120366574947072 +1662120366619948032 +1662120366661948928 +1662120366706949888 +1662120366748950784 +1662120366790951680 +1662120366835952640 +1662120366874953472 +1662120366916954368 +1662120366955955200 +1662120366994956032 +1662120367039956992 +1662120367081957888 +1662120367126958848 +1662120367168959744 +1662120367210960640 +1662120367249961472 +1662120367294962432 +1662120367336963328 +1662120367375964160 +1662120367420965120 +1662120367465966080 +1662120367507966976 +1662120367546967808 +1662120367591968768 +1662120367636969728 +1662120367675970560 +1662120367714971392 +1662120367759972352 +1662120367801973248 +1662120367846974208 +1662120367888975104 +1662120367933976064 +1662120367975976960 +1662120368020977920 +1662120368065978880 +1662120368110979840 +1662120368152980736 +1662120368194981632 +1662120368236982528 +1662120368275983360 +1662120368320984320 +1662120368359985152 +1662120368404986112 +1662120368446987008 +1662120368485987840 +1662120368530988800 +1662120368575989760 +1662120368617990656 +1662120368662991616 +1662120368704992512 +1662120368746993408 +1662120368791994368 +1662120368833995264 +1662120368875996160 +1662120368920997120 +1662120368965998080 +1662120369010999040 +1662120369056000000 +1662120369101000960 +1662120369146001920 +1662120369188002816 +1662120369230003712 +1662120369272004608 +1662120369317005568 +1662120369359006464 +1662120369404007424 +1662120369449008384 +1662120369500009472 +1662120369542010368 +1662120369584011264 +1662120369623012096 +1662120369665012992 +1662120369704013824 +1662120369749014784 +1662120369794015744 +1662120369836016640 +1662120369878017536 +1662120369923018496 +1662120369965019392 +1662120370007020288 +1662120370046021120 +1662120370088022016 +1662120370130022912 +1662120370175023872 +1662120370217024768 +1662120370259025664 +1662120370298026496 +1662120370340027392 +1662120370385028352 +1662120370427029248 +1662120370469030144 +1662120370511031040 +1662120370556032000 +1662120370604033024 +1662120370652034048 +1662120370697035008 +1662120370739035904 +1662120370781036800 +1662120370826037760 +1662120370877038848 +1662120370919039744 +1662120370961040640 +1662120371000041472 +1662120371045042432 +1662120371087043328 +1662120371126044160 +1662120371162044928 +1662120371207045888 +1662120371252046848 +1662120371294047744 +1662120371336048640 +1662120371381049600 +1662120371423050496 +1662120371468051456 +1662120371510052352 +1662120371552053248 +1662120371597054208 +1662120371642055168 +1662120371690056192 +1662120371735057152 +1662120371786058240 +1662120371828059136 +1662120371867059968 +1662120371912060928 +1662120371960061952 +1662120372005062912 +1662120372053063936 +1662120372098064896 +1662120372143065856 +1662120372185066752 +1662120372227067648 +1662120372272068608 +1662120372317069568 +1662120372362070528 +1662120372407071488 +1662120372452072448 +1662120372494073344 +1662120372536074240 +1662120372578075136 +1662120372623076096 +1662120372668077056 +1662120372713078016 +1662120372755078912 +1662120372800079872 +1662120372839080704 +1662120372881081600 +1662120372923082496 +1662120372968083456 +1662120373016084480 +1662120373055085312 +1662120373097086208 +1662120373139087104 +1662120373178087936 +1662120373220088832 +1662120373262089728 +1662120373307090688 +1662120373355091712 +1662120373394092544 +1662120373436093440 +1662120373481094400 +1662120373523095296 +1662120373565096192 +1662120373604097024 +1662120373652098048 +1662120373697099008 +1662120373748100096 +1662120373790100992 +1662120373832101888 +1662120373874102784 +1662120373919103744 +1662120373961104640 +1662120374000105472 +1662120374045106432 +1662120374090107392 +1662120374138108416 +1662120374183109376 +1662120374225110272 +1662120374270111232 +1662120374312112128 +1662120374354113024 +1662120374396113920 +1662120374438114816 +1662120374480115712 +1662120374525116672 +1662120374564117504 +1662120374609118464 +1662120374651119360 +1662120374699120384 +1662120374741121280 +1662120374786122240 +1662120374831123200 +1662120374873124096 +1662120374918125056 +1662120374966126080 +1662120375008126976 +1662120375056128000 +1662120375101128960 +1662120375146129920 +1662120375188130816 +1662120375236131840 +1662120375278132736 +1662120375323133696 +1662120375365134592 +1662120375413135616 +1662120375455136512 +1662120375497137408 +1662120375539138304 +1662120375581139200 +1662120375626140160 +1662120375668141056 +1662120375707141888 +1662120375752142848 +1662120375794143744 +1662120375839144704 +1662120375884145664 +1662120375929146624 +1662120375968147456 +1662120376010148352 +1662120376052149248 +1662120376094150144 +1662120376136151040 +1662120376175151872 +1662120376226152960 +1662120376268153856 +1662120376310154752 +1662120376355155712 +1662120376394156544 +1662120376436157440 +1662120376481158400 +1662120376523159296 +1662120376562160128 +1662120376604161024 +1662120376646161920 +1662120376688162816 +1662120376730163712 +1662120376775164672 +1662120376817165568 +1662120376859166464 +1662120376907167488 +1662120376952168448 +1662120376991169280 +1662120377036170240 +1662120377081171200 +1662120377123172096 +1662120377165172992 +1662120377204173824 +1662120377246174720 +1662120377288175616 +1662120377330176512 +1662120377372177408 +1662120377414178304 +1662120377456179200 +1662120377495180032 +1662120377537180928 +1662120377579181824 +1662120377621182720 +1662120377666183680 +1662120377711184640 +1662120377759185664 +1662120377801186560 +1662120377843187456 +1662120377882188288 +1662120377927189248 +1662120377966190080 +1662120378011191040 +1662120378053191936 +1662120378098192896 +1662120378140193792 +1662120378185194752 +1662120378224195584 +1662120378266196480 +1662120378308197376 +1662120378350198272 +1662120378392199168 +1662120378440200192 +1662120378482201088 +1662120378527202048 +1662120378569202944 +1662120378611203840 +1662120378656204800 +1662120378701205760 +1662120378746206720 +1662120378791207680 +1662120378833208576 +1662120378875209472 +1662120378917210368 +1662120378959211264 +1662120378998212096 +1662120379040212992 +1662120379082213888 +1662120379121214720 +1662120379160215552 +1662120379202216448 +1662120379247217408 +1662120379289218304 +1662120379331219200 +1662120379373220096 +1662120379418221056 +1662120379460221952 +1662120379505222912 +1662120379547223808 +1662120379604225024 +1662120379652226048 +1662120379691226880 +1662120379733227776 +1662120379775228672 +1662120379820229632 +1662120379868230656 +1662120379913231616 +1662120379955232512 +1662120379997233408 +1662120380042234368 +1662120380078235136 +1662120380123236096 +1662120380165236992 +1662120380216238080 +1662120380258238976 +1662120380300239872 +1662120380339240704 +1662120380384241664 +1662120380426242560 +1662120380468243456 +1662120380513244416 +1662120380564245504 +1662120380609246464 +1662120380654247424 +1662120380693248256 +1662120380735249152 +1662120380777250048 +1662120380816250880 +1662120380858251776 +1662120380906252800 +1662120380954253824 +1662120380999254784 +1662120381041255680 +1662120381083256576 +1662120381128257536 +1662120381170258432 +1662120381212259328 +1662120381251260160 +1662120381293261056 +1662120381335261952 +1662120381377262848 +1662120381428263936 +1662120381473264896 +1662120381512265728 +1662120381557266688 +1662120381599267584 +1662120381641268480 +1662120381686269440 +1662120381734270464 +1662120381776271360 +1662120381815272192 +1662120381857273088 +1662120381902274048 +1662120381950275072 +1662120381995276032 +1662120382037276928 +1662120382082277888 +1662120382127278848 +1662120382169279744 +1662120382214280704 +1662120382256281600 +1662120382301282560 +1662120382343283456 +1662120382385284352 +1662120382424285184 +1662120382463286016 +1662120382508286976 +1662120382547287808 +1662120382589288704 +1662120382631289600 +1662120382676290560 +1662120382721291520 +1662120382763292416 +1662120382808293376 +1662120382850294272 +1662120382898295296 +1662120382937296128 +1662120382976296960 +1662120383018297856 +1662120383063298816 +1662120383105299712 +1662120383147300608 +1662120383192301568 +1662120383234302464 +1662120383279303424 +1662120383321304320 +1662120383366305280 +1662120383417306368 +1662120383462307328 +1662120383504308224 +1662120383552309248 +1662120383594310144 +1662120383636311040 +1662120383678311936 +1662120383720312832 +1662120383768313856 +1662120383813314816 +1662120383858315776 +1662120383903316736 +1662120383945317632 +1662120383987318528 +1662120384032319488 +1662120384071320320 +1662120384113321216 +1662120384155322112 +1662120384200323072 +1662120384242323968 +1662120384287324928 +1662120384329325824 +1662120384371326720 +1662120384413327616 +1662120384455328512 +1662120384500329472 +1662120384542330368 +1662120384587331328 +1662120384632332288 +1662120384674333184 +1662120384719334144 +1662120384761335040 +1662120384803335936 +1662120384845336832 +1662120384890337792 +1662120384935338752 +1662120384974339584 +1662120385025340672 +1662120385070341632 +1662120385112342528 +1662120385160343552 +1662120385202344448 +1662120385241345280 +1662120385283346176 +1662120385325347072 +1662120385370348032 +1662120385418349056 +1662120385463350016 +1662120385514351104 +1662120385556352000 +1662120385598352896 +1662120385637353728 +1662120385679354624 +1662120385721355520 +1662120385766356480 +1662120385805357312 +1662120385847358208 +1662120385889359104 +1662120385934360064 +1662120385976360960 +1662120386021361920 +1662120386066362880 +1662120386108363776 +1662120386147364608 +1662120386186365440 +1662120386231366400 +1662120386270367232 +1662120386315368192 +1662120386360369152 +1662120386405370112 +1662120386447371008 +1662120386486371840 +1662120386531372800 +1662120386576373760 +1662120386615374592 +1662120386660375552 +1662120386699376384 +1662120386738377216 +1662120386783378176 +1662120386822379008 +1662120386870380032 +1662120386912380928 +1662120386951381760 +1662120386993382656 +1662120387032383488 +1662120387083384576 +1662120387122385408 +1662120387164386304 +1662120387206387200 +1662120387248388096 +1662120387293389056 +1662120387335389952 +1662120387371390720 +1662120387416391680 +1662120387461392640 +1662120387503393536 +1662120387548394496 +1662120387590395392 +1662120387629396224 +1662120387668397056 +1662120387713398016 +1662120387755398912 +1662120387800399872 +1662120387842400768 +1662120387887401728 +1662120387929402624 +1662120387971403520 +1662120388016404480 +1662120388055405312 +1662120388097406208 +1662120388142407168 +1662120388184408064 +1662120388223408896 +1662120388265409792 +1662120388304410624 +1662120388346411520 +1662120388388412416 +1662120388430413312 +1662120388472414208 +1662120388520415232 +1662120388565416192 +1662120388607417088 +1662120388649417984 +1662120388688418816 +1662120388733419776 +1662120388778420736 +1662120388823421696 +1662120388862422528 +1662120388904423424 +1662120388946424320 +1662120388991425280 +1662120389036426240 +1662120389078427136 +1662120389123428096 +1662120389165428992 +1662120389204429824 +1662120389252430848 +1662120389291431680 +1662120389333432576 +1662120389375433472 +1662120389414434304 +1662120389456435200 +1662120389498436096 +1662120389540436992 +1662120389585437952 +1662120389627438848 +1662120389669439744 +1662120389711440640 +1662120389756441600 +1662120389798442496 +1662120389846443520 +1662120389888444416 +1662120389933445376 +1662120389972446208 +1662120390014447104 +1662120390056448000 +1662120390101448960 +1662120390143449856 +1662120390185450752 +1662120390233451776 +1662120390278452736 +1662120390323453696 +1662120390365454592 +1662120390410455552 +1662120390455456512 +1662120390497457408 +1662120390533458176 +1662120390575459072 +1662120390617459968 +1662120390659460864 +1662120390704461824 +1662120390749462784 +1662120390791463680 +1662120390836464640 +1662120390878465536 +1662120390923466496 +1662120390974467584 +1662120391013468416 +1662120391055469312 +1662120391097470208 +1662120391145471232 +1662120391187472128 +1662120391229473024 +1662120391271473920 +1662120391319474944 +1662120391358475776 +1662120391403476736 +1662120391445477632 +1662120391487478528 +1662120391529479424 +1662120391571480320 +1662120391613481216 +1662120391655482112 +1662120391700483072 +1662120391739483904 +1662120391784484864 +1662120391835485952 +1662120391883486976 +1662120391925487872 +1662120391967488768 +1662120392012489728 +1662120392057490688 +1662120392099491584 +1662120392144492544 +1662120392186493440 +1662120392231494400 +1662120392273495296 +1662120392312496128 +1662120392357497088 +1662120392399497984 +1662120392444498944 +1662120392492499968 +1662120392543501056 +1662120392585501952 +1662120392630502912 +1662120392669503744 +1662120392711504640 +1662120392753505536 +1662120392801506560 +1662120392846507520 +1662120392891508480 +1662120392933509376 +1662120392981510400 +1662120393026511360 +1662120393068512256 +1662120393113513216 +1662120393158514176 +1662120393200515072 diff --git a/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_track0.txt b/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_track0.txt new file mode 100644 index 0000000000..d40335079d --- /dev/null +++ b/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_track0.txt @@ -0,0 +1,2847 @@ +1661868173547958016 +1661868173589958912 +1661868173628959744 +1661868173676960768 +1661868173715961600 +1661868173760962560 +1661868173802963456 +1661868173844964352 +1661868173886965248 +1661868173931966208 +1661868173973967104 +1661868174021968128 +1661868174063969024 +1661868174105969920 +1661868174147970816 +1661868174183971584 +1661868174225972480 +1661868174264973312 +1661868174306974208 +1661868174354975232 +1661868174399976192 +1661868174441977088 +1661868174483977984 +1661868174525978880 +1661868174564979712 +1661868174603980544 +1661868174645981440 +1661868174693982464 +1661868174735983360 +1661868174780984320 +1661868174828985344 +1661868174870986240 +1661868174912987136 +1661868174960988160 +1661868175002989056 +1661868175044989952 +1661868175086990848 +1661868175128991744 +1661868175170992640 +1661868175209993472 +1661868175251994368 +1661868175302995456 +1661868175341996288 +1661868175383997184 +1661868175425998080 +1661868175470999040 +1661868175509999872 +1661868175549000704 +1661868175591001600 +1661868175639002624 +1661868175681003520 +1661868175723004416 +1661868175765005312 +1661868175810006272 +1661868175849007104 +1661868175897008128 +1661868175939009024 +1661868175981009920 +1661868176029010944 +1661868176071011840 +1661868176113012736 +1661868176152013568 +1661868176197014528 +1661868176242015488 +1661868176284016384 +1661868176323017216 +1661868176368018176 +1661868176410019072 +1661868176452019968 +1661868176497020928 +1661868176536021760 +1661868176578022656 +1661868176617023488 +1661868176659024384 +1661868176701025280 +1661868176743026176 +1661868176785027072 +1661868176824027904 +1661868176869028864 +1661868176914029824 +1661868176953030656 +1661868176992031488 +1661868177034032384 +1661868177076033280 +1661868177118034176 +1661868177163035136 +1661868177208036096 +1661868177244036864 +1661868177283037696 +1661868177325038592 +1661868177367039488 +1661868177409040384 +1661868177451041280 +1661868177493042176 +1661868177535043072 +1661868177580044032 +1661868177625044992 +1661868177670045952 +1661868177712046848 +1661868177748047616 +1661868177793048576 +1661868177838049536 +1661868177877050368 +1661868177916051200 +1661868177958052096 +1661868178003053056 +1661868178048054016 +1661868178090054912 +1661868178132055808 +1661868178171056640 +1661868178207057408 +1661868178249058304 +1661868178297059328 +1661868178339060224 +1661868178384061184 +1661868178426062080 +1661868178468062976 +1661868178510063872 +1661868178546064640 +1661868178588065536 +1661868178630066432 +1661868178669067264 +1661868178711068160 +1661868178759069184 +1661868178804070144 +1661868178846071040 +1661868178888071936 +1661868178930072832 +1661868178972073728 +1661868179014074624 +1661868179059075584 +1661868179107076608 +1661868179152077568 +1661868179191078400 +1661868179233079296 +1661868179278080256 +1661868179320081152 +1661868179362082048 +1661868179407083008 +1661868179452083968 +1661868179494084864 +1661868179539085824 +1661868179581086720 +1661868179623087616 +1661868179665088512 +1661868179713089536 +1661868179758090496 +1661868179803091456 +1661868179845092352 +1661868179887093248 +1661868179926094080 +1661868179968094976 +1661868180010095872 +1661868180049096704 +1661868180088097536 +1661868180130098432 +1661868180175099392 +1661868180217100288 +1661868180256101120 +1661868180298102016 +1661868180340102912 +1661868180385103872 +1661868180427104768 +1661868180466105600 +1661868180508106496 +1661868180550107392 +1661868180589108224 +1661868180628109056 +1661868180670109952 +1661868180715110912 +1661868180760111872 +1661868180802112768 +1661868180844113664 +1661868180886114560 +1661868180922115328 +1661868180967116288 +1661868181009117184 +1661868181051118080 +1661868181090118912 +1661868181132119808 +1661868181174120704 +1661868181216121600 +1661868181258122496 +1661868181303123456 +1661868181348124416 +1661868181387125248 +1661868181432126208 +1661868181474127104 +1661868181516128000 +1661868181558128896 +1661868181597129728 +1661868181636130560 +1661868181678131456 +1661868181720132352 +1661868181762133248 +1661868181804134144 +1661868181846135040 +1661868181885135872 +1661868181927136768 +1661868181966137600 +1661868182008138496 +1661868182050139392 +1661868182095140352 +1661868182140141312 +1661868182182142208 +1661868182221143040 +1661868182263143936 +1661868182302144768 +1661868182344145664 +1661868182386146560 +1661868182428147456 +1661868182464148224 +1661868182506149120 +1661868182551150080 +1661868182590150912 +1661868182635151872 +1661868182677152768 +1661868182716153600 +1661868182758154496 +1661868182800155392 +1661868182839156224 +1661868182884157184 +1661868182926158080 +1661868182971159040 +1661868183010159872 +1661868183049160704 +1661868183091161600 +1661868183130162432 +1661868183172163328 +1661868183214164224 +1661868183256165120 +1661868183298166016 +1661868183340166912 +1661868183382167808 +1661868183427168768 +1661868183469169664 +1661868183511170560 +1661868183550171392 +1661868183595172352 +1661868183637173248 +1661868183679174144 +1661868183718174976 +1661868183769176064 +1661868183811176960 +1661868183850177792 +1661868183892178688 +1661868183931179520 +1661868183973180416 +1661868184018181376 +1661868184060182272 +1661868184102183168 +1661868184147184128 +1661868184192185088 +1661868184240186112 +1661868184282187008 +1661868184324187904 +1661868184366188800 +1661868184411189760 +1661868184447190528 +1661868184486191360 +1661868184528192256 +1661868184573193216 +1661868184618194176 +1661868184660195072 +1661868184705196032 +1661868184747196928 +1661868184786197760 +1661868184831198720 +1661868184873199616 +1661868184921200640 +1661868184960201472 +1661868185005202432 +1661868185047203328 +1661868185086204160 +1661868185125204992 +1661868185170205952 +1661868185215206912 +1661868185257207808 +1661868185299208704 +1661868185341209600 +1661868185383210496 +1661868185422211328 +1661868185464212224 +1661868185506213120 +1661868185545213952 +1661868185590214912 +1661868185632215808 +1661868185671216640 +1661868185707217408 +1661868185752218368 +1661868185794219264 +1661868185839220224 +1661868185875220992 +1661868185914221824 +1661868185962222848 +1661868186004223744 +1661868186046224640 +1661868186091225600 +1661868186130226432 +1661868186175227392 +1661868186220228352 +1661868186262229248 +1661868186307230208 +1661868186349231104 +1661868186391232000 +1661868186433232896 +1661868186478233856 +1661868186520234752 +1661868186562235648 +1661868186601236480 +1661868186643237376 +1661868186679238144 +1661868186718238976 +1661868186760239872 +1661868186805240832 +1661868186844241664 +1661868186883242496 +1661868186925243392 +1661868186964244224 +1661868187006245120 +1661868187048246016 +1661868187090246912 +1661868187129247744 +1661868187174248704 +1661868187216249600 +1661868187255250432 +1661868187297251328 +1661868187339252224 +1661868187381253120 +1661868187423254016 +1661868187465254912 +1661868187507255808 +1661868187549256704 +1661868187597257728 +1661868187639258624 +1661868187681259520 +1661868187726260480 +1661868187768261376 +1661868187807262208 +1661868187846263040 +1661868187888263936 +1661868187930264832 +1661868187978265856 +1661868188020266752 +1661868188062267648 +1661868188101268480 +1661868188143269376 +1661868188185270272 +1661868188224271104 +1661868188263271936 +1661868188302272768 +1661868188341273600 +1661868188380274432 +1661868188419275264 +1661868188464276224 +1661868188509277184 +1661868188551278080 +1661868188596279040 +1661868188641280000 +1661868188686280960 +1661868188728281856 +1661868188776282880 +1661868188824283904 +1661868188869284864 +1661868188911285760 +1661868188950286592 +1661868188992287488 +1661868189034288384 +1661868189079289344 +1661868189121290240 +1661868189163291136 +1661868189205292032 +1661868189247292928 +1661868189292293888 +1661868189328294656 +1661868189370295552 +1661868189412296448 +1661868189457297408 +1661868189502298368 +1661868189541299200 +1661868189580300032 +1661868189616300800 +1661868189661301760 +1661868189703302656 +1661868189742303488 +1661868189784304384 +1661868189832305408 +1661868189871306240 +1661868189913307136 +1661868189949307904 +1661868189988308736 +1661868190030309632 +1661868190072310528 +1661868190114311424 +1661868190156312320 +1661868190195313152 +1661868190237314048 +1661868190276314880 +1661868190321315840 +1661868190363316736 +1661868190405317632 +1661868190441318400 +1661868190486319360 +1661868190528320256 +1661868190570321152 +1661868190609321984 +1661868190654322944 +1661868190699323904 +1661868190741324800 +1661868190780325632 +1661868190822326528 +1661868190864327424 +1661868190906328320 +1661868190945329152 +1661868190990330112 +1661868191041331200 +1661868191086332160 +1661868191128333056 +1661868191170333952 +1661868191212334848 +1661868191254335744 +1661868191296336640 +1661868191338337536 +1661868191377338368 +1661868191425339392 +1661868191464340224 +1661868191509341184 +1661868191554342144 +1661868191596343040 +1661868191638343936 +1661868191683344896 +1661868191722345728 +1661868191776346880 +1661868191818347776 +1661868191857348608 +1661868191902349568 +1661868191941350400 +1661868191983351296 +1661868192028352256 +1661868192070353152 +1661868192112354048 +1661868192151354880 +1661868192193355776 +1661868192235356672 +1661868192277357568 +1661868192319358464 +1661868192361359360 +1661868192400360192 +1661868192442361088 +1661868192484361984 +1661868192526362880 +1661868192568363776 +1661868192613364736 +1661868192655365632 +1661868192700366592 +1661868192739367424 +1661868192781368320 +1661868192823369216 +1661868192862370048 +1661868192907371008 +1661868192946371840 +1661868192988372736 +1661868193027373568 +1661868193066374400 +1661868193105375232 +1661868193147376128 +1661868193192377088 +1661868193234377984 +1661868193276378880 +1661868193318379776 +1661868193354380544 +1661868193396381440 +1661868193441382400 +1661868193489383424 +1661868193531384320 +1661868193570385152 +1661868193609385984 +1661868193651386880 +1661868193693387776 +1661868193735388672 +1661868193789389824 +1661868193828390656 +1661868193870391552 +1661868193909392384 +1661868193951393280 +1661868193993394176 +1661868194038395136 +1661868194074395904 +1661868194119396864 +1661868194161397760 +1661868194203398656 +1661868194245399552 +1661868194287400448 +1661868194329401344 +1661868194371402240 +1661868194413403136 +1661868194455404032 +1661868194497404928 +1661868194539405824 +1661868194581406720 +1661868194620407552 +1661868194662408448 +1661868194707409408 +1661868194752410368 +1661868194791411200 +1661868194830412032 +1661868194869412864 +1661868194914413824 +1661868194956414720 +1661868194998415616 +1661868195040416512 +1661868195079417344 +1661868195121418240 +1661868195163419136 +1661868195205420032 +1661868195244420864 +1661868195286421760 +1661868195331422720 +1661868195376423680 +1661868195418424576 +1661868195460425472 +1661868195508426496 +1661868195550427392 +1661868195592428288 +1661868195640429312 +1661868195682430208 +1661868195724431104 +1661868195769432064 +1661868195811432960 +1661868195853433856 +1661868195895434752 +1661868195931435520 +1661868195973436416 +1661868196015437312 +1661868196060438272 +1661868196102439168 +1661868196147440128 +1661868196195441152 +1661868196237442048 +1661868196285443072 +1661868196330444032 +1661868196375444992 +1661868196414445824 +1661868196453446656 +1661868196495447552 +1661868196537448448 +1661868196579449344 +1661868196624450304 +1661868196666451200 +1661868196711452160 +1661868196747452928 +1661868196789453824 +1661868196831454720 +1661868196873455616 +1661868196921456640 +1661868196969457664 +1661868197020458752 +1661868197059459584 +1661868197098460416 +1661868197140461312 +1661868197182462208 +1661868197221463040 +1661868197263463936 +1661868197302464768 +1661868197344465664 +1661868197386466560 +1661868197428467456 +1661868197470468352 +1661868197509469184 +1661868197554470144 +1661868197593470976 +1661868197635471872 +1661868197677472768 +1661868197716473600 +1661868197758474496 +1661868197800475392 +1661868197848476416 +1661868197890477312 +1661868197932478208 +1661868197971479040 +1661868198010479872 +1661868198052480768 +1661868198100481792 +1661868198139482624 +1661868198181483520 +1661868198220484352 +1661868198262485248 +1661868198304486144 +1661868198349487104 +1661868198394488064 +1661868198439489024 +1661868198481489920 +1661868198523490816 +1661868198559491584 +1661868198604492544 +1661868198646493440 +1661868198685494272 +1661868198730495232 +1661868198775496192 +1661868198817497088 +1661868198862498048 +1661868198904498944 +1661868198946499840 +1661868198988500736 +1661868199030501632 +1661868199072502528 +1661868199114503424 +1661868199156504320 +1661868199198505216 +1661868199243506176 +1661868199285507072 +1661868199333508096 +1661868199375508992 +1661868199420509952 +1661868199462510848 +1661868199504511744 +1661868199546512640 +1661868199588513536 +1661868199630514432 +1661868199672515328 +1661868199714516224 +1661868199753517056 +1661868199795517952 +1661868199834518784 +1661868199876519680 +1661868199915520512 +1661868199954521344 +1661868199996522240 +1661868200038523136 +1661868200080524032 +1661868200119524864 +1661868200158525696 +1661868200200526592 +1661868200242527488 +1661868200284528384 +1661868200329529344 +1661868200365530112 +1661868200410531072 +1661868200452531968 +1661868200491532800 +1661868200533533696 +1661868200572534528 +1661868200614535424 +1661868200662536448 +1661868200710537472 +1661868200755538432 +1661868200797539328 +1661868200836540160 +1661868200872540928 +1661868200914541824 +1661868200956542720 +1661868200998543616 +1661868201037544448 +1661868201076545280 +1661868201118546176 +1661868201154546944 +1661868201193547776 +1661868201235548672 +1661868201280549632 +1661868201319550464 +1661868201364551424 +1661868201406552320 +1661868201451553280 +1661868201493554176 +1661868201532555008 +1661868201574555904 +1661868201616556800 +1661868201658557696 +1661868201700558592 +1661868201739559424 +1661868201778560256 +1661868201820561152 +1661868201862562048 +1661868201913563136 +1661868201955564032 +1661868202000564992 +1661868202042565888 +1661868202084566784 +1661868202129567744 +1661868202168568576 +1661868202210569472 +1661868202252570368 +1661868202288571136 +1661868202330572032 +1661868202372572928 +1661868202414573824 +1661868202462574848 +1661868202504575744 +1661868202546576640 +1661868202588577536 +1661868202630578432 +1661868202675579392 +1661868202717580288 +1661868202756581120 +1661868202801582080 +1661868202846583040 +1661868202885583872 +1661868202927584768 +1661868202972585728 +1661868203011586560 +1661868203056587520 +1661868203101588480 +1661868203140589312 +1661868203182590208 +1661868203230591232 +1661868203272592128 +1661868203314593024 +1661868203359593984 +1661868203401594880 +1661868203443595776 +1661868203485596672 +1661868203527597568 +1661868203569598464 +1661868203611599360 +1661868203653600256 +1661868203695601152 +1661868203737602048 +1661868203779602944 +1661868203824603904 +1661868203863604736 +1661868203905605632 +1661868203947606528 +1661868203989607424 +1661868204034608384 +1661868204079609344 +1661868204121610240 +1661868204163611136 +1661868204205612032 +1661868204247612928 +1661868204289613824 +1661868204328614656 +1661868204367615488 +1661868204400616192 +1661868204442617088 +1661868204490618112 +1661868204532619008 +1661868204574619904 +1661868204616620800 +1661868204658621696 +1661868204697622528 +1661868204733623296 +1661868204775624192 +1661868204820625152 +1661868204856625920 +1661868204898626816 +1661868204943627776 +1661868204988628736 +1661868205033629696 +1661868205075630592 +1661868205114631424 +1661868205156632320 +1661868205204633344 +1661868205249634304 +1661868205288635136 +1661868205330636032 +1661868205372636928 +1661868205414637824 +1661868205456638720 +1661868205498639616 +1661868205537640448 +1661868205579641344 +1661868205621642240 +1661868205654642944 +1661868205696643840 +1661868205738644736 +1661868205789645824 +1661868205828646656 +1661868205870647552 +1661868205915648512 +1661868205960649472 +1661868206002650368 +1661868206044651264 +1661868206083652096 +1661868206125652992 +1661868206170653952 +1661868206212654848 +1661868206254655744 +1661868206299656704 +1661868206341657600 +1661868206380658432 +1661868206422659328 +1661868206467660288 +1661868206509661184 +1661868206548662016 +1661868206590662912 +1661868206638663936 +1661868206677664768 +1661868206722665728 +1661868206767666688 +1661868206809667584 +1661868206851668480 +1661868206890669312 +1661868206932670208 +1661868206971671040 +1661868207013671936 +1661868207055672832 +1661868207097673728 +1661868207139674624 +1661868207187675648 +1661868207229676544 +1661868207271677440 +1661868207313678336 +1661868207355679232 +1661868207397680128 +1661868207442681088 +1661868207487682048 +1661868207526682880 +1661868207568683776 +1661868207613684736 +1661868207658685696 +1661868207700686592 +1661868207742687488 +1661868207790688512 +1661868207829689344 +1661868207868690176 +1661868207913691136 +1661868207955692032 +1661868207997692928 +1661868208039693824 +1661868208084694784 +1661868208132695808 +1661868208177696768 +1661868208216697600 +1661868208255698432 +1661868208297699328 +1661868208339700224 +1661868208375700992 +1661868208417701888 +1661868208459702784 +1661868208501703680 +1661868208549704704 +1661868208591705600 +1661868208630706432 +1661868208672707328 +1661868208714708224 +1661868208756709120 +1661868208795709952 +1661868208831710720 +1661868208876711680 +1661868208918712576 +1661868208960713472 +1661868209002714368 +1661868209047715328 +1661868209089716224 +1661868209131717120 +1661868209173718016 +1661868209218718976 +1661868209260719872 +1661868209299720704 +1661868209341721600 +1661868209386722560 +1661868209434723584 +1661868209476724480 +1661868209518725376 +1661868209563726336 +1661868209608727296 +1661868209647728128 +1661868209686728960 +1661868209731729920 +1661868209773730816 +1661868209809731584 +1661868209851732480 +1661868209899733504 +1661868209941734400 +1661868209980735232 +1661868210022736128 +1661868210067737088 +1661868210109737984 +1661868210148738816 +1661868210187739648 +1661868210226740480 +1661868210268741376 +1661868210310742272 +1661868210349743104 +1661868210391744000 +1661868210430744832 +1661868210472745728 +1661868210514746624 +1661868210556747520 +1661868210601748480 +1661868210640749312 +1661868210682750208 +1661868210724751104 +1661868210766752000 +1661868210811752960 +1661868210856753920 +1661868210898754816 +1661868210937755648 +1661868210979756544 +1661868211021757440 +1661868211063758336 +1661868211102759168 +1661868211150760192 +1661868211195761152 +1661868211237762048 +1661868211273762816 +1661868211315763712 +1661868211357764608 +1661868211396765440 +1661868211441766400 +1661868211480767232 +1661868211522768128 +1661868211567769088 +1661868211606769920 +1661868211648770816 +1661868211687771648 +1661868211729772544 +1661868211771773440 +1661868211813774336 +1661868211861775360 +1661868211906776320 +1661868211948777216 +1661868211993778176 +1661868212041779200 +1661868212083780096 +1661868212131781120 +1661868212173782016 +1661868212215782912 +1661868212257783808 +1661868212302784768 +1661868212347785728 +1661868212386786560 +1661868212431787520 +1661868212473788416 +1661868212515789312 +1661868212557790208 +1661868212599791104 +1661868212641792000 +1661868212683792896 +1661868212725793792 +1661868212767794688 +1661868212809795584 +1661868212851796480 +1661868212893797376 +1661868212935798272 +1661868212971799040 +1661868213016800000 +1661868213055800832 +1661868213094801664 +1661868213139802624 +1661868213178803456 +1661868213220804352 +1661868213259805184 +1661868213307806208 +1661868213343806976 +1661868213391808000 +1661868213430808832 +1661868213475809792 +1661868213523810816 +1661868213568811776 +1661868213610812672 +1661868213649813504 +1661868213691814400 +1661868213733815296 +1661868213772816128 +1661868213814817024 +1661868213850817792 +1661868213892818688 +1661868213937819648 +1661868213979820544 +1661868214015821312 +1661868214060822272 +1661868214099823104 +1661868214141824000 +1661868214180824832 +1661868214222825728 +1661868214264826624 +1661868214306827520 +1661868214351828480 +1661868214393829376 +1661868214432830208 +1661868214471831040 +1661868214513831936 +1661868214555832832 +1661868214594833664 +1661868214636834560 +1661868214678835456 +1661868214720836352 +1661868214762837248 +1661868214807838208 +1661868214849839104 +1661868214885839872 +1661868214927840768 +1661868214972841728 +1661868215014842624 +1661868215059843584 +1661868215101844480 +1661868215140845312 +1661868215188846336 +1661868215230847232 +1661868215278848256 +1661868215320849152 +1661868215362850048 +1661868215401850880 +1661868215443851776 +1661868215488852736 +1661868215530853632 +1661868215569854464 +1661868215611855360 +1661868215650856192 +1661868215692857088 +1661868215734857984 +1661868215776858880 +1661868215815859712 +1661868215860860672 +1661868215902861568 +1661868215944862464 +1661868215986863360 +1661868216034864384 +1661868216076865280 +1661868216121866240 +1661868216163867136 +1661868216202867968 +1661868216250868992 +1661868216295869952 +1661868216337870848 +1661868216385871872 +1661868216427872768 +1661868216475873792 +1661868216520874752 +1661868216562875648 +1661868216607876608 +1661868216649877504 +1661868216700878592 +1661868216742879488 +1661868216784880384 +1661868216823881216 +1661868216865882112 +1661868216913883136 +1661868216952883968 +1661868216991884800 +1661868217033885696 +1661868217075886592 +1661868217117887488 +1661868217162888448 +1661868217198889216 +1661868217240890112 +1661868217282891008 +1661868217321891840 +1661868217363892736 +1661868217405893632 +1661868217447894528 +1661868217489895424 +1661868217534896384 +1661868217576897280 +1661868217618898176 +1661868217666899200 +1661868217711900160 +1661868217753901056 +1661868217795901952 +1661868217837902848 +1661868217879903744 +1661868217921904640 +1661868217963905536 +1661868218005906432 +1661868218047907328 +1661868218092908288 +1661868218134909184 +1661868218182910208 +1661868218224911104 +1661868218266912000 +1661868218305912832 +1661868218350913792 +1661868218392914688 +1661868218437915648 +1661868218479916544 +1661868218521917440 +1661868218563918336 +1661868218605919232 +1661868218644920064 +1661868218686920960 +1661868218728921856 +1661868218770922752 +1661868218815923712 +1661868218857924608 +1661868218896925440 +1661868218944926464 +1661868218986927360 +1661868219028928256 +1661868219073929216 +1661868219115930112 +1661868219154930944 +1661868219202931968 +1661868219247932928 +1661868219295933952 +1661868219343934976 +1661868219385935872 +1661868219430936832 +1661868219469937664 +1661868219511938560 +1661868219553939456 +1661868219595940352 +1661868219637941248 +1661868219676942080 +1661868219715942912 +1661868219757943808 +1661868219796944640 +1661868219841945600 +1661868219883946496 +1661868219925947392 +1661868219967948288 +1661868220006949120 +1661868220045949952 +1661868220087950848 +1661868220129951744 +1661868220174952704 +1661868220213953536 +1661868220252954368 +1661868220291955200 +1661868220333956096 +1661868220375956992 +1661868220420957952 +1661868220462958848 +1661868220504959744 +1661868220549960704 +1661868220594961664 +1661868220636962560 +1661868220678963456 +1661868220717964288 +1661868220762965248 +1661868220804966144 +1661868220855967232 +1661868220897968128 +1661868220942969088 +1661868220984969984 +1661868221026970880 +1661868221068971776 +1661868221107972608 +1661868221146973440 +1661868221185974272 +1661868221224975104 +1661868221269976064 +1661868221311976960 +1661868221350977792 +1661868221395978752 +1661868221440979712 +1661868221479980544 +1661868221518981376 +1661868221560982272 +1661868221602983168 +1661868221647984128 +1661868221686984960 +1661868221731985920 +1661868221779986944 +1661868221821987840 +1661868221866988800 +1661868221908989696 +1661868221947990528 +1661868221995991552 +1661868222034992384 +1661868222076993280 +1661868222121994240 +1661868222166995200 +1661868222211996160 +1661868222253997056 +1661868222292997888 +1661868222331998720 +1661868222373999616 +1661868222416000512 +1661868222458001408 +1661868222500002304 +1661868222548003328 +1661868222584004096 +1661868222626004992 +1661868222671005952 +1661868222713006848 +1661868222764007936 +1661868222806008832 +1661868222848009728 +1661868222890010624 +1661868222932011520 +1661868222974012416 +1661868223022013440 +1661868223070014464 +1661868223109015296 +1661868223151016192 +1661868223190017024 +1661868223241018112 +1661868223283019008 +1661868223328019968 +1661868223367020800 +1661868223409021696 +1661868223457022720 +1661868223499023616 +1661868223541024512 +1661868223583025408 +1661868223625026304 +1661868223670027264 +1661868223709028096 +1661868223751028992 +1661868223793029888 +1661868223841030912 +1661868223883031808 +1661868223925032704 +1661868223967033600 +1661868224006034432 +1661868224045035264 +1661868224087036160 +1661868224129037056 +1661868224168037888 +1661868224207038720 +1661868224261039872 +1661868224300040704 +1661868224342041600 +1661868224384042496 +1661868224432043520 +1661868224474044416 +1661868224519045376 +1661868224561046272 +1661868224603047168 +1661868224645048064 +1661868224687048960 +1661868224732049920 +1661868224774050816 +1661868224816051712 +1661868224855052544 +1661868224897053440 +1661868224939054336 +1661868224981055232 +1661868225023056128 +1661868225074057216 +1661868225116058112 +1661868225161059072 +1661868225203059968 +1661868225248060928 +1661868225290061824 +1661868225338062848 +1661868225380063744 +1661868225422064640 +1661868225467065600 +1661868225509066496 +1661868225545067264 +1661868225590068224 +1661868225638069248 +1661868225686070272 +1661868225728071168 +1661868225770072064 +1661868225818073088 +1661868225860073984 +1661868225902074880 +1661868225944075776 +1661868225992076800 +1661868226034077696 +1661868226076078592 +1661868226118079488 +1661868226160080384 +1661868226199081216 +1661868226241082112 +1661868226289083136 +1661868226334084096 +1661868226376084992 +1661868226418085888 +1661868226454086656 +1661868226496087552 +1661868226535088384 +1661868226586089472 +1661868226628090368 +1661868226670091264 +1661868226709092096 +1661868226751092992 +1661868226799094016 +1661868226838094848 +1661868226883095808 +1661868226925096704 +1661868226967097600 +1661868227012098560 +1661868227054099456 +1661868227093100288 +1661868227141101312 +1661868227186102272 +1661868227225103104 +1661868227270104064 +1661868227312104960 +1661868227354105856 +1661868227396106752 +1661868227441107712 +1661868227483108608 +1661868227525109504 +1661868227567110400 +1661868227609111296 +1661868227651112192 +1661868227690113024 +1661868227732113920 +1661868227774114816 +1661868227819115776 +1661868227867116800 +1661868227912117760 +1661868227954118656 +1661868227996119552 +1661868228038120448 +1661868228086121472 +1661868228134122496 +1661868228179123456 +1661868228221124352 +1661868228263125248 +1661868228305126144 +1661868228353127168 +1661868228395128064 +1661868228434128896 +1661868228479129856 +1661868228524130816 +1661868228569131776 +1661868228611132672 +1661868228656133632 +1661868228698134528 +1661868228737135360 +1661868228776136192 +1661868228824137216 +1661868228866138112 +1661868228908139008 +1661868228950139904 +1661868228992140800 +1661868229031141632 +1661868229073142528 +1661868229124143616 +1661868229166144512 +1661868229208145408 +1661868229253146368 +1661868229295147264 +1661868229337148160 +1661868229379149056 +1661868229421149952 +1661868229463150848 +1661868229508151808 +1661868229547152640 +1661868229592153600 +1661868229634154496 +1661868229673155328 +1661868229715156224 +1661868229757157120 +1661868229796157952 +1661868229838158848 +1661868229880159744 +1661868229931160832 +1661868229973161728 +1661868230015162624 +1661868230057163520 +1661868230099164416 +1661868230141165312 +1661868230186166272 +1661868230228167168 +1661868230270168064 +1661868230309168896 +1661868230354169856 +1661868230396170752 +1661868230435171584 +1661868230480172544 +1661868230525173504 +1661868230561174272 +1661868230603175168 +1661868230642176000 +1661868230684176896 +1661868230723177728 +1661868230765178624 +1661868230807179520 +1661868230849180416 +1661868230891181312 +1661868230936182272 +1661868230978183168 +1661868231020184064 +1661868231059184896 +1661868231104185856 +1661868231146186752 +1661868231191187712 +1661868231233188608 +1661868231275189504 +1661868231317190400 +1661868231356191232 +1661868231401192192 +1661868231443193088 +1661868231482193920 +1661868231524194816 +1661868231569195776 +1661868231611196672 +1661868231653197568 +1661868231692198400 +1661868231731199232 +1661868231770200064 +1661868231812200960 +1661868231857201920 +1661868231902202880 +1661868231944203776 +1661868231986204672 +1661868232031205632 +1661868232070206464 +1661868232112207360 +1661868232157208320 +1661868232199209216 +1661868232241210112 +1661868232283211008 +1661868232328211968 +1661868232370212864 +1661868232412213760 +1661868232454214656 +1661868232496215552 +1661868232532216320 +1661868232574217216 +1661868232616218112 +1661868232652218880 +1661868232691219712 +1661868232733220608 +1661868232775221504 +1661868232817222400 +1661868232859223296 +1661868232901224192 +1661868232946225152 +1661868232991226112 +1661868233030226944 +1661868233075227904 +1661868233117228800 +1661868233159229696 +1661868233204230656 +1661868233240231424 +1661868233282232320 +1661868233324233216 +1661868233363234048 +1661868233405234944 +1661868233441235712 +1661868233483236608 +1661868233528237568 +1661868233576238592 +1661868233624239616 +1661868233669240576 +1661868233711241472 +1661868233756242432 +1661868233798243328 +1661868233840244224 +1661868233882245120 +1661868233924246016 +1661868233963246848 +1661868234005247744 +1661868234053248768 +1661868234095249664 +1661868234134250496 +1661868234179251456 +1661868234221252352 +1661868234263253248 +1661868234305254144 +1661868234347255040 +1661868234389255936 +1661868234431256832 +1661868234473257728 +1661868234518258688 +1661868234560259584 +1661868234602260480 +1661868234644261376 +1661868234686262272 +1661868234728263168 +1661868234770264064 +1661868234812264960 +1661868234848265728 +1661868234890266624 +1661868234929267456 +1661868234974268416 +1661868235013269248 +1661868235055270144 +1661868235103271168 +1661868235148272128 +1661868235187272960 +1661868235232273920 +1661868235274274816 +1661868235319275776 +1661868235361276672 +1661868235403277568 +1661868235448278528 +1661868235499279616 +1661868235544280576 +1661868235589281536 +1661868235631282432 +1661868235670283264 +1661868235715284224 +1661868235760285184 +1661868235802286080 +1661868235850287104 +1661868235892288000 +1661868235937288960 +1661868235979289856 +1661868236021290752 +1661868236069291776 +1661868236111292672 +1661868236153293568 +1661868236195294464 +1661868236240295424 +1661868236282296320 +1661868236333297408 +1661868236375298304 +1661868236417299200 +1661868236462300160 +1661868236507301120 +1661868236543301888 +1661868236585302784 +1661868236627303680 +1661868236666304512 +1661868236708305408 +1661868236756306432 +1661868236795307264 +1661868236834308096 +1661868236870308864 +1661868236915309824 +1661868236957310720 +1661868237005311744 +1661868237047312640 +1661868237089313536 +1661868237134314496 +1661868237176315392 +1661868237218316288 +1661868237263317248 +1661868237302318080 +1661868237344318976 +1661868237383319808 +1661868237425320704 +1661868237467321600 +1661868237506322432 +1661868237557323520 +1661868237599324416 +1661868237641325312 +1661868237683326208 +1661868237725327104 +1661868237770328064 +1661868237809328896 +1661868237851329792 +1661868237899330816 +1661868237941331712 +1661868237989332736 +1661868238028333568 +1661868238073334528 +1661868238118335488 +1661868238160336384 +1661868238202337280 +1661868238241338112 +1661868238292339200 +1661868238337340160 +1661868238379341056 +1661868238421341952 +1661868238463342848 +1661868238505343744 +1661868238547344640 +1661868238583345408 +1661868238628346368 +1661868238667347200 +1661868238709348096 +1661868238757349120 +1661868238799350016 +1661868238844350976 +1661868238889351936 +1661868238928352768 +1661868238967353600 +1661868239003354368 +1661868239045355264 +1661868239090356224 +1661868239138357248 +1661868239183358208 +1661868239234359296 +1661868239279360256 +1661868239321361152 +1661868239369362176 +1661868239411363072 +1661868239456364032 +1661868239504365056 +1661868239546365952 +1661868239591366912 +1661868239633367808 +1661868239678368768 +1661868239717369600 +1661868239759370496 +1661868239810371584 +1661868239852372480 +1661868239894373376 +1661868239936374272 +1661868239975375104 +1661868240023376128 +1661868240065377024 +1661868240107377920 +1661868240149378816 +1661868240191379712 +1661868240236380672 +1661868240281381632 +1661868240320382464 +1661868240359383296 +1661868240398384128 +1661868240437384960 +1661868240479385856 +1661868240521386752 +1661868240560387584 +1661868240599388416 +1661868240641389312 +1661868240683390208 +1661868240728391168 +1661868240770392064 +1661868240815393024 +1661868240857393920 +1661868240902394880 +1661868240947395840 +1661868240986396672 +1661868241028397568 +1661868241070398464 +1661868241121399552 +1661868241166400512 +1661868241208401408 +1661868241247402240 +1661868241289403136 +1661868241331404032 +1661868241373404928 +1661868241418405888 +1661868241460406784 +1661868241505407744 +1661868241544408576 +1661868241583409408 +1661868241625410304 +1661868241667411200 +1661868241709412096 +1661868241754413056 +1661868241796413952 +1661868241838414848 +1661868241880415744 +1661868241925416704 +1661868241979417856 +1661868242021418752 +1661868242060419584 +1661868242099420416 +1661868242141421312 +1661868242183422208 +1661868242225423104 +1661868242267424000 +1661868242312424960 +1661868242354425856 +1661868242390426624 +1661868242432427520 +1661868242471428352 +1661868242507429120 +1661868242549430016 +1661868242591430912 +1661868242633431808 +1661868242675432704 +1661868242717433600 +1661868242759434496 +1661868242801435392 +1661868242843436288 +1661868242885437184 +1661868242927438080 +1661868242969438976 +1661868243011439872 +1661868243053440768 +1661868243095441664 +1661868243140442624 +1661868243182443520 +1661868243221444352 +1661868243272445440 +1661868243317446400 +1661868243359447296 +1661868243401448192 +1661868243440449024 +1661868243488450048 +1661868243533451008 +1661868243575451904 +1661868243617452800 +1661868243656453632 +1661868243698454528 +1661868243740455424 +1661868243782456320 +1661868243824457216 +1661868243866458112 +1661868243914459136 +1661868243956460032 +1661868243998460928 +1661868244043461888 +1661868244085462784 +1661868244127463680 +1661868244172464640 +1661868244220465664 +1661868244265466624 +1661868244304467456 +1661868244349468416 +1661868244394469376 +1661868244439470336 +1661868244481471232 +1661868244520472064 +1661868244559472896 +1661868244601473792 +1661868244649474816 +1661868244691475712 +1661868244736476672 +1661868244778477568 +1661868244823478528 +1661868244865479424 +1661868244913480448 +1661868244961481472 +1661868245012482560 +1661868245054483456 +1661868245096484352 +1661868245138485248 +1661868245180486144 +1661868245222487040 +1661868245267488000 +1661868245309488896 +1661868245351489792 +1661868245396490752 +1661868245438491648 +1661868245483492608 +1661868245525493504 +1661868245570494464 +1661868245615495424 +1661868245657496320 +1661868245702497280 +1661868245741498112 +1661868245783499008 +1661868245822499840 +1661868245867500800 +1661868245909501696 +1661868245951502592 +1661868245993503488 +1661868246038504448 +1661868246080505344 +1661868246125506304 +1661868246182507520 +1661868246224508416 +1661868246263509248 +1661868246302510080 +1661868246344510976 +1661868246389511936 +1661868246434512896 +1661868246476513792 +1661868246521514752 +1661868246563515648 +1661868246602516480 +1661868246638517248 +1661868246686518272 +1661868246725519104 +1661868246767520000 +1661868246809520896 +1661868246851521792 +1661868246893522688 +1661868246944523776 +1661868246986524672 +1661868247028525568 +1661868247076526592 +1661868247118527488 +1661868247151528192 +1661868247190529024 +1661868247238530048 +1661868247280530944 +1661868247325531904 +1661868247370532864 +1661868247415533824 +1661868247457534720 +1661868247499535616 +1661868247541536512 +1661868247580537344 +1661868247622538240 +1661868247664539136 +1661868247709540096 +1661868247751540992 +1661868247790541824 +1661868247832542720 +1661868247874543616 +1661868247925544704 +1661868247967545600 +1661868248015546624 +1661868248057547520 +1661868248099548416 +1661868248141549312 +1661868248183550208 +1661868248222551040 +1661868248264551936 +1661868248312552960 +1661868248354553856 +1661868248399554816 +1661868248444555776 +1661868248486556672 +1661868248528557568 +1661868248567558400 +1661868248606559232 +1661868248645560064 +1661868248693561088 +1661868248735561984 +1661868248777562880 +1661868248819563776 +1661868248861564672 +1661868248906565632 +1661868248945566464 +1661868248987567360 +1661868249029568256 +1661868249077569280 +1661868249119570176 +1661868249164571136 +1661868249206572032 +1661868249248572928 +1661868249299574016 +1661868249341574912 +1661868249386575872 +1661868249425576704 +1661868249470577664 +1661868249509578496 +1661868249554579456 +1661868249599580416 +1661868249641581312 +1661868249686582272 +1661868249728583168 +1661868249767584000 +1661868249806584832 +1661868249851585792 +1661868249896586752 +1661868249932587520 +1661868249974588416 +1661868250016589312 +1661868250055590144 +1661868250097591040 +1661868250139591936 +1661868250181592832 +1661868250223593728 +1661868250265594624 +1661868250304595456 +1661868250343596288 +1661868250385597184 +1661868250430598144 +1661868250472599040 +1661868250523600128 +1661868250574601216 +1661868250619602176 +1661868250658603008 +1661868250703603968 +1661868250754605056 +1661868250796605952 +1661868250838606848 +1661868250880607744 +1661868250922608640 +1661868250964609536 +1661868251006610432 +1661868251048611328 +1661868251090612224 +1661868251129613056 +1661868251177614080 +1661868251219614976 +1661868251261615872 +1661868251303616768 +1661868251342617600 +1661868251384618496 +1661868251426619392 +1661868251471620352 +1661868251513621248 +1661868251555622144 +1661868251597623040 +1661868251642624000 +1661868251693625088 +1661868251732625920 +1661868251771626752 +1661868251810627584 +1661868251855628544 +1661868251897629440 +1661868251939630336 +1661868251984631296 +1661868252035632384 +1661868252074633216 +1661868252122634240 +1661868252164635136 +1661868252206636032 +1661868252245636864 +1661868252287637760 +1661868252338638848 +1661868252380639744 +1661868252422640640 +1661868252464641536 +1661868252506642432 +1661868252545643264 +1661868252590644224 +1661868252632645120 +1661868252677646080 +1661868252722647040 +1661868252764647936 +1661868252806648832 +1661868252842649600 +1661868252884650496 +1661868252938651648 +1661868252980652544 +1661868253022653440 +1661868253064654336 +1661868253100655104 +1661868253145656064 +1661868253184656896 +1661868253226657792 +1661868253268658688 +1661868253307659520 +1661868253349660416 +1661868253391661312 +1661868253433662208 +1661868253478663168 +1661868253520664064 +1661868253562664960 +1661868253610665984 +1661868253652666880 +1661868253694667776 +1661868253736668672 +1661868253778669568 +1661868253817670400 +1661868253859671296 +1661868253901672192 +1661868253943673088 +1661868253985673984 +1661868254027674880 +1661868254069675776 +1661868254111676672 +1661868254153677568 +1661868254195678464 +1661868254234679296 +1661868254279680256 +1661868254318681088 +1661868254360681984 +1661868254402682880 +1661868254444683776 +1661868254489684736 +1661868254534685696 +1661868254582686720 +1661868254624687616 +1661868254666688512 +1661868254708689408 +1661868254750690304 +1661868254798691328 +1661868254843692288 +1661868254885693184 +1661868254924694016 +1661868254969694976 +1661868255011695872 +1661868255053696768 +1661868255095697664 +1661868255137698560 +1661868255179699456 +1661868255224700416 +1661868255266701312 +1661868255317702400 +1661868255359703296 +1661868255398704128 +1661868255437704960 +1661868255479705856 +1661868255518706688 +1661868255557707520 +1661868255599708416 +1661868255641709312 +1661868255680710144 +1661868255722711040 +1661868255761711872 +1661868255803712768 +1661868255845713664 +1661868255887714560 +1661868255932715520 +1661868255977716480 +1661868256019717376 +1661868256061718272 +1661868256103719168 +1661868256145720064 +1661868256196721152 +1661868256238722048 +1661868256280722944 +1661868256319723776 +1661868256361724672 +1661868256403725568 +1661868256442726400 +1661868256490727424 +1661868256529728256 +1661868256568729088 +1661868256607729920 +1661868256649730816 +1661868256691731712 +1661868256727732480 +1661868256766733312 +1661868256808734208 +1661868256847735040 +1661868256892736000 +1661868256934736896 +1661868256979737856 +1661868257021738752 +1661868257063739648 +1661868257105740544 +1661868257150741504 +1661868257192742400 +1661868257234743296 +1661868257276744192 +1661868257318745088 +1661868257360745984 +1661868257408747008 +1661868257450747904 +1661868257492748800 +1661868257534749696 +1661868257582750720 +1661868257621751552 +1661868257663752448 +1661868257702753280 +1661868257741754112 +1661868257783755008 +1661868257828755968 +1661868257873756928 +1661868257915757824 +1661868257960758784 +1661868257999759616 +1661868258044760576 +1661868258092761600 +1661868258134762496 +1661868258170763264 +1661868258209764096 +1661868258251764992 +1661868258293765888 +1661868258332766720 +1661868258374767616 +1661868258416768512 +1661868258458769408 +1661868258503770368 +1661868258545771264 +1661868258587772160 +1661868258629773056 +1661868258674774016 +1661868258713774848 +1661868258749775616 +1661868258788776448 +1661868258830777344 +1661868258872778240 +1661868258914779136 +1661868258950779904 +1661868258992780800 +1661868259034781696 +1661868259073782528 +1661868259118783488 +1661868259160784384 +1661868259202785280 +1661868259244786176 +1661868259286787072 +1661868259328787968 +1661868259373788928 +1661868259415789824 +1661868259460790784 +1661868259502791680 +1661868259544792576 +1661868259592793600 +1661868259631794432 +1661868259673795328 +1661868259715796224 +1661868259757797120 +1661868259799798016 +1661868259838798848 +1661868259883799808 +1661868259928800768 +1661868259973801728 +1661868260015802624 +1661868260054803456 +1661868260096804352 +1661868260138805248 +1661868260180806144 +1661868260219806976 +1661868260261807872 +1661868260303808768 +1661868260348809728 +1661868260390810624 +1661868260432811520 +1661868260477812480 +1661868260519813376 +1661868260564814336 +1661868260606815232 +1661868260648816128 +1661868260690817024 +1661868260732817920 +1661868260774818816 +1661868260816819712 +1661868260861820672 +1661868260903821568 +1661868260939822336 +1661868260981823232 +1661868261020824064 +1661868261059824896 +1661868261104825856 +1661868261149826816 +1661868261188827648 +1661868261224828416 +1661868261272829440 +1661868261314830336 +1661868261359831296 +1661868261398832128 +1661868261443833088 +1661868261488834048 +1661868261530834944 +1661868261572835840 +1661868261620836864 +1661868261662837760 +1661868261707838720 +1661868261752839680 +1661868261791840512 +1661868261833841408 +1661868261875842304 +1661868261923843328 +1661868261965844224 +1661868262010845184 +1661868262052846080 +1661868262100847104 +1661868262139847936 +1661868262178848768 +1661868262217849600 +1661868262259850496 +1661868262301851392 +1661868262343852288 +1661868262388853248 +1661868262430854144 +1661868262472855040 +1661868262511855872 +1661868262559856896 +1661868262601857792 +1661868262646858752 +1661868262691859712 +1661868262733860608 +1661868262775861504 +1661868262820862464 +1661868262868863488 +1661868262907864320 +1661868262949865216 +1661868262991866112 +1661868263033867008 +1661868263075867904 +1661868263117868800 +1661868263159869696 +1661868263198870528 +1661868263240871424 +1661868263279872256 +1661868263321873152 +1661868263363874048 +1661868263408875008 +1661868263444875776 +1661868263486876672 +1661868263528877568 +1661868263567878400 +1661868263609879296 +1661868263651880192 +1661868263696881152 +1661868263738882048 +1661868263780882944 +1661868263822883840 +1661868263867884800 +1661868263906885632 +1661868263954886656 +1661868263996887552 +1661868264035888384 +1661868264074889216 +1661868264119890176 +1661868264161891072 +1661868264203891968 +1661868264242892800 +1661868264287893760 +1661868264329894656 +1661868264371895552 +1661868264413896448 +1661868264461897472 +1661868264500898304 +1661868264539899136 +1661868264584900096 +1661868264626900992 +1661868264665901824 +1661868264707902720 +1661868264752903680 +1661868264800904704 +1661868264851905792 +1661868264893906688 +1661868264935907584 +1661868264977908480 +1661868265016909312 +1661868265058910208 +1661868265100911104 +1661868265142912000 +1661868265187912960 +1661868265229913856 +1661868265274914816 +1661868265322915840 +1661868265361916672 +1661868265403917568 +1661868265445918464 +1661868265484919296 +1661868265526920192 +1661868265565921024 +1661868265619922176 +1661868265664923136 +1661868265706924032 +1661868265748924928 +1661868265790925824 +1661868265829926656 +1661868265874927616 +1661868265916928512 +1661868265955929344 +1661868265997930240 +1661868266036931072 +1661868266081932032 +1661868266123932928 +1661868266162933760 +1661868266204934656 +1661868266246935552 +1661868266288936448 +1661868266330937344 +1661868266369938176 +1661868266408939008 +1661868266450939904 +1661868266492940800 +1661868266540941824 +1661868266588942848 +1661868266633943808 +1661868266675944704 +1661868266729945856 +1661868266768946688 +1661868266813947648 +1661868266852948480 +1661868266894949376 +1661868266939950336 +1661868266978951168 +1661868267020952064 +1661868267065953024 +1661868267110953984 +1661868267149954816 +1661868267194955776 +1661868267236956672 +1661868267278957568 +1661868267317958400 +1661868267359959296 +1661868267398960128 +1661868267440961024 +1661868267485961984 +1661868267527962880 +1661868267569963776 +1661868267611964672 +1661868267650965504 +1661868267686966272 +1661868267728967168 +1661868267770968064 +1661868267818969088 +1661868267860969984 +1661868267902970880 +1661868267950971904 +1661868268001972992 +1661868268043973888 +1661868268091974912 +1661868268133975808 +1661868268175976704 +1661868268217977600 +1661868268259978496 +1661868268301979392 +1661868268340980224 +1661868268382981120 +1661868268427982080 +1661868268472983040 +1661868268511983872 +1661868268553984768 +1661868268598985728 +1661868268640986624 +1661868268685987584 +1661868268727988480 +1661868268766989312 +1661868268811990272 +1661868268853991168 +1661868268892992000 +1661868268937992960 +1661868268979993856 +1661868269021994752 +1661868269063995648 +1661868269105996544 +1661868269147997440 +1661868269192998400 +1661868269234999296 +1661868269277000192 +1661868269316001024 +1661868269361001984 +1661868269400002816 +1661868269442003712 +1661868269484004608 +1661868269529005568 +1661868269568006400 +1661868269607007232 +1661868269649008128 +1661868269694009088 +1661868269736009984 +1661868269784011008 +1661868269829011968 +1661868269877012992 +1661868269919013888 +1661868269961014784 +1661868270009015808 +1661868270051016704 +1661868270096017664 +1661868270147018752 +1661868270186019584 +1661868270225020416 +1661868270264021248 +1661868270300022016 +1661868270339022848 +1661868270384023808 +1661868270423024640 +1661868270474025728 +1661868270516026624 +1661868270558027520 +1661868270600028416 +1661868270639029248 +1661868270681030144 +1661868270723031040 +1661868270762031872 +1661868270807032832 +1661868270849033728 +1661868270897034752 +1661868270939035648 +1661868270978036480 +1661868271026037504 +1661868271071038464 +1661868271113039360 +1661868271152040192 +1661868271194041088 +1661868271248042240 +1661868271290043136 +1661868271335044096 +1661868271380045056 +1661868271422045952 +1661868271467046912 +1661868271506047744 +1661868271545048576 +1661868271587049472 +1661868271629050368 +1661868271668051200 +1661868271713052160 +1661868271758053120 +1661868271803054080 +1661868271845054976 +1661868271887055872 +1661868271929056768 +1661868271971057664 +1661868272010058496 +1661868272052059392 +1661868272094060288 +1661868272136061184 +1661868272181062144 +1661868272223063040 +1661868272265063936 +1661868272307064832 +1661868272352065792 +1661868272391066624 +1661868272427067392 +1661868272469068288 +1661868272508069120 +1661868272550070016 +1661868272592070912 +1661868272631071744 +1661868272673072640 +1661868272715073536 +1661868272757074432 +1661868272796075264 +1661868272838076160 +1661868272880077056 +1661868272922077952 +1661868272964078848 +1661868273006079744 +1661868273045080576 +1661868273087081472 +1661868273129082368 +1661868273171083264 +1661868273213084160 +1661868273255085056 +1661868273297085952 +1661868273342086912 +1661868273387087872 +1661868273429088768 +1661868273471089664 +1661868273516090624 +1661868273558091520 +1661868273606092544 +1661868273651093504 +1661868273693094400 +1661868273735095296 +1661868273777096192 +1661868273822097152 +1661868273864098048 +1661868273909099008 +1661868273957100032 +1661868273999100928 +1661868274041101824 +1661868274092102912 +1661868274131103744 +1661868274173104640 +1661868274215105536 +1661868274260106496 +1661868274299107328 +1661868274341108224 +1661868274386109184 +1661868274428110080 +1661868274476111104 +1661868274521112064 +1661868274566113024 +1661868274605113856 +1661868274656114944 +1661868274701115904 +1661868274743116800 +1661868274785117696 +1661868274827118592 +1661868274869119488 +1661868274911120384 +1661868274953121280 +1661868274989122048 +1661868275031122944 +1661868275070123776 +1661868275109124608 +1661868275151125504 +1661868275193126400 +1661868275238127360 +1661868275280128256 +1661868275322129152 +1661868275364130048 +1661868275403130880 +1661868275451131904 +1661868275493132800 +1661868275538133760 +1661868275580134656 +1661868275622135552 +1661868275670136576 +1661868275706137344 +1661868275745138176 +1661868275784139008 +1661868275829139968 +1661868275874140928 +1661868275916141824 +1661868275958142720 +1661868275997143552 +1661868276039144448 +1661868276081145344 +1661868276123146240 +1661868276168147200 +1661868276210148096 +1661868276249148928 +1661868276291149824 +1661868276333150720 +1661868276378151680 +1661868276417152512 +1661868276459153408 +1661868276501154304 +1661868276546155264 +1661868276588156160 +1661868276630157056 +1661868276675158016 +1661868276717158912 +1661868276759159808 +1661868276804160768 +1661868276846161664 +1661868276885162496 +1661868276924163328 +1661868276963164160 +1661868277002164992 +1661868277044165888 +1661868277086166784 +1661868277128167680 +1661868277170168576 +1661868277215169536 +1661868277260170496 +1661868277308171520 +1661868277347172352 +1661868277389173248 +1661868277431174144 +1661868277470174976 +1661868277512175872 +1661868277554176768 +1661868277596177664 +1661868277641178624 +1661868277686179584 +1661868277728180480 +1661868277770181376 +1661868277812182272 +1661868277851183104 +1661868277893184000 +1661868277932184832 +1661868277971185664 +1661868278013186560 +1661868278055187456 +1661868278100188416 +1661868278145189376 +1661868278187190272 +1661868278229191168 +1661868278271192064 +1661868278310192896 +1661868278349193728 +1661868278391194624 +1661868278427195392 +1661868278469196288 +1661868278511197184 +1661868278550198016 +1661868278598199040 +1661868278637199872 +1661868278676200704 +1661868278721201664 +1661868278763202560 +1661868278805203456 +1661868278847204352 +1661868278886205184 +1661868278925206016 +1661868278967206912 +1661868279009207808 +1661868279048208640 +1661868279090209536 +1661868279132210432 +1661868279177211392 +1661868279216212224 +1661868279264213248 +1661868279309214208 +1661868279351215104 +1661868279393216000 +1661868279435216896 +1661868279477217792 +1661868279522218752 +1661868279570219776 +1661868279612220672 +1661868279651221504 +1661868279687222272 +1661868279732223232 +1661868279774224128 +1661868279816225024 +1661868279858225920 +1661868279900226816 +1661868279945227776 +1661868279990228736 +1661868280035229696 +1661868280077230592 +1661868280125231616 +1661868280167232512 +1661868280209233408 +1661868280251234304 +1661868280293235200 +1661868280338236160 +1661868280380237056 +1661868280422237952 +1661868280464238848 +1661868280503239680 +1661868280548240640 +1661868280590241536 +1661868280635242496 +1661868280680243456 +1661868280722244352 +1661868280764245248 +1661868280800246016 +1661868280851247104 +1661868280905248256 +1661868280956249344 +1661868280998250240 +1661868281040251136 +1661868281082252032 +1661868281124252928 +1661868281166253824 +1661868281208254720 +1661868281253255680 +1661868281292256512 +1661868281337257472 +1661868281379258368 +1661868281424259328 +1661868281466260224 +1661868281511261184 +1661868281550262016 +1661868281592262912 +1661868281631263744 +1661868281676264704 +1661868281718265600 +1661868281763266560 +1661868281808267520 +1661868281850268416 +1661868281892269312 +1661868281937270272 +1661868281985271296 +1661868282024272128 +1661868282066273024 +1661868282111273984 +1661868282159275008 +1661868282204275968 +1661868282249276928 +1661868282288277760 +1661868282330278656 +1661868282378279680 +1661868282417280512 +1661868282459281408 +1661868282513282560 +1661868282555283456 +1661868282597284352 +1661868282639285248 +1661868282681286144 +1661868282726287104 +1661868282768288000 +1661868282813288960 +1661868282852289792 +1661868282894290688 +1661868282939291648 +1661868282984292608 +1661868283023293440 +1661868283068294400 +1661868283116295424 +1661868283158296320 +1661868283203297280 +1661868283245298176 +1661868283284299008 +1661868283329299968 +1661868283371300864 +1661868283419301888 +1661868283461302784 +1661868283500303616 +1661868283548304640 +1661868283590305536 +1661868283638306560 +1661868283677307392 +1661868283725308416 +1661868283770309376 +1661868283812310272 +1661868283857311232 +1661868283899312128 +1661868283941313024 +1661868283989314048 +1661868284028314880 +1661868284067315712 +1661868284109316608 +1661868284157317632 +1661868284199318528 +1661868284247319552 +1661868284286320384 +1661868284328321280 +1661868284379322368 +1661868284421323264 +1661868284457324032 +1661868284496324864 +1661868284538325760 +1661868284580326656 +1661868284622327552 +1661868284667328512 +1661868284709329408 +1661868284763330560 +1661868284805331456 +1661868284850332416 +1661868284895333376 +1661868284937334272 +1661868284976335104 +1661868285021336064 +1661868285066337024 +1661868285105337856 +1661868285156338944 +1661868285201339904 +1661868285243340800 +1661868285294341888 +1661868285336342784 +1661868285378343680 +1661868285420344576 +1661868285459345408 +1661868285501346304 +1661868285543347200 +1661868285585348096 +1661868285624348928 +1661868285666349824 +1661868285711350784 +1661868285753351680 +1661868285795352576 +1661868285834353408 +1661868285885354496 +1661868285927355392 +1661868285969356288 +1661868286011357184 +1661868286050358016 +1661868286089358848 +1661868286131359744 +1661868286176360704 +1661868286221361664 +1661868286263362560 +1661868286314363648 +1661868286353364480 +1661868286398365440 +1661868286440366336 +1661868286482367232 +1661868286524368128 +1661868286560368896 +1661868286602369792 +1661868286644370688 +1661868286686371584 +1661868286728372480 +1661868286770373376 +1661868286821374464 +1661868286863375360 +1661868286908376320 +1661868286950377216 +1661868286992378112 +1661868287037379072 +1661868287079379968 +1661868287127380992 +1661868287169381888 +1661868287208382720 +1661868287253383680 +1661868287298384640 +1661868287340385536 +1661868287382386432 +1661868287424387328 +1661868287466388224 +1661868287508389120 +1661868287550390016 +1661868287592390912 +1661868287634391808 +1661868287676392704 +1661868287718393600 +1661868287760394496 +1661868287805395456 +1661868287847396352 +1661868287895397376 +1661868287937398272 +1661868287976399104 +1661868288015399936 +1661868288063400960 +1661868288105401856 +1661868288147402752 +1661868288189403648 +1661868288231404544 +1661868288273405440 +1661868288315406336 +1661868288354407168 +1661868288396408064 +1661868288438408960 +1661868288483409920 +1661868288525410816 +1661868288570411776 +1661868288606412544 +1661868288648413440 +1661868288690414336 +1661868288732415232 +1661868288774416128 +1661868288816417024 +1661868288858417920 +1661868288900418816 +1661868288951419904 +1661868288993420800 +1661868289041421824 +1661868289083422720 +1661868289128423680 +1661868289170424576 +1661868289212425472 +1661868289257426432 +1661868289296427264 +1661868289338428160 +1661868289380429056 +1661868289428430080 +1661868289476431104 +1661868289518432000 +1661868289560432896 +1661868289602433792 +1661868289641434624 +1661868289683435520 +1661868289725436416 +1661868289767437312 +1661868289809438208 +1661868289851439104 +1661868289890439936 +1661868289935440896 +1661868289983441920 +1661868290025442816 +1661868290067443712 +1661868290115444736 +1661868290154445568 +1661868290199446528 +1661868290244447488 +1661868290289448448 +1661868290328449280 +1661868290364450048 +1661868290412451072 +1661868290454451968 +1661868290496452864 +1661868290535453696 +1661868290580454656 +1661868290622455552 +1661868290664456448 +1661868290706457344 +1661868290754458368 +1661868290802459392 +1661868290841460224 +1661868290883461120 +1661868290925462016 +1661868290967462912 +1661868291015463936 +1661868291060464896 +1661868291102465792 +1661868291144466688 +1661868291186467584 +1661868291231468544 +1661868291270469376 +1661868291312470272 +1661868291354471168 +1661868291396472064 +1661868291438472960 +1661868291483473920 +1661868291525474816 +1661868291567475712 +1661868291609476608 +1661868291648477440 +1661868291690478336 +1661868291732479232 +1661868291771480064 +1661868291813480960 +1661868291855481856 +1661868291900482816 +1661868291942483712 +1661868291984484608 +1661868292026485504 +1661868292071486464 +1661868292113487360 +1661868292152488192 +1661868292194489088 +1661868292233489920 +1661868292281490944 +1661868292320491776 +1661868292359492608 +1661868292401493504 +1661868292443494400 +1661868292485495296 +1661868292530496256 +1661868292572497152 +1661868292614498048 +1661868292656498944 +1661868292698499840 +1661868292743500800 +1661868292785501696 +1661868292821502464 +1661868292869503488 +1661868292911504384 +1661868292959505408 +1661868293001506304 +1661868293043507200 +1661868293085508096 +1661868293130509056 +1661868293175510016 +1661868293217510912 +1661868293265511936 +1661868293313512960 +1661868293352513792 +1661868293391514624 +1661868293430515456 +1661868293472516352 +1661868293520517376 +1661868293562518272 +1661868293601519104 +1661868293643520000 +1661868293685520896 +1661868293730521856 +1661868293772522752 +1661868293811523584 +1661868293853524480 +1661868293898525440 +1661868293940526336 +1661868293985527296 +1661868294027528192 +1661868294069529088 +1661868294111529984 +1661868294162531072 +1661868294204531968 +1661868294246532864 +1661868294285533696 +1661868294324534528 +1661868294366535424 diff --git a/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_track1.txt b/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_track1.txt new file mode 100644 index 0000000000..f8502440d4 --- /dev/null +++ b/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_track1.txt @@ -0,0 +1,2030 @@ +1662015311059723520 +1662015311101724416 +1662015311146725376 +1662015311203726592 +1662015311248727552 +1662015311293728512 +1662015311335729408 +1662015311377730304 +1662015311422731264 +1662015311464732160 +1662015311506733056 +1662015311548733952 +1662015311590734848 +1662015311635735808 +1662015311677736704 +1662015311719737600 +1662015311761738496 +1662015311809739520 +1662015311857740544 +1662015311902741504 +1662015311944742400 +1662015311986743296 +1662015312031744256 +1662015312076745216 +1662015312130746368 +1662015312169747200 +1662015312208748032 +1662015312253748992 +1662015312295749888 +1662015312340750848 +1662015312379751680 +1662015312424752640 +1662015312463753472 +1662015312508754432 +1662015312550755328 +1662015312592756224 +1662015312631757056 +1662015312679758080 +1662015312724759040 +1662015312766759936 +1662015312811760896 +1662015312856761856 +1662015312901762816 +1662015312943763712 +1662015312985764608 +1662015313027765504 +1662015313075766528 +1662015313117767424 +1662015313159768320 +1662015313201769216 +1662015313240770048 +1662015313282770944 +1662015313327771904 +1662015313369772800 +1662015313411773696 +1662015313456774656 +1662015313498775552 +1662015313540776448 +1662015313591777536 +1662015313630778368 +1662015313672779264 +1662015313717780224 +1662015313756781056 +1662015313801782016 +1662015313843782912 +1662015313885783808 +1662015313927784704 +1662015313972785664 +1662015314014786560 +1662015314056787456 +1662015314101788416 +1662015314143789312 +1662015314185790208 +1662015314227791104 +1662015314272792064 +1662015314317793024 +1662015314362793984 +1662015314413795072 +1662015314455795968 +1662015314497796864 +1662015314539797760 +1662015314581798656 +1662015314626799616 +1662015314668800512 +1662015314716801536 +1662015314761802496 +1662015314803803392 +1662015314848804352 +1662015314896805376 +1662015314938806272 +1662015314980807168 +1662015315028808192 +1662015315073809152 +1662015315115810048 +1662015315154810880 +1662015315199811840 +1662015315238812672 +1662015315280813568 +1662015315328814592 +1662015315379815680 +1662015315427816704 +1662015315475817728 +1662015315532818944 +1662015315577819904 +1662015315619820800 +1662015315670821888 +1662015315721822976 +1662015315766823936 +1662015315814824960 +1662015315859825920 +1662015315904826880 +1662015315949827840 +1662015315991828736 +1662015316033829632 +1662015316078830592 +1662015316126831616 +1662015316174832640 +1662015316219833600 +1662015316270834688 +1662015316315835648 +1662015316366836736 +1662015316414837760 +1662015316462838784 +1662015316507839744 +1662015316552840704 +1662015316597841664 +1662015316648842752 +1662015316690843648 +1662015316729844480 +1662015316774845440 +1662015316822846464 +1662015316867847424 +1662015316909848320 +1662015316951849216 +1662015316993850112 +1662015317038851072 +1662015317083852032 +1662015317128852992 +1662015317170853888 +1662015317218854912 +1662015317260855808 +1662015317302856704 +1662015317344857600 +1662015317389858560 +1662015317434859520 +1662015317473860352 +1662015317515861248 +1662015317560862208 +1662015317605863168 +1662015317647864064 +1662015317692865024 +1662015317740866048 +1662015317782866944 +1662015317830867968 +1662015317872868864 +1662015317914869760 +1662015317962870784 +1662015318010871808 +1662015318058872832 +1662015318109873920 +1662015318148874752 +1662015318193875712 +1662015318235876608 +1662015318280877568 +1662015318325878528 +1662015318367879424 +1662015318412880384 +1662015318454881280 +1662015318499882240 +1662015318547883264 +1662015318589884160 +1662015318631885056 +1662015318682886144 +1662015318727887104 +1662015318769888000 +1662015318814888960 +1662015318859889920 +1662015318907890944 +1662015318952891904 +1662015318994892800 +1662015319036893696 +1662015319078894592 +1662015319120895488 +1662015319162896384 +1662015319207897344 +1662015319249898240 +1662015319291899136 +1662015319339900160 +1662015319387901184 +1662015319432902144 +1662015319474903040 +1662015319516903936 +1662015319561904896 +1662015319609905920 +1662015319654906880 +1662015319699907840 +1662015319741908736 +1662015319792909824 +1662015319840910848 +1662015319891911936 +1662015319939912960 +1662015319981913856 +1662015320023914752 +1662015320077915904 +1662015320125916928 +1662015320167917824 +1662015320209918720 +1662015320251919616 +1662015320296920576 +1662015320338921472 +1662015320389922560 +1662015320437923584 +1662015320485924608 +1662015320530925568 +1662015320575926528 +1662015320617927424 +1662015320659928320 +1662015320704929280 +1662015320746930176 +1662015320791931136 +1662015320839932160 +1662015320881933056 +1662015320926934016 +1662015320968934912 +1662015321010935808 +1662015321058936832 +1662015321103937792 +1662015321145938688 +1662015321193939712 +1662015321241940736 +1662015321283941632 +1662015321328942592 +1662015321373943552 +1662015321415944448 +1662015321454945280 +1662015321499946240 +1662015321541947136 +1662015321592948224 +1662015321637949184 +1662015321685950208 +1662015321727951104 +1662015321775952128 +1662015321817953024 +1662015321859953920 +1662015321901954816 +1662015321943955712 +1662015321985956608 +1662015322033957632 +1662015322084958720 +1662015322126959616 +1662015322171960576 +1662015322222961664 +1662015322267962624 +1662015322309963520 +1662015322351964416 +1662015322396965376 +1662015322438966272 +1662015322483967232 +1662015322528968192 +1662015322567969024 +1662015322609969920 +1662015322651970816 +1662015322699971840 +1662015322741972736 +1662015322786973696 +1662015322828974592 +1662015322876975616 +1662015322918976512 +1662015322966977536 +1662015323008978432 +1662015323059979520 +1662015323101980416 +1662015323143981312 +1662015323188982272 +1662015323230983168 +1662015323272984064 +1662015323314984960 +1662015323359985920 +1662015323404986880 +1662015323455987968 +1662015323494988800 +1662015323542989824 +1662015323584990720 +1662015323629991680 +1662015323671992576 +1662015323713993472 +1662015323755994368 +1662015323803995392 +1662015323848996352 +1662015323896997376 +1662015323938998272 +1662015323980999168 +1662015324026000128 +1662015324071001088 +1662015324113001984 +1662015324164003072 +1662015324206003968 +1662015324251004928 +1662015324293005824 +1662015324338006784 +1662015324386007808 +1662015324431008768 +1662015324473009664 +1662015324515010560 +1662015324560011520 +1662015324605012480 +1662015324653013504 +1662015324695014400 +1662015324740015360 +1662015324785016320 +1662015324827017216 +1662015324875018240 +1662015324917019136 +1662015324965020160 +1662015325013021184 +1662015325055022080 +1662015325100023040 +1662015325145024000 +1662015325190024960 +1662015325232025856 +1662015325274026752 +1662015325322027776 +1662015325367028736 +1662015325412029696 +1662015325457030656 +1662015325505031680 +1662015325547032576 +1662015325592033536 +1662015325634034432 +1662015325676035328 +1662015325718036224 +1662015325760037120 +1662015325805038080 +1662015325847038976 +1662015325889039872 +1662015325934040832 +1662015325985041920 +1662015326036043008 +1662015326084044032 +1662015326126044928 +1662015326177046016 +1662015326225047040 +1662015326276048128 +1662015326321049088 +1662015326363049984 +1662015326408050944 +1662015326453051904 +1662015326495052800 +1662015326537053696 +1662015326582054656 +1662015326627055616 +1662015326681056768 +1662015326723057664 +1662015326771058688 +1662015326813059584 +1662015326855060480 +1662015326897061376 +1662015326942062336 +1662015326987063296 +1662015327029064192 +1662015327074065152 +1662015327116066048 +1662015327161067008 +1662015327203067904 +1662015327245068800 +1662015327290069760 +1662015327335070720 +1662015327380071680 +1662015327419072512 +1662015327464073472 +1662015327509074432 +1662015327554075392 +1662015327596076288 +1662015327644077312 +1662015327686078208 +1662015327731079168 +1662015327776080128 +1662015327818081024 +1662015327863081984 +1662015327905082880 +1662015327950083840 +1662015327992084736 +1662015328034085632 +1662015328076086528 +1662015328118087424 +1662015328163088384 +1662015328205089280 +1662015328247090176 +1662015328292091136 +1662015328334092032 +1662015328376092928 +1662015328418093824 +1662015328457094656 +1662015328499095552 +1662015328544096512 +1662015328589097472 +1662015328634098432 +1662015328682099456 +1662015328724100352 +1662015328775101440 +1662015328820102400 +1662015328868103424 +1662015328907104256 +1662015328955105280 +1662015329012106496 +1662015329066107648 +1662015329108108544 +1662015329153109504 +1662015329198110464 +1662015329243111424 +1662015329288112384 +1662015329336113408 +1662015329378114304 +1662015329423115264 +1662015329468116224 +1662015329513117184 +1662015329555118080 +1662015329597118976 +1662015329639119872 +1662015329681120768 +1662015329726121728 +1662015329771122688 +1662015329816123648 +1662015329861124608 +1662015329906125568 +1662015329948126464 +1662015329996127488 +1662015330044128512 +1662015330086129408 +1662015330134130432 +1662015330185131520 +1662015330227132416 +1662015330272133376 +1662015330320134400 +1662015330368135424 +1662015330413136384 +1662015330458137344 +1662015330506138368 +1662015330548139264 +1662015330596140288 +1662015330638141184 +1662015330683142144 +1662015330725143040 +1662015330770144000 +1662015330815144960 +1662015330857145856 +1662015330914147072 +1662015330959148032 +1662015331010149120 +1662015331049149952 +1662015331094150912 +1662015331136151808 +1662015331178152704 +1662015331223153664 +1662015331265154560 +1662015331310155520 +1662015331355156480 +1662015331397157376 +1662015331442158336 +1662015331487159296 +1662015331529160192 +1662015331571161088 +1662015331619162112 +1662015331667163136 +1662015331709164032 +1662015331751164928 +1662015331796165888 +1662015331847166976 +1662015331895168000 +1662015331940168960 +1662015331994170112 +1662015332039171072 +1662015332081171968 +1662015332123172864 +1662015332165173760 +1662015332213174784 +1662015332255175680 +1662015332300176640 +1662015332342177536 +1662015332384178432 +1662015332432179456 +1662015332477180416 +1662015332525181440 +1662015332567182336 +1662015332609183232 +1662015332654184192 +1662015332699185152 +1662015332747186176 +1662015332792187136 +1662015332837188096 +1662015332885189120 +1662015332930190080 +1662015332972190976 +1662015333017191936 +1662015333065192960 +1662015333107193856 +1662015333149194752 +1662015333191195648 +1662015333242196736 +1662015333293197824 +1662015333335198720 +1662015333380199680 +1662015333422200576 +1662015333470201600 +1662015333515202560 +1662015333557203456 +1662015333602204416 +1662015333647205376 +1662015333689206272 +1662015333734207232 +1662015333776208128 +1662015333821209088 +1662015333863209984 +1662015333905210880 +1662015333947211776 +1662015333992212736 +1662015334037213696 +1662015334082214656 +1662015334124215552 +1662015334169216512 +1662015334214217472 +1662015334259218432 +1662015334301219328 +1662015334343220224 +1662015334385221120 +1662015334427222016 +1662015334472222976 +1662015334520224000 +1662015334559224832 +1662015334604225792 +1662015334649226752 +1662015334694227712 +1662015334739228672 +1662015334781229568 +1662015334826230528 +1662015334874231552 +1662015334925232640 +1662015334967233536 +1662015335018234624 +1662015335063235584 +1662015335111236608 +1662015335153237504 +1662015335195238400 +1662015335240239360 +1662015335285240320 +1662015335330241280 +1662015335369242112 +1662015335423243264 +1662015335465244160 +1662015335507245056 +1662015335552246016 +1662015335597246976 +1662015335639247872 +1662015335690248960 +1662015335735249920 +1662015335774250752 +1662015335822251776 +1662015335864252672 +1662015335909253632 +1662015335957254656 +1662015336005255680 +1662015336047256576 +1662015336101257728 +1662015336149258752 +1662015336191259648 +1662015336233260544 +1662015336275261440 +1662015336317262336 +1662015336365263360 +1662015336407264256 +1662015336449265152 +1662015336497266176 +1662015336536267008 +1662015336581267968 +1662015336626268928 +1662015336671269888 +1662015336716270848 +1662015336767271936 +1662015336812272896 +1662015336857273856 +1662015336902274816 +1662015336950275840 +1662015336992276736 +1662015337034277632 +1662015337076278528 +1662015337118279424 +1662015337163280384 +1662015337208281344 +1662015337250282240 +1662015337295283200 +1662015337343284224 +1662015337385285120 +1662015337427286016 +1662015337469286912 +1662015337517287936 +1662015337568289024 +1662015337610289920 +1662015337652290816 +1662015337694291712 +1662015337733292544 +1662015337778293504 +1662015337826294528 +1662015337871295488 +1662015337913296384 +1662015337958297344 +1662015338000298240 +1662015338042299136 +1662015338087300096 +1662015338135301120 +1662015338177302016 +1662015338219302912 +1662015338258303744 +1662015338300304640 +1662015338345305600 +1662015338396306688 +1662015338438307584 +1662015338474308352 +1662015338519309312 +1662015338561310208 +1662015338606311168 +1662015338645312000 +1662015338687312896 +1662015338732313856 +1662015338774314752 +1662015338816315648 +1662015338858316544 +1662015338900317440 +1662015338942318336 +1662015338984319232 +1662015339026320128 +1662015339068321024 +1662015339113321984 +1662015339161323008 +1662015339206323968 +1662015339248324864 +1662015339296325888 +1662015339338326784 +1662015339380327680 +1662015339422328576 +1662015339467329536 +1662015339509330432 +1662015339551331328 +1662015339596332288 +1662015339641333248 +1662015339686334208 +1662015339728335104 +1662015339770336000 +1662015339809336832 +1662015339857337856 +1662015339902338816 +1662015339944339712 +1662015339986340608 +1662015340028341504 +1662015340079342592 +1662015340121343488 +1662015340163344384 +1662015340205345280 +1662015340259346432 +1662015340301347328 +1662015340346348288 +1662015340388349184 +1662015340433350144 +1662015340475351040 +1662015340520352000 +1662015340565352960 +1662015340613353984 +1662015340655354880 +1662015340697355776 +1662015340745356800 +1662015340793357824 +1662015340835358720 +1662015340874359552 +1662015340919360512 +1662015340964361472 +1662015341006362368 +1662015341051363328 +1662015341093364224 +1662015341141365248 +1662015341183366144 +1662015341225367040 +1662015341270368000 +1662015341312368896 +1662015341354369792 +1662015341399370752 +1662015341438371584 +1662015341480372480 +1662015341525373440 +1662015341570374400 +1662015341615375360 +1662015341663376384 +1662015341705377280 +1662015341750378240 +1662015341798379264 +1662015341840380160 +1662015341882381056 +1662015341930382080 +1662015341969382912 +1662015342011383808 +1662015342053384704 +1662015342095385600 +1662015342140386560 +1662015342185387520 +1662015342230388480 +1662015342278389504 +1662015342326390528 +1662015342371391488 +1662015342416392448 +1662015342458393344 +1662015342500394240 +1662015342539395072 +1662015342581395968 +1662015342632397056 +1662015342674397952 +1662015342716398848 +1662015342764399872 +1662015342803400704 +1662015342845401600 +1662015342884402432 +1662015342926403328 +1662015342968404224 +1662015343013405184 +1662015343055406080 +1662015343097406976 +1662015343148408064 +1662015343193409024 +1662015343238409984 +1662015343286411008 +1662015343331411968 +1662015343373412864 +1662015343418413824 +1662015343466414848 +1662015343511415808 +1662015343553416704 +1662015343595417600 +1662015343637418496 +1662015343685419520 +1662015343727420416 +1662015343772421376 +1662015343823422464 +1662015343865423360 +1662015343907424256 +1662015343952425216 +1662015343997426176 +1662015344039427072 +1662015344084428032 +1662015344129428992 +1662015344177430016 +1662015344219430912 +1662015344264431872 +1662015344315432960 +1662015344357433856 +1662015344405434880 +1662015344447435776 +1662015344495436800 +1662015344537437696 +1662015344585438720 +1662015344627439616 +1662015344672440576 +1662015344717441536 +1662015344759442432 +1662015344810443520 +1662015344855444480 +1662015344894445312 +1662015344939446272 +1662015344987447296 +1662015345029448192 +1662015345074449152 +1662015345119450112 +1662015345161451008 +1662015345206451968 +1662015345248452864 +1662015345296453888 +1662015345338454784 +1662015345380455680 +1662015345428456704 +1662015345476457728 +1662015345521458688 +1662015345560459520 +1662015345608460544 +1662015345656461568 +1662015345695462400 +1662015345737463296 +1662015345779464192 +1662015345824465152 +1662015345866466048 +1662015345914467072 +1662015345956467968 +1662015346001468928 +1662015346052470016 +1662015346094470912 +1662015346136471808 +1662015346184472832 +1662015346229473792 +1662015346277474816 +1662015346322475776 +1662015346364476672 +1662015346406477568 +1662015346448478464 +1662015346490479360 +1662015346535480320 +1662015346577481216 +1662015346622482176 +1662015346661483008 +1662015346706483968 +1662015346748484864 +1662015346790485760 +1662015346835486720 +1662015346883487744 +1662015346922488576 +1662015346964489472 +1662015347009490432 +1662015347051491328 +1662015347093492224 +1662015347138493184 +1662015347180494080 +1662015347222494976 +1662015347270496000 +1662015347315496960 +1662015347354497792 +1662015347396498688 +1662015347438499584 +1662015347483500544 +1662015347525501440 +1662015347567502336 +1662015347609503232 +1662015347663504384 +1662015347705505280 +1662015347750506240 +1662015347798507264 +1662015347840508160 +1662015347885509120 +1662015347933510144 +1662015347975511040 +1662015348017511936 +1662015348062512896 +1662015348107513856 +1662015348155514880 +1662015348197515776 +1662015348239516672 +1662015348284517632 +1662015348332518656 +1662015348377519616 +1662015348419520512 +1662015348464521472 +1662015348509522432 +1662015348557523456 +1662015348602524416 +1662015348644525312 +1662015348683526144 +1662015348725527040 +1662015348770528000 +1662015348812528896 +1662015348854529792 +1662015348899530752 +1662015348944531712 +1662015348992532736 +1662015349034533632 +1662015349076534528 +1662015349121535488 +1662015349163536384 +1662015349205537280 +1662015349247538176 +1662015349292539136 +1662015349343540224 +1662015349391541248 +1662015349433542144 +1662015349475543040 +1662015349517543936 +1662015349562544896 +1662015349604545792 +1662015349649546752 +1662015349694547712 +1662015349739548672 +1662015349781549568 +1662015349826550528 +1662015349865551360 +1662015349907552256 +1662015349949553152 +1662015349994554112 +1662015350045555200 +1662015350090556160 +1662015350135557120 +1662015350177558016 +1662015350219558912 +1662015350255559680 +1662015350297560576 +1662015350339561472 +1662015350387562496 +1662015350438563584 +1662015350480564480 +1662015350522565376 +1662015350564566272 +1662015350606567168 +1662015350651568128 +1662015350693569024 +1662015350738569984 +1662015350786571008 +1662015350831571968 +1662015350873572864 +1662015350918573824 +1662015350963574784 +1662015351005575680 +1662015351050576640 +1662015351095577600 +1662015351140578560 +1662015351182579456 +1662015351224580352 +1662015351269581312 +1662015351314582272 +1662015351359583232 +1662015351398584064 +1662015351443585024 +1662015351488585984 +1662015351530586880 +1662015351575587840 +1662015351626588928 +1662015351668589824 +1662015351716590848 +1662015351767591936 +1662015351809592832 +1662015351857593856 +1662015351905594880 +1662015351950595840 +1662015351992596736 +1662015352037597696 +1662015352082598656 +1662015352127599616 +1662015352166600448 +1662015352214601472 +1662015352256602368 +1662015352298603264 +1662015352340604160 +1662015352373604864 +1662015352412605696 +1662015352454606592 +1662015352499607552 +1662015352544608512 +1662015352592609536 +1662015352637610496 +1662015352679611392 +1662015352724612352 +1662015352769613312 +1662015352814614272 +1662015352859615232 +1662015352901616128 +1662015352949617152 +1662015352994618112 +1662015353036619008 +1662015353081619968 +1662015353126620928 +1662015353174621952 +1662015353219622912 +1662015353264623872 +1662015353309624832 +1662015353351625728 +1662015353396626688 +1662015353438627584 +1662015353483628544 +1662015353525629440 +1662015353564630272 +1662015353606631168 +1662015353648632064 +1662015353690632960 +1662015353738633984 +1662015353780634880 +1662015353822635776 +1662015353861636608 +1662015353909637632 +1662015353954638592 +1662015353993639424 +1662015354035640320 +1662015354083641344 +1662015354122642176 +1662015354164643072 +1662015354209644032 +1662015354251644928 +1662015354299645952 +1662015354341646848 +1662015354380647680 +1662015354425648640 +1662015354470649600 +1662015354512650496 +1662015354554651392 +1662015354599652352 +1662015354647653376 +1662015354689654272 +1662015354731655168 +1662015354779656192 +1662015354824657152 +1662015354863657984 +1662015354911659008 +1662015354953659904 +1662015354992660736 +1662015355037661696 +1662015355085662720 +1662015355130663680 +1662015355172664576 +1662015355217665536 +1662015355259666432 +1662015355301667328 +1662015355343668224 +1662015355388669184 +1662015355433670144 +1662015355475671040 +1662015355520672000 +1662015355565672960 +1662015355604673792 +1662015355649674752 +1662015355691675648 +1662015355739676672 +1662015355781677568 +1662015355823678464 +1662015355865679360 +1662015355907680256 +1662015355949681152 +1662015355997682176 +1662015356042683136 +1662015356087684096 +1662015356129684992 +1662015356174685952 +1662015356216686848 +1662015356261687808 +1662015356303688704 +1662015356351689728 +1662015356399690752 +1662015356441691648 +1662015356480692480 +1662015356522693376 +1662015356564694272 +1662015356612695296 +1662015356654696192 +1662015356699697152 +1662015356741698048 +1662015356783698944 +1662015356828699904 +1662015356864700672 +1662015356906701568 +1662015356951702528 +1662015356993703424 +1662015357035704320 +1662015357083705344 +1662015357128706304 +1662015357170707200 +1662015357212708096 +1662015357254708992 +1662015357293709824 +1662015357338710784 +1662015357383711744 +1662015357428712704 +1662015357482713856 +1662015357524714752 +1662015357566715648 +1662015357611716608 +1662015357659717632 +1662015357704718592 +1662015357746719488 +1662015357794720512 +1662015357836721408 +1662015357884722432 +1662015357929723392 +1662015357971724288 +1662015358013725184 +1662015358058726144 +1662015358103727104 +1662015358145728000 +1662015358187728896 +1662015358241730048 +1662015358280730880 +1662015358325731840 +1662015358367732736 +1662015358409733632 +1662015358451734528 +1662015358493735424 +1662015358544736512 +1662015358586737408 +1662015358631738368 +1662015358676739328 +1662015358718740224 +1662015358763741184 +1662015358811742208 +1662015358853743104 +1662015358895744000 +1662015358943745024 +1662015358988745984 +1662015359036747008 +1662015359078747904 +1662015359123748864 +1662015359165749760 +1662015359207750656 +1662015359246751488 +1662015359294752512 +1662015359336753408 +1662015359381754368 +1662015359423755264 +1662015359462756096 +1662015359504756992 +1662015359546757888 +1662015359588758784 +1662015359630759680 +1662015359675760640 +1662015359714761472 +1662015359756762368 +1662015359798763264 +1662015359843764224 +1662015359888765184 +1662015359927766016 +1662015359969766912 +1662015360011767808 +1662015360053768704 +1662015360098769664 +1662015360143770624 +1662015360185771520 +1662015360230772480 +1662015360275773440 +1662015360320774400 +1662015360371775488 +1662015360413776384 +1662015360452777216 +1662015360503778304 +1662015360542779136 +1662015360590780160 +1662015360635781120 +1662015360680782080 +1662015360722782976 +1662015360767783936 +1662015360812784896 +1662015360863785984 +1662015360905786880 +1662015360947787776 +1662015360989788672 +1662015361037789696 +1662015361079790592 +1662015361121791488 +1662015361169792512 +1662015361214793472 +1662015361259794432 +1662015361301795328 +1662015361346796288 +1662015361394797312 +1662015361436798208 +1662015361478799104 +1662015361520800000 +1662015361571801088 +1662015361613801984 +1662015361658802944 +1662015361700803840 +1662015361751804928 +1662015361793805824 +1662015361838806784 +1662015361880807680 +1662015361922808576 +1662015361967809536 +1662015362012810496 +1662015362054811392 +1662015362099812352 +1662015362144813312 +1662015362189814272 +1662015362234815232 +1662015362279816192 +1662015362321817088 +1662015362363817984 +1662015362408818944 +1662015362444819712 +1662015362480820480 +1662015362522821376 +1662015362567822336 +1662015362612823296 +1662015362654824192 +1662015362702825216 +1662015362744826112 +1662015362792827136 +1662015362840828160 +1662015362885829120 +1662015362927830016 +1662015362969830912 +1662015363014831872 +1662015363056832768 +1662015363098833664 +1662015363140834560 +1662015363185835520 +1662015363230836480 +1662015363269837312 +1662015363311838208 +1662015363353839104 +1662015363401840128 +1662015363446841088 +1662015363494842112 +1662015363536843008 +1662015363581843968 +1662015363623844864 +1662015363665845760 +1662015363716846848 +1662015363758847744 +1662015363800848640 +1662015363842849536 +1662015363884850432 +1662015363926851328 +1662015363971852288 +1662015364016853248 +1662015364061854208 +1662015364106855168 +1662015364151856128 +1662015364196857088 +1662015364241858048 +1662015364283858944 +1662015364325859840 +1662015364370860800 +1662015364421861888 +1662015364469862912 +1662015364508863744 +1662015364556864768 +1662015364601865728 +1662015364643866624 +1662015364685867520 +1662015364730868480 +1662015364778869504 +1662015364823870464 +1662015364865871360 +1662015364904872192 +1662015364946873088 +1662015364991874048 +1662015365042875136 +1662015365087876096 +1662015365129876992 +1662015365177878016 +1662015365225879040 +1662015365267879936 +1662015365315880960 +1662015365357881856 +1662015365399882752 +1662015365441883648 +1662015365483884544 +1662015365525885440 +1662015365570886400 +1662015365612887296 +1662015365657888256 +1662015365696889088 +1662015365741890048 +1662015365783890944 +1662015365828891904 +1662015365870892800 +1662015365915893760 +1662015365960894720 +1662015366002895616 +1662015366050896640 +1662015366092897536 +1662015366137898496 +1662015366179899392 +1662015366224900352 +1662015366266901248 +1662015366314902272 +1662015366359903232 +1662015366407904256 +1662015366449905152 +1662015366503906304 +1662015366545907200 +1662015366590908160 +1662015366635909120 +1662015366680910080 +1662015366722910976 +1662015366773912064 +1662015366818913024 +1662015366863913984 +1662015366914915072 +1662015366959916032 +1662015367004916992 +1662015367046917888 +1662015367091918848 +1662015367145920000 +1662015367190920960 +1662015367232921856 +1662015367274922752 +1662015367319923712 +1662015367364924672 +1662015367409925632 +1662015367451926528 +1662015367496927488 +1662015367538928384 +1662015367583929344 +1662015367628930304 +1662015367667931136 +1662015367712932096 +1662015367757933056 +1662015367799933952 +1662015367841934848 +1662015367880935680 +1662015367922936576 +1662015367970937600 +1662015368012938496 +1662015368054939392 +1662015368099940352 +1662015368144941312 +1662015368183942144 +1662015368228943104 +1662015368273944064 +1662015368315944960 +1662015368360945920 +1662015368402946816 +1662015368453947904 +1662015368495948800 +1662015368537949696 +1662015368579950592 +1662015368627951616 +1662015368672952576 +1662015368723953664 +1662015368768954624 +1662015368816955648 +1662015368861956608 +1662015368900957440 +1662015368948958464 +1662015368990959360 +1662015369035960320 +1662015369077961216 +1662015369119962112 +1662015369158962944 +1662015369200963840 +1662015369242964736 +1662015369284965632 +1662015369329966592 +1662015369377967616 +1662015369419968512 +1662015369461969408 +1662015369509970432 +1662015369560971520 +1662015369602972416 +1662015369641973248 +1662015369686974208 +1662015369725975040 +1662015369770976000 +1662015369809976832 +1662015369854977792 +1662015369896978688 +1662015369935979520 +1662015369977980416 +1662015370022981376 +1662015370064982272 +1662015370103983104 +1662015370151984128 +1662015370196985088 +1662015370238985984 +1662015370280986880 +1662015370322987776 +1662015370373988864 +1662015370415989760 +1662015370457990656 +1662015370502991616 +1662015370547992576 +1662015370592993536 +1662015370640994560 +1662015370682995456 +1662015370724996352 +1662015370775997440 +1662015370820998400 +1662015370862999296 +1662015370908000256 +1662015370950001152 +1662015370995002112 +1662015371040003072 +1662015371085004032 +1662015371133005056 +1662015371172005888 +1662015371214006784 +1662015371256007680 +1662015371298008576 +1662015371340009472 +1662015371385010432 +1662015371430011392 +1662015371478012416 +1662015371526013440 +1662015371571014400 +1662015371616015360 +1662015371661016320 +1662015371703017216 +1662015371742018048 +1662015371781018880 +1662015371826019840 +1662015371865020672 +1662015371913021696 +1662015371958022656 +1662015372003023616 +1662015372045024512 +1662015372087025408 +1662015372129026304 +1662015372177027328 +1662015372216028160 +1662015372258029056 +1662015372303030016 +1662015372345030912 +1662015372384031744 +1662015372438032896 +1662015372483033856 +1662015372525034752 +1662015372570035712 +1662015372615036672 +1662015372660037632 +1662015372702038528 +1662015372747039488 +1662015372792040448 +1662015372834041344 +1662015372876042240 +1662015372915043072 +1662015372960044032 +1662015373005044992 +1662015373047045888 +1662015373089046784 +1662015373134047744 +1662015373179048704 +1662015373227049728 +1662015373278050816 +1662015373323051776 +1662015373368052736 +1662015373416053760 +1662015373464054784 +1662015373512055808 +1662015373557056768 +1662015373590057472 +1662015373635058432 +1662015373677059328 +1662015373722060288 +1662015373770061312 +1662015373812062208 +1662015373854063104 +1662015373896064000 +1662015373941064960 +1662015373986065920 +1662015374028066816 +1662015374070067712 +1662015374112068608 +1662015374157069568 +1662015374199070464 +1662015374244071424 +1662015374292072448 +1662015374334073344 +1662015374373074176 +1662015374415075072 +1662015374460076032 +1662015374511077120 +1662015374553078016 +1662015374595078912 +1662015374643079936 +1662015374697081088 +1662015374742082048 +1662015374784082944 +1662015374823083776 +1662015374868084736 +1662015374913085696 +1662015374958086656 +1662015375003087616 +1662015375045088512 +1662015375087089408 +1662015375129090304 +1662015375180091392 +1662015375225092352 +1662015375276093440 +1662015375315094272 +1662015375360095232 +1662015375402096128 +1662015375453097216 +1662015375498098176 +1662015375549099264 +1662015375591100160 +1662015375636101120 +1662015375678102016 +1662015375720102912 +1662015375765103872 +1662015375813104896 +1662015375858105856 +1662015375903106816 +1662015375948107776 +1662015375996108800 +1662015376038109696 +1662015376080110592 +1662015376119111424 +1662015376167112448 +1662015376209113344 +1662015376257114368 +1662015376305115392 +1662015376347116288 +1662015376392117248 +1662015376434118144 +1662015376479119104 +1662015376524120064 +1662015376569121024 +1662015376614121984 +1662015376656122880 +1662015376707123968 +1662015376752124928 +1662015376803126016 +1662015376848126976 +1662015376893127936 +1662015376938128896 +1662015376980129792 +1662015377028130816 +1662015377073131776 +1662015377115132672 +1662015377154133504 +1662015377196134400 +1662015377238135296 +1662015377286136320 +1662015377337137408 +1662015377379138304 +1662015377424139264 +1662015377466140160 +1662015377514141184 +1662015377556142080 +1662015377604143104 +1662015377649144064 +1662015377694145024 +1662015377739145984 +1662015377781146880 +1662015377823147776 +1662015377868148736 +1662015377907149568 +1662015377949150464 +1662015377991151360 +1662015378036152320 +1662015378081153280 +1662015378120154112 +1662015378165155072 +1662015378207155968 +1662015378249156864 +1662015378285157632 +1662015378327158528 +1662015378366159360 +1662015378408160256 +1662015378456161280 +1662015378495162112 +1662015378546163200 +1662015378591164160 +1662015378636165120 +1662015378684166144 +1662015378726167040 +1662015378768167936 +1662015378813168896 +1662015378855169792 +1662015378894170624 +1662015378936171520 +1662015378978172416 +1662015379023173376 +1662015379065174272 +1662015379107175168 +1662015379149176064 +1662015379194177024 +1662015379236177920 +1662015379278178816 +1662015379323179776 +1662015379365180672 +1662015379419181824 +1662015379461182720 +1662015379500183552 +1662015379542184448 +1662015379584185344 +1662015379629186304 +1662015379680187392 +1662015379722188288 +1662015379767189248 +1662015379812190208 +1662015379854191104 +1662015379896192000 +1662015379941192960 +1662015379989193984 +1662015380037195008 +1662015380082195968 +1662015380130196992 +1662015380175197952 +1662015380220198912 +1662015380265199872 +1662015380313200896 +1662015380355201792 +1662015380397202688 +1662015380439203584 +1662015380481204480 +1662015380526205440 +1662015380568206336 +1662015380616207360 +1662015380658208256 +1662015380706209280 +1662015380760210432 +1662015380805211392 +1662015380853212416 +1662015380895213312 +1662015380937214208 +1662015380982215168 +1662015381027216128 +1662015381078217216 +1662015381120218112 +1662015381162219008 +1662015381204219904 +1662015381246220800 +1662015381288221696 +1662015381333222656 +1662015381378223616 +1662015381423224576 +1662015381468225536 +1662015381513226496 +1662015381558227456 +1662015381600228352 +1662015381639229184 +1662015381681230080 +1662015381723230976 +1662015381768231936 +1662015381816232960 +1662015381861233920 +1662015381903234816 +1662015381945235712 +1662015381990236672 +1662015382038237696 +1662015382086238720 +1662015382134239744 +1662015382182240768 +1662015382230241792 +1662015382278242816 +1662015382323243776 +1662015382365244672 +1662015382407245568 +1662015382458246656 +1662015382500247552 +1662015382545248512 +1662015382581249280 +1662015382623250176 +1662015382662251008 +1662015382713252096 +1662015382755252992 +1662015382797253888 +1662015382839254784 +1662015382878255616 +1662015382923256576 +1662015382965257472 +1662015383007258368 +1662015383052259328 +1662015383097260288 +1662015383145261312 +1662015383193262336 +1662015383238263296 +1662015383277264128 +1662015383319265024 +1662015383364265984 +1662015383409266944 +1662015383454267904 +1662015383496268800 +1662015383541269760 +1662015383583270656 +1662015383631271680 +1662015383676272640 +1662015383718273536 +1662015383763274496 +1662015383808275456 +1662015383850276352 +1662015383892277248 +1662015383934278144 +1662015383985279232 +1662015384024280064 +1662015384066280960 +1662015384108281856 +1662015384153282816 +1662015384198283776 +1662015384246284800 +1662015384288285696 +1662015384336286720 +1662015384381287680 +1662015384423288576 +1662015384465289472 +1662015384507290368 +1662015384558291456 +1662015384603292416 +1662015384642293248 +1662015384687294208 +1662015384732295168 +1662015384789296384 +1662015384831297280 +1662015384879298304 +1662015384921299200 +1662015384963300096 +1662015385005300992 +1662015385047301888 +1662015385089302784 +1662015385131303680 +1662015385176304640 +1662015385218305536 +1662015385263306496 +1662015385305307392 +1662015385347308288 +1662015385392309248 +1662015385434310144 +1662015385476311040 +1662015385518311936 +1662015385563312896 +1662015385608313856 +1662015385653314816 +1662015385710316032 +1662015385755316992 +1662015385797317888 +1662015385839318784 +1662015385884319744 +1662015385929320704 +1662015385974321664 +1662015386022322688 +1662015386061323520 +1662015386103324416 +1662015386145325312 +1662015386187326208 +1662015386229327104 +1662015386274328064 +1662015386322329088 +1662015386370330112 +1662015386412331008 +1662015386457331968 +1662015386502332928 +1662015386547333888 +1662015386595334912 +1662015386637335808 +1662015386688336896 +1662015386733337856 +1662015386778338816 +1662015386820339712 +1662015386868340736 +1662015386916341760 +1662015386961342720 +1662015387003343616 +1662015387048344576 +1662015387093345536 +1662015387141346560 +1662015387186347520 +1662015387228348416 +1662015387282349568 +1662015387330350592 +1662015387366351360 +1662015387408352256 +1662015387447353088 +1662015387489353984 +1662015387534354944 +1662015387579355904 +1662015387627356928 +1662015387669357824 +1662015387714358784 +1662015387759359744 +1662015387804360704 +1662015387858361856 +1662015387900362752 +1662015387945363712 +1662015387987364608 +1662015388029365504 +1662015388071366400 +1662015388119367424 +1662015388164368384 +1662015388209369344 +1662015388251370240 +1662015388293371136 +1662015388332371968 +1662015388374372864 +1662015388419373824 +1662015388464374784 +1662015388506375680 +1662015388548376576 +1662015388593377536 +1662015388644378624 +1662015388689379584 +1662015388731380480 +1662015388776381440 +1662015388818382336 +1662015388860383232 +1662015388905384192 +1662015388944385024 +1662015388992386048 +1662015389040387072 +1662015389082387968 +1662015389124388864 +1662015389163389696 +1662015389205390592 +1662015389247391488 +1662015389295392512 +1662015389337393408 +1662015389382394368 +1662015389424395264 +1662015389466396160 +1662015389508397056 +1662015389556398080 +1662015389598398976 +1662015389643399936 +1662015389682400768 +1662015389724401664 +1662015389766402560 +1662015389814403584 +1662015389859404544 +1662015389904405504 +1662015389940406272 +1662015389979407104 +1662015390021408000 +1662015390072409088 +1662015390120410112 +1662015390162411008 +1662015390210412032 +1662015390255412992 +1662015390300413952 +1662015390342414848 +1662015390384415744 +1662015390429416704 +1662015390468417536 +1662015390510418432 +1662015390555419392 +1662015390597420288 +1662015390639421184 +1662015390684422144 +1662015390726423040 +1662015390771424000 +1662015390813424896 +1662015390855425792 +1662015390897426688 +1662015390936427520 +1662015390978428416 +1662015391020429312 +1662015391062430208 +1662015391104431104 +1662015391152432128 +1662015391194433024 +1662015391236433920 +1662015391278434816 +1662015391326435840 +1662015391371436800 +1662015391416437760 +1662015391461438720 +1662015391503439616 +1662015391545440512 +1662015391587441408 +1662015391632442368 +1662015391677443328 +1662015391722444288 +1662015391764445184 +1662015391806446080 +1662015391848446976 +1662015391890447872 +1662015391932448768 +1662015391974449664 +1662015392019450624 +1662015392070451712 +1662015392112452608 +1662015392160453632 +1662015392202454528 +1662015392247455488 +1662015392289456384 +1662015392334457344 +1662015392379458304 +1662015392424459264 +1662015392469460224 +1662015392520461312 +1662015392562462208 +1662015392607463168 +1662015392652464128 +1662015392694465024 +1662015392739465984 +1662015392784466944 +1662015392829467904 +1662015392877468928 +1662015392916469760 +1662015392955470592 +1662015392997471488 +1662015393054472704 +1662015393102473728 +1662015393147474688 +1662015393192475648 +1662015393240476672 +1662015393282477568 +1662015393324478464 +1662015393372479488 +1662015393423480576 +1662015393468481536 +1662015393510482432 +1662015393552483328 +1662015393597484288 +1662015393642485248 +1662015393690486272 +1662015393732487168 +1662015393771488000 +1662015393819489024 +1662015393864489984 +1662015393906490880 +1662015393948491776 +1662015393993492736 +1662015394038493696 +1662015394089494784 +1662015394131495680 +1662015394173496576 +1662015394218497536 +1662015394260498432 +1662015394302499328 +1662015394347500288 +1662015394392501248 +1662015394434502144 +1662015394479503104 +1662015394521504000 +1662015394566504960 +1662015394608505856 +1662015394653506816 +1662015394698507776 +1662015394746508800 +1662015394788509696 +1662015394833510656 +1662015394878511616 +1662015394923512576 +1662015394965513472 +1662015395010514432 +1662015395061515520 +1662015395097516288 +1662015395139517184 +1662015395181518080 +1662015395223518976 +1662015395274520064 +1662015395316520960 +1662015395367522048 +1662015395409522944 +1662015395454523904 +1662015395499524864 +1662015395550525952 +1662015395589526784 +1662015395631527680 +1662015395679528704 +1662015395724529664 +1662015395766530560 +1662015395814531584 +1662015395856532480 +1662015395898533376 +1662015395943534336 +1662015395991535360 +1662015396036536320 +1662015396078537216 +1662015396126538240 +1662015396168539136 +1662015396216540160 +1662015396264541184 +1662015396309542144 +1662015396357543168 +1662015396399544064 +1662015396447545088 +1662015396492546048 +1662015396540547072 +1662015396582547968 +1662015396627548928 +1662015396675549952 +1662015396720550912 +1662015396765551872 +1662015396807552768 +1662015396852553728 +1662015396894554624 +1662015396939555584 +1662015396987556608 +1662015397020557312 +1662015397068558336 +1662015397116559360 +1662015397161560320 +1662015397203561216 +1662015397248562176 +1662015397287563008 +1662015397332563968 +1662015397377564928 +1662015397416565760 +1662015397458566656 +1662015397503567616 +1662015397545568512 +1662015397584569344 +1662015397632570368 +1662015397677571328 +1662015397722572288 +1662015397767573248 +1662015397815574272 +1662015397860575232 +1662015397905576192 +1662015397953577216 +1662015397995578112 +1662015398040579072 +1662015398085580032 +1662015398130580992 +1662015398172581888 +1662015398217582848 +1662015398259583744 +1662015398301584640 +1662015398349585664 +1662015398391586560 +1662015398436587520 +1662015398481588480 +1662015398523589376 +1662015398568590336 +1662015398613591296 +1662015398655592192 +1662015398700593152 +1662015398742594048 +1662015398793595136 +1662015398835596032 +1662015398883597056 +1662015398928598016 +1662015398967598848 +1662015399009599744 +1662015399054600704 +1662015399102601728 +1662015399150602752 +1662015399198603776 +1662015399240604672 +1662015399282605568 +1662015399330606592 +1662015399375607552 +1662015399423608576 +1662015399465609472 +1662015399507610368 +1662015399552611328 +1662015399591612160 +1662015399636613120 +1662015399678614016 +1662015399723614976 +1662015399765615872 +1662015399819617024 +1662015399867618048 +1662015399921619200 +1662015399960620032 +1662015400005620992 +1662015400050621952 +1662015400098622976 +1662015400140623872 +1662015400182624768 +1662015400227625728 +1662015400272626688 +1662015400311627520 +1662015400353628416 +1662015400404629504 +1662015400446630400 +1662015400488631296 +1662015400530632192 +1662015400575633152 +1662015400617634048 +1662015400665635072 +1662015400710636032 +1662015400752636928 diff --git a/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_track2.txt b/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_track2.txt new file mode 100644 index 0000000000..c35350d63a --- /dev/null +++ b/Examples/Stereo/MIMIR_TimeStamps/SeaFloor_track2.txt @@ -0,0 +1,2537 @@ +1662122091767260928 +1662122091809261824 +1662122091851262720 +1662122091893263616 +1662122091935264512 +1662122091980265472 +1662122092022266368 +1662122092064267264 +1662122092106268160 +1662122092148269056 +1662122092193270016 +1662122092232270848 +1662122092280271872 +1662122092322272768 +1662122092364273664 +1662122092412274688 +1662122092454275584 +1662122092493276416 +1662122092535277312 +1662122092580278272 +1662122092625279232 +1662122092667280128 +1662122092709281024 +1662122092751281920 +1662122092796282880 +1662122092847283968 +1662122092889284864 +1662122092931285760 +1662122092970286592 +1662122093015287552 +1662122093060288512 +1662122093105289472 +1662122093153290496 +1662122093201291520 +1662122093240292352 +1662122093282293248 +1662122093324294144 +1662122093366295040 +1662122093408295936 +1662122093453296896 +1662122093501297920 +1662122093543298816 +1662122093591299840 +1662122093633300736 +1662122093675301632 +1662122093723302656 +1662122093768303616 +1662122093810304512 +1662122093855305472 +1662122093894306304 +1662122093939307264 +1662122093981308160 +1662122094023309056 +1662122094065309952 +1662122094110310912 +1662122094146311680 +1662122094191312640 +1662122094227313408 +1662122094275314432 +1662122094317315328 +1662122094359316224 +1662122094395316992 +1662122094437317888 +1662122094482318848 +1662122094524319744 +1662122094566320640 +1662122094611321600 +1662122094653322496 +1662122094695323392 +1662122094740324352 +1662122094782325248 +1662122094824326144 +1662122094872327168 +1662122094917328128 +1662122094965329152 +1662122095007330048 +1662122095052331008 +1662122095094331904 +1662122095139332864 +1662122095181333760 +1662122095220334592 +1662122095265335552 +1662122095316336640 +1662122095358337536 +1662122095406338560 +1662122095454339584 +1662122095496340480 +1662122095541341440 +1662122095586342400 +1662122095625343232 +1662122095667344128 +1662122095709345024 +1662122095751345920 +1662122095793346816 +1662122095835347712 +1662122095874348544 +1662122095916349440 +1662122095958350336 +1662122096000351232 +1662122096045352192 +1662122096084353024 +1662122096120353792 +1662122096162354688 +1662122096204355584 +1662122096243356416 +1662122096279357184 +1662122096327358208 +1662122096375359232 +1662122096417360128 +1662122096453360896 +1662122096495361792 +1662122096540362752 +1662122096585363712 +1662122096627364608 +1662122096669365504 +1662122096717366528 +1662122096759367424 +1662122096801368320 +1662122096843369216 +1662122096885370112 +1662122096924370944 +1662122096966371840 +1662122097005372672 +1662122097047373568 +1662122097089374464 +1662122097134375424 +1662122097179376384 +1662122097221377280 +1662122097263378176 +1662122097305379072 +1662122097347379968 +1662122097395380992 +1662122097437381888 +1662122097479382784 +1662122097521383680 +1662122097563384576 +1662122097605385472 +1662122097656386560 +1662122097704387584 +1662122097743388416 +1662122097785389312 +1662122097836390400 +1662122097881391360 +1662122097923392256 +1662122097968393216 +1662122098010394112 +1662122098052395008 +1662122098094395904 +1662122098136396800 +1662122098178397696 +1662122098226398720 +1662122098271399680 +1662122098316400640 +1662122098358401536 +1662122098397402368 +1662122098439403264 +1662122098481404160 +1662122098529405184 +1662122098577406208 +1662122098628407296 +1662122098670408192 +1662122098712409088 +1662122098757410048 +1662122098796410880 +1662122098841411840 +1662122098883412736 +1662122098922413568 +1662122098970414592 +1662122099012415488 +1662122099054416384 +1662122099096417280 +1662122099141418240 +1662122099183419136 +1662122099222419968 +1662122099267420928 +1662122099315421952 +1662122099360422912 +1662122099405423872 +1662122099450424832 +1662122099498425856 +1662122099537426688 +1662122099585427712 +1662122099624428544 +1662122099669429504 +1662122099711430400 +1662122099753431296 +1662122099798432256 +1662122099843433216 +1662122099888434176 +1662122099933435136 +1662122099969435904 +1662122100014436864 +1662122100056437760 +1662122100101438720 +1662122100146439680 +1662122100197440768 +1662122100236441600 +1662122100281442560 +1662122100323443456 +1662122100365444352 +1662122100410445312 +1662122100449446144 +1662122100494447104 +1662122100536448000 +1662122100578448896 +1662122100617449728 +1662122100659450624 +1662122100701451520 +1662122100743452416 +1662122100785453312 +1662122100824454144 +1662122100866455040 +1662122100908455936 +1662122100950456832 +1662122100992457728 +1662122101037458688 +1662122101079459584 +1662122101124460544 +1662122101160461312 +1662122101205462272 +1662122101244463104 +1662122101298464256 +1662122101340465152 +1662122101379465984 +1662122101421466880 +1662122101466467840 +1662122101514468864 +1662122101556469760 +1662122101601470720 +1662122101649471744 +1662122101694472704 +1662122101733473536 +1662122101784474624 +1662122101826475520 +1662122101865476352 +1662122101904477184 +1662122101949478144 +1662122101997479168 +1662122102042480128 +1662122102090481152 +1662122102129481984 +1662122102171482880 +1662122102213483776 +1662122102255484672 +1662122102297485568 +1662122102342486528 +1662122102384487424 +1662122102423488256 +1662122102465489152 +1662122102507490048 +1662122102546490880 +1662122102588491776 +1662122102627492608 +1662122102663493376 +1662122102705494272 +1662122102747495168 +1662122102789496064 +1662122102834497024 +1662122102876497920 +1662122102918498816 +1662122102960499712 +1662122103005500672 +1662122103044501504 +1662122103089502464 +1662122103131503360 +1662122103176504320 +1662122103221505280 +1662122103263506176 +1662122103308507136 +1662122103350508032 +1662122103392508928 +1662122103437509888 +1662122103479510784 +1662122103515511552 +1662122103557512448 +1662122103593513216 +1662122103635514112 +1662122103680515072 +1662122103725516032 +1662122103767516928 +1662122103809517824 +1662122103845518592 +1662122103887519488 +1662122103932520448 +1662122103974521344 +1662122104019522304 +1662122104061523200 +1662122104106524160 +1662122104148525056 +1662122104184525824 +1662122104223526656 +1662122104268527616 +1662122104310528512 +1662122104355529472 +1662122104397530368 +1662122104439531264 +1662122104478532096 +1662122104520532992 +1662122104562533888 +1662122104604534784 +1662122104646535680 +1662122104688536576 +1662122104730537472 +1662122104772538368 +1662122104814539264 +1662122104859540224 +1662122104904541184 +1662122104949542144 +1662122104988542976 +1662122105027543808 +1662122105072544768 +1662122105114545664 +1662122105159546624 +1662122105201547520 +1662122105243548416 +1662122105285549312 +1662122105327550208 +1662122105366551040 +1662122105408551936 +1662122105450552832 +1662122105489553664 +1662122105531554560 +1662122105573555456 +1662122105615556352 +1662122105657557248 +1662122105699558144 +1662122105747559168 +1662122105789560064 +1662122105834561024 +1662122105882562048 +1662122105924562944 +1662122105969563904 +1662122106008564736 +1662122106053565696 +1662122106092566528 +1662122106134567424 +1662122106173568256 +1662122106215569152 +1662122106251569920 +1662122106290570752 +1662122106326571520 +1662122106374572544 +1662122106416573440 +1662122106461574400 +1662122106506575360 +1662122106548576256 +1662122106584577024 +1662122106626577920 +1662122106665578752 +1662122106707579648 +1662122106752580608 +1662122106794581504 +1662122106836582400 +1662122106881583360 +1662122106923584256 +1662122106965585152 +1662122107007586048 +1662122107055587072 +1662122107097587968 +1662122107136588800 +1662122107172589568 +1662122107214590464 +1662122107259591424 +1662122107307592448 +1662122107349593344 +1662122107394594304 +1662122107433595136 +1662122107472595968 +1662122107517596928 +1662122107556597760 +1662122107598598656 +1662122107643599616 +1662122107682600448 +1662122107724601344 +1662122107769602304 +1662122107814603264 +1662122107862604288 +1662122107904605184 +1662122107949606144 +1662122107991607040 +1662122108030607872 +1662122108075608832 +1662122108117609728 +1662122108159610624 +1662122108207611648 +1662122108249612544 +1662122108291613440 +1662122108339614464 +1662122108387615488 +1662122108429616384 +1662122108471617280 +1662122108516618240 +1662122108558619136 +1662122108600620032 +1662122108642620928 +1662122108687621888 +1662122108729622784 +1662122108774623744 +1662122108816624640 +1662122108861625600 +1662122108909626624 +1662122108951627520 +1662122108990628352 +1662122109035629312 +1662122109083630336 +1662122109125631232 +1662122109164632064 +1662122109206632960 +1662122109245633792 +1662122109287634688 +1662122109332635648 +1662122109368636416 +1662122109410637312 +1662122109452638208 +1662122109491639040 +1662122109539640064 +1662122109587641088 +1662122109635642112 +1662122109674642944 +1662122109716643840 +1662122109761644800 +1662122109803645696 +1662122109845646592 +1662122109887647488 +1662122109929648384 +1662122109968649216 +1662122110010650112 +1662122110055651072 +1662122110097651968 +1662122110136652800 +1662122110178653696 +1662122110220654592 +1662122110265655552 +1662122110307656448 +1662122110352657408 +1662122110394658304 +1662122110436659200 +1662122110481660160 +1662122110526661120 +1662122110571662080 +1662122110613662976 +1662122110661664000 +1662122110703664896 +1662122110748665856 +1662122110793666816 +1662122110835667712 +1662122110880668672 +1662122110919669504 +1662122110970670592 +1662122111012671488 +1662122111054672384 +1662122111093673216 +1662122111138674176 +1662122111186675200 +1662122111225676032 +1662122111267676928 +1662122111309677824 +1662122111351678720 +1662122111393679616 +1662122111435680512 +1662122111477681408 +1662122111522682368 +1662122111570683392 +1662122111615684352 +1662122111657685248 +1662122111702686208 +1662122111747687168 +1662122111789688064 +1662122111834689024 +1662122111876689920 +1662122111918690816 +1662122111963691776 +1662122112005692672 +1662122112047693568 +1662122112089694464 +1662122112134695424 +1662122112182696448 +1662122112224697344 +1662122112266698240 +1662122112308699136 +1662122112353700096 +1662122112395700992 +1662122112434701824 +1662122112476702720 +1662122112521703680 +1662122112572704768 +1662122112617705728 +1662122112656706560 +1662122112698707456 +1662122112746708480 +1662122112788709376 +1662122112833710336 +1662122112875711232 +1662122112914712064 +1662122112953712896 +1662122112998713856 +1662122113037714688 +1662122113079715584 +1662122113118716416 +1662122113154717184 +1662122113196718080 +1662122113235718912 +1662122113277719808 +1662122113319720704 +1662122113355721472 +1662122113400722432 +1662122113448723456 +1662122113487724288 +1662122113529725184 +1662122113571726080 +1662122113613726976 +1662122113655727872 +1662122113700728832 +1662122113742729728 +1662122113784730624 +1662122113826731520 +1662122113871732480 +1662122113913733376 +1662122113958734336 +1662122114006735360 +1662122114048736256 +1662122114090737152 +1662122114132738048 +1662122114177739008 +1662122114222739968 +1662122114264740864 +1662122114309741824 +1662122114354742784 +1662122114396743680 +1662122114438744576 +1662122114489745664 +1662122114534746624 +1662122114579747584 +1662122114627748608 +1662122114669749504 +1662122114708750336 +1662122114750751232 +1662122114792752128 +1662122114837753088 +1662122114882754048 +1662122114921754880 +1662122114966755840 +1662122115008756736 +1662122115059757824 +1662122115110758912 +1662122115149759744 +1662122115194760704 +1662122115236761600 +1662122115278762496 +1662122115320763392 +1662122115365764352 +1662122115404765184 +1662122115446766080 +1662122115491767040 +1662122115533767936 +1662122115575768832 +1662122115620769792 +1662122115662770688 +1662122115707771648 +1662122115749772544 +1662122115788773376 +1662122115830774272 +1662122115875775232 +1662122115917776128 +1662122115959777024 +1662122115998777856 +1662122116043778816 +1662122116088779776 +1662122116136780800 +1662122116175781632 +1662122116217782528 +1662122116265783552 +1662122116307784448 +1662122116352785408 +1662122116394786304 +1662122116430787072 +1662122116475788032 +1662122116517788928 +1662122116562789888 +1662122116604790784 +1662122116643791616 +1662122116685792512 +1662122116727793408 +1662122116769794304 +1662122116811795200 +1662122116856796160 +1662122116901797120 +1662122116943798016 +1662122116985798912 +1662122117033799936 +1662122117075800832 +1662122117114801664 +1662122117153802496 +1662122117192803328 +1662122117240804352 +1662122117282805248 +1662122117324806144 +1662122117363806976 +1662122117408807936 +1662122117450808832 +1662122117495809792 +1662122117540810752 +1662122117582811648 +1662122117627812608 +1662122117669813504 +1662122117711814400 +1662122117759815424 +1662122117798816256 +1662122117846817280 +1662122117888818176 +1662122117933819136 +1662122117978820096 +1662122118023821056 +1662122118068822016 +1662122118113822976 +1662122118161824000 +1662122118206824960 +1662122118248825856 +1662122118287826688 +1662122118332827648 +1662122118374828544 +1662122118416829440 +1662122118461830400 +1662122118503831296 +1662122118548832256 +1662122118593833216 +1662122118638834176 +1662122118680835072 +1662122118722835968 +1662122118764836864 +1662122118806837760 +1662122118848838656 +1662122118890839552 +1662122118935840512 +1662122118977841408 +1662122119019842304 +1662122119061843200 +1662122119100844032 +1662122119145844992 +1662122119187845888 +1662122119226846720 +1662122119271847680 +1662122119319848704 +1662122119364849664 +1662122119403850496 +1662122119442851328 +1662122119484852224 +1662122119526853120 +1662122119571854080 +1662122119613854976 +1662122119652855808 +1662122119697856768 +1662122119739857664 +1662122119778858496 +1662122119823859456 +1662122119874860544 +1662122119922861568 +1662122119964862464 +1662122120009863424 +1662122120054864384 +1662122120096865280 +1662122120138866176 +1662122120180867072 +1662122120222867968 +1662122120270868992 +1662122120315869952 +1662122120360870912 +1662122120405871872 +1662122120450872832 +1662122120486873600 +1662122120525874432 +1662122120567875328 +1662122120609876224 +1662122120648877056 +1662122120690877952 +1662122120732878848 +1662122120777879808 +1662122120819880704 +1662122120858881536 +1662122120903882496 +1662122120948883456 +1662122120987884288 +1662122121023885056 +1662122121068886016 +1662122121110886912 +1662122121152887808 +1662122121194888704 +1662122121239889664 +1662122121281890560 +1662122121320891392 +1662122121365892352 +1662122121407893248 +1662122121449894144 +1662122121491895040 +1662122121536896000 +1662122121581896960 +1662122121626897920 +1662122121668898816 +1662122121710899712 +1662122121752900608 +1662122121797901568 +1662122121836902400 +1662122121878903296 +1662122121923904256 +1662122121968905216 +1662122122007906048 +1662122122049906944 +1662122122091907840 +1662122122136908800 +1662122122178909696 +1662122122223910656 +1662122122265911552 +1662122122307912448 +1662122122349913344 +1662122122394914304 +1662122122436915200 +1662122122481916160 +1662122122520916992 +1662122122568918016 +1662122122616919040 +1662122122661920000 +1662122122703920896 +1662122122745921792 +1662122122790922752 +1662122122832923648 +1662122122874924544 +1662122122913925376 +1662122122955926272 +1662122123000927232 +1662122123042928128 +1662122123087929088 +1662122123132930048 +1662122123171930880 +1662122123210931712 +1662122123249932544 +1662122123288933376 +1662122123330934272 +1662122123372935168 +1662122123414936064 +1662122123456936960 +1662122123498937856 +1662122123540938752 +1662122123579939584 +1662122123621940480 +1662122123663941376 +1662122123708942336 +1662122123753943296 +1662122123795944192 +1662122123837945088 +1662122123879945984 +1662122123918946816 +1662122123960947712 +1662122124005948672 +1662122124047949568 +1662122124092950528 +1662122124134951424 +1662122124179952384 +1662122124224953344 +1662122124266954240 +1662122124311955200 +1662122124359956224 +1662122124398957056 +1662122124440957952 +1662122124482958848 +1662122124530959872 +1662122124572960768 +1662122124617961728 +1662122124659962624 +1662122124701963520 +1662122124743964416 +1662122124788965376 +1662122124833966336 +1662122124878967296 +1662122124923968256 +1662122124968969216 +1662122125013970176 +1662122125058971136 +1662122125097971968 +1662122125139972864 +1662122125181973760 +1662122125226974720 +1662122125271975680 +1662122125310976512 +1662122125361977600 +1662122125400978432 +1662122125445979392 +1662122125493980416 +1662122125535981312 +1662122125583982336 +1662122125625983232 +1662122125670984192 +1662122125709985024 +1662122125751985920 +1662122125793986816 +1662122125835987712 +1662122125874988544 +1662122125916989440 +1662122125961990400 +1662122126003991296 +1662122126045992192 +1662122126087993088 +1662122126129993984 +1662122126171994880 +1662122126219995904 +1662122126264996864 +1662122126303997696 +1662122126351998720 +1662122126393999616 +1662122126436000512 +1662122126478001408 +1662122126523002368 +1662122126565003264 +1662122126601004032 +1662122126640004864 +1662122126685005824 +1662122126727006720 +1662122126769007616 +1662122126808008448 +1662122126850009344 +1662122126895010304 +1662122126940011264 +1662122126985012224 +1662122127021012992 +1662122127063013888 +1662122127105014784 +1662122127144015616 +1662122127189016576 +1662122127231017472 +1662122127273018368 +1662122127315019264 +1662122127363020288 +1662122127408021248 +1662122127462022400 +1662122127507023360 +1662122127549024256 +1662122127594025216 +1662122127639026176 +1662122127681027072 +1662122127729028096 +1662122127783029248 +1662122127828030208 +1662122127867031040 +1662122127909031936 +1662122127954032896 +1662122127999033856 +1662122128044034816 +1662122128086035712 +1662122128125036544 +1662122128170037504 +1662122128212038400 +1662122128257039360 +1662122128302040320 +1662122128347041280 +1662122128389042176 +1662122128440043264 +1662122128479044096 +1662122128518044928 +1662122128557045760 +1662122128599046656 +1662122128644047616 +1662122128689048576 +1662122128737049600 +1662122128776050432 +1662122128824051456 +1662122128866052352 +1662122128908053248 +1662122128950054144 +1662122128992055040 +1662122129034055936 +1662122129073056768 +1662122129115057664 +1662122129160058624 +1662122129208059648 +1662122129247060480 +1662122129295061504 +1662122129340062464 +1662122129382063360 +1662122129427064320 +1662122129472065280 +1662122129517066240 +1662122129559067136 +1662122129601068032 +1662122129640068864 +1662122129679069696 +1662122129727070720 +1662122129766071552 +1662122129808072448 +1662122129844073216 +1662122129889074176 +1662122129934075136 +1662122129976076032 +1662122130021076992 +1662122130066077952 +1662122130114078976 +1662122130159079936 +1662122130198080768 +1662122130240081664 +1662122130282082560 +1662122130330083584 +1662122130369084416 +1662122130414085376 +1662122130456086272 +1662122130498087168 +1662122130540088064 +1662122130582088960 +1662122130624089856 +1662122130669090816 +1662122130711091712 +1662122130753092608 +1662122130798093568 +1662122130840094464 +1662122130885095424 +1662122130927096320 +1662122130969097216 +1662122131011098112 +1662122131056099072 +1662122131095099904 +1662122131137100800 +1662122131182101760 +1662122131227102720 +1662122131263103488 +1662122131305104384 +1662122131350105344 +1662122131395106304 +1662122131437107200 +1662122131482108160 +1662122131527109120 +1662122131566109952 +1662122131605110784 +1662122131647111680 +1662122131689112576 +1662122131737113600 +1662122131776114432 +1662122131821115392 +1662122131863116288 +1662122131905117184 +1662122131947118080 +1662122131989118976 +1662122132028119808 +1662122132073120768 +1662122132115121664 +1662122132154122496 +1662122132205123584 +1662122132247124480 +1662122132286125312 +1662122132325126144 +1662122132370127104 +1662122132409127936 +1662122132454128896 +1662122132502129920 +1662122132541130752 +1662122132583131648 +1662122132628132608 +1662122132670133504 +1662122132712134400 +1662122132754135296 +1662122132799136256 +1662122132838137088 +1662122132877137920 +1662122132919138816 +1662122132964139776 +1662122133006140672 +1662122133051141632 +1662122133093142528 +1662122133135143424 +1662122133180144384 +1662122133225145344 +1662122133267146240 +1662122133309147136 +1662122133351148032 +1662122133393148928 +1662122133438149888 +1662122133480150784 +1662122133525151744 +1662122133567152640 +1662122133609153536 +1662122133654154496 +1662122133696155392 +1662122133744156416 +1662122133786157312 +1662122133831158272 +1662122133876159232 +1662122133921160192 +1662122133966161152 +1662122134011162112 +1662122134059163136 +1662122134101164032 +1662122134143164928 +1662122134188165888 +1662122134233166848 +1662122134281167872 +1662122134326168832 +1662122134368169728 +1662122134410170624 +1662122134452171520 +1662122134500172544 +1662122134539173376 +1662122134584174336 +1662122134626175232 +1662122134668176128 +1662122134710177024 +1662122134755177984 +1662122134797178880 +1662122134839179776 +1662122134887180800 +1662122134932181760 +1662122134971182592 +1662122135013183488 +1662122135052184320 +1662122135094185216 +1662122135133186048 +1662122135175186944 +1662122135217187840 +1662122135262188800 +1662122135310189824 +1662122135355190784 +1662122135400191744 +1662122135442192640 +1662122135487193600 +1662122135526194432 +1662122135571195392 +1662122135613196288 +1662122135652197120 +1662122135697198080 +1662122135736198912 +1662122135781199872 +1662122135823200768 +1662122135868201728 +1662122135907202560 +1662122135952203520 +1662122135994204416 +1662122136039205376 +1662122136081206272 +1662122136123207168 +1662122136168208128 +1662122136207208960 +1662122136252209920 +1662122136297210880 +1662122136342211840 +1662122136381212672 +1662122136426213632 +1662122136471214592 +1662122136516215552 +1662122136561216512 +1662122136600217344 +1662122136642218240 +1662122136684219136 +1662122136726220032 +1662122136771220992 +1662122136813221888 +1662122136861222912 +1662122136903223808 +1662122136951224832 +1662122136993225728 +1662122137035226624 +1662122137083227648 +1662122137125228544 +1662122137167229440 +1662122137209230336 +1662122137254231296 +1662122137290232064 +1662122137335233024 +1662122137371233792 +1662122137416234752 +1662122137461235712 +1662122137503236608 +1662122137551237632 +1662122137596238592 +1662122137641239552 +1662122137683240448 +1662122137728241408 +1662122137770242304 +1662122137815243264 +1662122137857244160 +1662122137902245120 +1662122137950246144 +1662122137998247168 +1662122138037248000 +1662122138082248960 +1662122138127249920 +1662122138169250816 +1662122138214251776 +1662122138265252864 +1662122138307253760 +1662122138349254656 +1662122138391255552 +1662122138433256448 +1662122138478257408 +1662122138520258304 +1662122138565259264 +1662122138610260224 +1662122138652261120 +1662122138688261888 +1662122138730262784 +1662122138772263680 +1662122138817264640 +1662122138862265600 +1662122138901266432 +1662122138940267264 +1662122138991268352 +1662122139030269184 +1662122139072270080 +1662122139117271040 +1662122139159271936 +1662122139201272832 +1662122139240273664 +1662122139282274560 +1662122139327275520 +1662122139369276416 +1662122139411277312 +1662122139450278144 +1662122139492279040 +1662122139534279936 +1662122139579280896 +1662122139621281792 +1662122139660282624 +1662122139702283520 +1662122139747284480 +1662122139792285440 +1662122139837286400 +1662122139879287296 +1662122139921288192 +1662122139963289088 +1662122140002289920 +1662122140044290816 +1662122140089291776 +1662122140128292608 +1662122140170293504 +1662122140209294336 +1662122140251295232 +1662122140296296192 +1662122140338297088 +1662122140383298048 +1662122140428299008 +1662122140470299904 +1662122140512300800 +1662122140560301824 +1662122140611302912 +1662122140659303936 +1662122140704304896 +1662122140746305792 +1662122140791306752 +1662122140833307648 +1662122140872308480 +1662122140914309376 +1662122140959310336 +1662122141004311296 +1662122141049312256 +1662122141094313216 +1662122141136314112 +1662122141178315008 +1662122141223315968 +1662122141268316928 +1662122141313317888 +1662122141352318720 +1662122141394319616 +1662122141436320512 +1662122141478321408 +1662122141523322368 +1662122141565323264 +1662122141610324224 +1662122141658325248 +1662122141706326272 +1662122141742327040 +1662122141790328064 +1662122141832328960 +1662122141871329792 +1662122141916330752 +1662122141961331712 +1662122142006332672 +1662122142045333504 +1662122142087334400 +1662122142129335296 +1662122142174336256 +1662122142216337152 +1662122142261338112 +1662122142303339008 +1662122142351340032 +1662122142393340928 +1662122142435341824 +1662122142480342784 +1662122142522343680 +1662122142561344512 +1662122142603345408 +1662122142648346368 +1662122142693347328 +1662122142735348224 +1662122142783349248 +1662122142825350144 +1662122142867351040 +1662122142915352064 +1662122142960353024 +1662122143002353920 +1662122143041354752 +1662122143086355712 +1662122143131356672 +1662122143173357568 +1662122143215358464 +1662122143260359424 +1662122143299360256 +1662122143341361152 +1662122143383362048 +1662122143425362944 +1662122143467363840 +1662122143512364800 +1662122143563365888 +1662122143605366784 +1662122143644367616 +1662122143683368448 +1662122143725369344 +1662122143767370240 +1662122143812371200 +1662122143854372096 +1662122143893372928 +1662122143935373824 +1662122143980374784 +1662122144022375680 +1662122144064376576 +1662122144112377600 +1662122144154378496 +1662122144199379456 +1662122144247380480 +1662122144289381376 +1662122144331382272 +1662122144373383168 +1662122144418384128 +1662122144454384896 +1662122144499385856 +1662122144541386752 +1662122144583387648 +1662122144628388608 +1662122144664389376 +1662122144709390336 +1662122144754391296 +1662122144793392128 +1662122144838393088 +1662122144883394048 +1662122144925394944 +1662122144973395968 +1662122145021396992 +1662122145063397888 +1662122145105398784 +1662122145144399616 +1662122145189400576 +1662122145231401472 +1662122145270402304 +1662122145315403264 +1662122145360404224 +1662122145408405248 +1662122145459406336 +1662122145504407296 +1662122145546408192 +1662122145588409088 +1662122145633410048 +1662122145678411008 +1662122145720411904 +1662122145765412864 +1662122145813413888 +1662122145855414784 +1662122145903415808 +1662122145948416768 +1662122145987417600 +1662122146032418560 +1662122146074419456 +1662122146122420480 +1662122146167421440 +1662122146212422400 +1662122146257423360 +1662122146302424320 +1662122146344425216 +1662122146389426176 +1662122146434427136 +1662122146476428032 +1662122146521428992 +1662122146563429888 +1662122146605430784 +1662122146647431680 +1662122146689432576 +1662122146734433536 +1662122146779434496 +1662122146821435392 +1662122146863436288 +1662122146908437248 +1662122146950438144 +1662122146992439040 +1662122147034439936 +1662122147070440704 +1662122147112441600 +1662122147163442688 +1662122147205443584 +1662122147244444416 +1662122147289445376 +1662122147331446272 +1662122147373447168 +1662122147415448064 +1662122147454448896 +1662122147496449792 +1662122147541450752 +1662122147583451648 +1662122147625452544 +1662122147670453504 +1662122147712454400 +1662122147754455296 +1662122147796456192 +1662122147838457088 +1662122147886458112 +1662122147931459072 +1662122147973459968 +1662122148018460928 +1662122148063461888 +1662122148105462784 +1662122148150463744 +1662122148192464640 +1662122148240465664 +1662122148279466496 +1662122148321467392 +1662122148366468352 +1662122148408469248 +1662122148447470080 +1662122148492471040 +1662122148534471936 +1662122148576472832 +1662122148621473792 +1662122148663474688 +1662122148705475584 +1662122148747476480 +1662122148792477440 +1662122148837478400 +1662122148882479360 +1662122148930480384 +1662122148972481280 +1662122149014482176 +1662122149059483136 +1662122149104484096 +1662122149146484992 +1662122149191485952 +1662122149233486848 +1662122149281487872 +1662122149323488768 +1662122149365489664 +1662122149407490560 +1662122149449491456 +1662122149491492352 +1662122149536493312 +1662122149575494144 +1662122149617495040 +1662122149659495936 +1662122149704496896 +1662122149746497792 +1662122149788498688 +1662122149830499584 +1662122149872500480 +1662122149914501376 +1662122149956502272 +1662122150001503232 +1662122150043504128 +1662122150088505088 +1662122150127505920 +1662122150169506816 +1662122150208507648 +1662122150250508544 +1662122150292509440 +1662122150334510336 +1662122150379511296 +1662122150421512192 +1662122150463513088 +1662122150511514112 +1662122150553515008 +1662122150592515840 +1662122150634516736 +1662122150679517696 +1662122150721518592 +1662122150763519488 +1662122150805520384 +1662122150847521280 +1662122150895522304 +1662122150940523264 +1662122150988524288 +1662122151033525248 +1662122151078526208 +1662122151123527168 +1662122151165528064 +1662122151210529024 +1662122151252529920 +1662122151297530880 +1662122151342531840 +1662122151384532736 +1662122151423533568 +1662122151465534464 +1662122151513535488 +1662122151561536512 +1662122151603537408 +1662122151648538368 +1662122151690539264 +1662122151735540224 +1662122151777541120 +1662122151819542016 +1662122151858542848 +1662122151903543808 +1662122151942544640 +1662122151987545600 +1662122152035546624 +1662122152077547520 +1662122152119548416 +1662122152164549376 +1662122152209550336 +1662122152254551296 +1662122152293552128 +1662122152335553024 +1662122152374553856 +1662122152416554752 +1662122152455555584 +1662122152497556480 +1662122152548557568 +1662122152587558400 +1662122152632559360 +1662122152674560256 +1662122152725561344 +1662122152770562304 +1662122152815563264 +1662122152857564160 +1662122152902565120 +1662122152941565952 +1662122152986566912 +1662122153028567808 +1662122153073568768 +1662122153115569664 +1662122153157570560 +1662122153199571456 +1662122153244572416 +1662122153286573312 +1662122153331574272 +1662122153376575232 +1662122153418576128 +1662122153463577088 +1662122153505577984 +1662122153550578944 +1662122153586579712 +1662122153637580800 +1662122153679581696 +1662122153721582592 +1662122153760583424 +1662122153805584384 +1662122153853585408 +1662122153901586432 +1662122153943587328 +1662122153982588160 +1662122154021588992 +1662122154063589888 +1662122154111590912 +1662122154153591808 +1662122154198592768 +1662122154243593728 +1662122154285594624 +1662122154324595456 +1662122154369596416 +1662122154411597312 +1662122154447598080 +1662122154489598976 +1662122154534599936 +1662122154579600896 +1662122154624601856 +1662122154666602752 +1662122154708603648 +1662122154750604544 +1662122154795605504 +1662122154837606400 +1662122154879607296 +1662122154924608256 +1662122154972609280 +1662122155014610176 +1662122155056611072 +1662122155095611904 +1662122155137612800 +1662122155179613696 +1662122155221614592 +1662122155260615424 +1662122155305616384 +1662122155347617280 +1662122155389618176 +1662122155434619136 +1662122155479620096 +1662122155524621056 +1662122155569622016 +1662122155611622912 +1662122155650623744 +1662122155695624704 +1662122155737625600 +1662122155779626496 +1662122155824627456 +1662122155866628352 +1662122155914629376 +1662122155953630208 +1662122155995631104 +1662122156043632128 +1662122156088633088 +1662122156130633984 +1662122156172634880 +1662122156214635776 +1662122156259636736 +1662122156307637760 +1662122156349638656 +1662122156397639680 +1662122156436640512 +1662122156481641472 +1662122156535642624 +1662122156574643456 +1662122156619644416 +1662122156667645440 +1662122156709646336 +1662122156751647232 +1662122156799648256 +1662122156841649152 +1662122156883650048 +1662122156928651008 +1662122156973651968 +1662122157015652864 +1662122157057653760 +1662122157102654720 +1662122157144655616 +1662122157183656448 +1662122157231657472 +1662122157273658368 +1662122157315659264 +1662122157363660288 +1662122157408661248 +1662122157450662144 +1662122157498663168 +1662122157537664000 +1662122157576664832 +1662122157618665728 +1662122157663666688 +1662122157705667584 +1662122157747668480 +1662122157789669376 +1662122157837670400 +1662122157882671360 +1662122157924672256 +1662122157966673152 +1662122158014674176 +1662122158062675200 +1662122158101676032 +1662122158149677056 +1662122158191677952 +1662122158236678912 +1662122158275679744 +1662122158317680640 +1662122158353681408 +1662122158395682304 +1662122158440683264 +1662122158482684160 +1662122158524685056 +1662122158572686080 +1662122158617687040 +1662122158662688000 +1662122158704688896 +1662122158746689792 +1662122158791690752 +1662122158830691584 +1662122158872692480 +1662122158911693312 +1662122158953694208 +1662122158998695168 +1662122159043696128 +1662122159085697024 +1662122159127697920 +1662122159163698688 +1662122159205699584 +1662122159247700480 +1662122159292701440 +1662122159337702400 +1662122159382703360 +1662122159421704192 +1662122159463705088 +1662122159502705920 +1662122159550706944 +1662122159589707776 +1662122159634708736 +1662122159673709568 +1662122159727710720 +1662122159766711552 +1662122159808712448 +1662122159850713344 +1662122159895714304 +1662122159940715264 +1662122159982716160 +1662122160021716992 +1662122160063717888 +1662122160108718848 +1662122160153719808 +1662122160201720832 +1662122160240721664 +1662122160282722560 +1662122160324723456 +1662122160366724352 +1662122160408725248 +1662122160456726272 +1662122160501727232 +1662122160546728192 +1662122160588729088 +1662122160636730112 +1662122160684731136 +1662122160732732160 +1662122160774733056 +1662122160816733952 +1662122160861734912 +1662122160903735808 +1662122160942736640 +1662122160984737536 +1662122161026738432 +1662122161068739328 +1662122161113740288 +1662122161158741248 +1662122161203742208 +1662122161245743104 +1662122161287744000 +1662122161332744960 +1662122161377745920 +1662122161419746816 +1662122161461747712 +1662122161503748608 +1662122161545749504 +1662122161593750528 +1662122161635751424 +1662122161680752384 +1662122161722753280 +1662122161764754176 +1662122161806755072 +1662122161845755904 +1662122161884756736 +1662122161926757632 +1662122161974758656 +1662122162016759552 +1662122162052760320 +1662122162091761152 +1662122162133762048 +1662122162178763008 +1662122162223763968 +1662122162265764864 +1662122162313765888 +1662122162355766784 +1662122162397767680 +1662122162439768576 +1662122162484769536 +1662122162523770368 +1662122162565771264 +1662122162607772160 +1662122162652773120 +1662122162694774016 +1662122162733774848 +1662122162778775808 +1662122162823776768 +1662122162868777728 +1662122162910778624 +1662122162949779456 +1662122162991780352 +1662122163039781376 +1662122163084782336 +1662122163126783232 +1662122163168784128 +1662122163213785088 +1662122163258786048 +1662122163297786880 +1662122163339787776 +1662122163378788608 +1662122163420789504 +1662122163456790272 +1662122163504791296 +1662122163549792256 +1662122163591793152 +1662122163633794048 +1662122163675794944 +1662122163717795840 +1662122163762796800 +1662122163804797696 +1662122163849798656 +1662122163888799488 +1662122163930800384 +1662122163972801280 +1662122164011802112 +1662122164050802944 +1662122164092803840 +1662122164134804736 +1662122164176805632 +1662122164221806592 +1662122164263807488 +1662122164305808384 +1662122164347809280 +1662122164392810240 +1662122164431811072 +1662122164470811904 +1662122164512812800 +1662122164548813568 +1662122164593814528 +1662122164635815424 +1662122164677816320 +1662122164719817216 +1662122164764818176 +1662122164812819200 +1662122164857820160 +1662122164893820928 +1662122164938821888 +1662122164980822784 +1662122165025823744 +1662122165070824704 +1662122165112825600 +1662122165157826560 +1662122165202827520 +1662122165244828416 +1662122165283829248 +1662122165325830144 +1662122165367831040 +1662122165412832000 +1662122165454832896 +1662122165499833856 +1662122165544834816 +1662122165586835712 +1662122165628836608 +1662122165670837504 +1662122165715838464 +1662122165760839424 +1662122165805840384 +1662122165853841408 +1662122165895842304 +1662122165934843136 +1662122165979844096 +1662122166021844992 +1662122166063845888 +1662122166105846784 +1662122166147847680 +1662122166189848576 +1662122166231849472 +1662122166276850432 +1662122166321851392 +1662122166360852224 +1662122166405853184 +1662122166450854144 +1662122166492855040 +1662122166531855872 +1662122166570856704 +1662122166615857664 +1662122166657858560 +1662122166702859520 +1662122166744860416 +1662122166786861312 +1662122166831862272 +1662122166876863232 +1662122166912864000 +1662122166951864832 +1662122166993865728 +1662122167035866624 +1662122167077867520 +1662122167116868352 +1662122167161869312 +1662122167206870272 +1662122167248871168 +1662122167296872192 +1662122167344873216 +1662122167386874112 +1662122167428875008 +1662122167470875904 +1662122167515876864 +1662122167560877824 +1662122167599878656 +1662122167638879488 +1662122167680880384 +1662122167722881280 +1662122167767882240 +1662122167815883264 +1662122167857884160 +1662122167899885056 +1662122167944886016 +1662122167989886976 +1662122168034887936 +1662122168079888896 +1662122168121889792 +1662122168163890688 +1662122168211891712 +1662122168253892608 +1662122168298893568 +1662122168331894272 +1662122168373895168 +1662122168415896064 +1662122168460897024 +1662122168502897920 +1662122168544898816 +1662122168586899712 +1662122168631900672 +1662122168670901504 +1662122168721902592 +1662122168763903488 +1662122168808904448 +1662122168850905344 +1662122168892906240 +1662122168931907072 +1662122168970907904 +1662122169012908800 +1662122169057909760 +1662122169096910592 +1662122169138911488 +1662122169180912384 +1662122169219913216 +1662122169264914176 +1662122169306915072 +1662122169354916096 +1662122169393916928 +1662122169438917888 +1662122169483918848 +1662122169522919680 +1662122169567920640 +1662122169609921536 +1662122169657922560 +1662122169702923520 +1662122169744924416 +1662122169786925312 +1662122169828926208 +1662122169870927104 +1662122169912928000 +1662122169957928960 +1662122169999929856 +1662122170041930752 +1662122170089931776 +1662122170128932608 +1662122170170933504 +1662122170209934336 +1662122170254935296 +1662122170296936192 +1662122170341937152 +1662122170389938176 +1662122170434939136 +1662122170476940032 +1662122170521940992 +1662122170563941888 +1662122170611942912 +1662122170659943936 +1662122170707944960 +1662122170749945856 +1662122170794946816 +1662122170839947776 +1662122170881948672 +1662122170920949504 +1662122170965950464 +1662122171016951552 +1662122171061952512 +1662122171106953472 +1662122171148954368 +1662122171193955328 +1662122171235956224 +1662122171280957184 +1662122171322958080 +1662122171364958976 +1662122171406959872 +1662122171451960832 +1662122171493961728 +1662122171541962752 +1662122171583963648 +1662122171625964544 +1662122171667965440 +1662122171715966464 +1662122171763967488 +1662122171805968384 +1662122171847969280 +1662122171892970240 +1662122171940971264 +1662122171982972160 +1662122172024973056 +1662122172066973952 +1662122172111974912 +1662122172153975808 +1662122172195976704 +1662122172237977600 +1662122172279978496 +1662122172318979328 +1662122172357980160 +1662122172402981120 +1662122172444982016 +1662122172489982976 +1662122172531983872 +1662122172576984832 +1662122172618985728 +1662122172663986688 +1662122172705987584 +1662122172750988544 +1662122172795989504 +1662122172837990400 +1662122172882991360 +1662122172924992256 +1662122172966993152 +1662122173011994112 +1662122173053995008 +1662122173095995904 +1662122173134996736 +1662122173185997824 +1662122173227998720 +1662122173275999744 +1662122173318000640 +1662122173363001600 +1662122173405002496 +1662122173447003392 +1662122173492004352 +1662122173537005312 +1662122173582006272 +1662122173627007232 +1662122173672008192 +1662122173717009152 +1662122173759010048 +1662122173804011008 +1662122173849011968 +1662122173894012928 +1662122173939013888 +1662122173981014784 +1662122174023015680 +1662122174065016576 +1662122174107017472 +1662122174149018368 +1662122174194019328 +1662122174236020224 +1662122174284021248 +1662122174329022208 +1662122174371023104 +1662122174416024064 +1662122174461025024 +1662122174503025920 +1662122174545026816 +1662122174593027840 +1662122174638028800 +1662122174680029696 +1662122174722030592 +1662122174764031488 +1662122174800032256 +1662122174845033216 +1662122174887034112 +1662122174926034944 +1662122174968035840 +1662122175007036672 +1662122175049037568 +1662122175091038464 +1662122175136039424 +1662122175175040256 +1662122175220041216 +1662122175262042112 +1662122175307043072 +1662122175352044032 +1662122175394044928 +1662122175442045952 +1662122175484046848 +1662122175535047936 +1662122175577048832 +1662122175625049856 +1662122175667050752 +1662122175712051712 +1662122175754052608 +1662122175799053568 +1662122175841054464 +1662122175883055360 +1662122175925056256 +1662122175973057280 +1662122176015058176 +1662122176057059072 +1662122176102060032 +1662122176144060928 +1662122176189061888 +1662122176231062784 +1662122176273063680 +1662122176312064512 +1662122176354065408 +1662122176396066304 +1662122176432067072 +1662122176474067968 +1662122176516068864 +1662122176558069760 +1662122176600070656 +1662122176636071424 +1662122176681072384 +1662122176726073344 +1662122176768074240 +1662122176816075264 +1662122176858076160 +1662122176900077056 +1662122176948078080 +1662122176990078976 +1662122177032079872 +1662122177077080832 +1662122177119081728 +1662122177161082624 +1662122177203083520 +1662122177245084416 +1662122177287085312 +1662122177332086272 +1662122177374087168 +1662122177416088064 +1662122177461089024 +1662122177506089984 +1662122177554091008 +1662122177596091904 +1662122177635092736 +1662122177680093696 +1662122177725094656 +1662122177770095616 +1662122177815096576 +1662122177860097536 +1662122177905098496 +1662122177947099392 +1662122177986100224 +1662122178028101120 +1662122178070102016 +1662122178112102912 +1662122178154103808 +1662122178202104832 +1662122178241105664 +1662122178280106496 +1662122178325107456 +1662122178370108416 +1662122178415109376 +1662122178454110208 +1662122178502111232 +1662122178547112192 +1662122178589113088 +1662122178634114048 +1662122178679115008 +1662122178724115968 +1662122178766116864 +1662122178814117888 +1662122178859118848 +1662122178910119936 +1662122178955120896 +1662122179003121920 +1662122179051122944 +1662122179096123904 +1662122179138124800 +1662122179180125696 +1662122179228126720 +1662122179267127552 +1662122179312128512 +1662122179363129600 +1662122179405130496 +1662122179450131456 +1662122179498132480 +1662122179540133376 +1662122179579134208 +1662122179624135168 +1662122179666136064 +1662122179711137024 +1662122179753137920 +1662122179798138880 +1662122179840139776 +1662122179885140736 +1662122179930141696 +1662122179972142592 +1662122180014143488 +1662122180056144384 +1662122180098145280 +1662122180137146112 +1662122180176146944 +1662122180227148032 +1662122180269148928 +1662122180314149888 +1662122180356150784 +1662122180395151616 +1662122180437152512 +1662122180479153408 +1662122180521154304 +1662122180566155264 +1662122180608156160 +1662122180653157120 +1662122180695158016 +1662122180734158848 +1662122180776159744 +1662122180821160704 +1662122180863161600 +1662122180908162560 +1662122180956163584 +1662122181001164544 +1662122181049165568 +1662122181091166464 +1662122181133167360 +1662122181172168192 +1662122181217169152 +1662122181262170112 +1662122181310171136 +1662122181355172096 +1662122181400173056 +1662122181442173952 +1662122181484174848 +1662122181526175744 +1662122181571176704 +1662122181613177600 +1662122181652178432 +1662122181694179328 +1662122181736180224 +1662122181772180992 +1662122181817181952 +1662122181862182912 +1662122181907183872 +1662122181949184768 +1662122181994185728 +1662122182042186752 +1662122182081187584 +1662122182117188352 +1662122182159189248 +1662122182198190080 +1662122182243191040 +1662122182285191936 +1662122182327192832 +1662122182369193728 +1662122182411194624 +1662122182456195584 +1662122182498196480 +1662122182540197376 +1662122182582198272 +1662122182624199168 +1662122182666200064 +1662122182708200960 +1662122182750201856 +1662122182795202816 +1662122182837203712 +1662122182882204672 +1662122182927205632 +1662122182969206528 +1662122183011207424 +1662122183059208448 +1662122183098209280 +1662122183137210112 +1662122183182211072 +1662122183224211968 +1662122183269212928 +1662122183308213760 +1662122183353214720 +1662122183395215616 +1662122183437216512 +1662122183476217344 +1662122183515218176 +1662122183557219072 +1662122183599219968 +1662122183641220864 +1662122183689221888 +1662122183731222784 +1662122183776223744 +1662122183821224704 +1662122183863225600 +1662122183908226560 +1662122183947227392 +1662122183989228288 +1662122184034229248 +1662122184076230144 +1662122184121231104 +1662122184163232000 +1662122184202232832 +1662122184247233792 +1662122184292234752 +1662122184334235648 +1662122184376236544 +1662122184421237504 +1662122184463238400 +1662122184508239360 +1662122184553240320 +1662122184595241216 +1662122184637242112 +1662122184679243008 +1662122184721243904 +1662122184763244800 +1662122184808245760 +1662122184850246656 +1662122184892247552 +1662122184934248448 +1662122184976249344 +1662122185015250176 +1662122185057251072 +1662122185099251968 +1662122185144252928 +1662122185192253952 +1662122185234254848 +1662122185276255744 +1662122185321256704 +1662122185366257664 +1662122185411258624 +1662122185450259456 +1662122185492260352 +1662122185531261184 +1662122185579262208 +1662122185627263232 +1662122185672264192 +1662122185717265152 +1662122185759266048 +1662122185807267072 +1662122185849267968 +1662122185888268800 +1662122185930269696 +1662122185966270464 +1662122186011271424 +1662122186053272320 +1662122186095273216 +1662122186137274112 +1662122186173274880 +1662122186218275840 +1662122186260276736 +1662122186299277568 +1662122186341278464 +1662122186383279360 +1662122186428280320 +1662122186473281280 +1662122186515282176 +1662122186563283200 +1662122186614284288 +1662122186656285184 +1662122186701286144 +1662122186746287104 +1662122186788288000 +1662122186833288960 +1662122186878289920 +1662122186917290752 +1662122186962291712 +1662122187004292608 +1662122187049293568 +1662122187088294400 +1662122187130295296 +1662122187175296256 +1662122187220297216 +1662122187262298112 +1662122187301298944 +1662122187343299840 +1662122187382300672 +1662122187424301568 +1662122187463302400 +1662122187505303296 +1662122187544304128 +1662122187586305024 +1662122187631305984 +1662122187673306880 +1662122187715307776 +1662122187757308672 +1662122187802309632 +1662122187844310528 +1662122187889311488 +1662122187934312448 +1662122187979313408 +1662122188024314368 +1662122188063315200 +1662122188111316224 +1662122188153317120 +1662122188201318144 +1662122188243319040 +1662122188294320128 +1662122188336321024 +1662122188378321920 +1662122188423322880 +1662122188465323776 +1662122188504324608 +1662122188549325568 +1662122188591326464 +1662122188636327424 +1662122188681328384 +1662122188723329280 +1662122188768330240 +1662122188813331200 +1662122188858332160 +1662122188906333184 +1662122188951334144 +1662122188996335104 +1662122189041336064 +1662122189086337024 +1662122189128337920 +1662122189173338880 +1662122189221339904 +1662122189263340800 +1662122189305341696 +1662122189350342656 +1662122189395343616 +1662122189431344384 +1662122189476345344 +1662122189518346240 +1662122189560347136 +1662122189605348096 +1662122189647348992 +1662122189692349952 +1662122189737350912 +1662122189782351872 +1662122189827352832 +1662122189872353792 +1662122189917354752 +1662122189962355712 +1662122190007356672 +1662122190052357632 +1662122190097358592 +1662122190139359488 +1662122190181360384 +1662122190220361216 +1662122190265362176 +1662122190307363072 +1662122190352364032 +1662122190397364992 +1662122190436365824 +1662122190475366656 +1662122190520367616 +1662122190565368576 +1662122190613369600 +1662122190661370624 +1662122190700371456 +1662122190742372352 +1662122190787373312 +1662122190829374208 +1662122190874375168 +1662122190916376064 +1662122190964377088 +1662122191006377984 +1662122191048378880 +1662122191099379968 +1662122191141380864 +1662122191186381824 +1662122191228382720 +1662122191276383744 +1662122191318384640 +1662122191360385536 +1662122191405386496 +1662122191444387328 +1662122191489388288 +1662122191531389184 +1662122191570390016 +1662122191609390848 +1662122191651391744 +1662122191690392576 +1662122191732393472 +1662122191774394368 +1662122191813395200 +1662122191855396096 +1662122191897396992 +1662122191936397824 +1662122191978398720 +1662122192020399616 +1662122192062400512 +1662122192101401344 +1662122192143402240 +1662122192185403136 +1662122192227404032 +1662122192269404928 +1662122192311405824 +1662122192350406656 +1662122192395407616 +1662122192437408512 +1662122192476409344 +1662122192518410240 +1662122192563411200 +1662122192608412160 +1662122192650413056 +1662122192695414016 +1662122192740414976 +1662122192782415872 +1662122192824416768 +1662122192869417728 +1662122192914418688 +1662122192956419584 +1662122193001420544 +1662122193040421376 +1662122193082422272 +1662122193127423232 +1662122193166424064 +1662122193208424960 +1662122193247425792 +1662122193289426688 +1662122193331427584 +1662122193370428416 +1662122193415429376 +1662122193454430208 +1662122193499431168 +1662122193541432064 +1662122193589433088 +1662122193631433984 +1662122193676434944 +1662122193721435904 +1662122193763436800 +1662122193808437760 +1662122193850438656 +1662122193889439488 +1662122193934440448 +1662122193976441344 +1662122194018442240 +1662122194057443072 +1662122194093443840 +1662122194135444736 +1662122194186445824 +1662122194231446784 +1662122194270447616 +1662122194309448448 +1662122194348449280 +1662122194390450176 +1662122194432451072 +1662122194471451904 +1662122194513452800 +1662122194558453760 +1662122194603454720 +1662122194645455616 +1662122194690456576 +1662122194729457408 +1662122194777458432 +1662122194819459328 +1662122194864460288 +1662122194906461184 +1662122194954462208 +1662122194999463168 +1662122195044464128 +1662122195089465088 +1662122195131465984 +1662122195179467008 +1662122195224467968 +1662122195266468864 +1662122195308469760 +1662122195353470720 +1662122195395471616 +1662122195443472640 +1662122195488473600 +1662122195533474560 +1662122195572475392 +1662122195614476288 +1662122195656477184 +1662122195698478080 +1662122195740478976 +1662122195782479872 +1662122195821480704 +1662122195866481664 +1662122195908482560 +1662122195953483520 +1662122195992484352 +1662122196037485312 +1662122196082486272 +1662122196127487232 +1662122196169488128 +1662122196211489024 +1662122196253489920 +1662122196292490752 +1662122196334491648 +1662122196373492480 +1662122196415493376 +1662122196454494208 +1662122196496495104 +1662122196538496000 +1662122196580496896 +1662122196622497792 +1662122196667498752 +1662122196709499648 +1662122196748500480 +1662122196793501440 +1662122196838502400 +1662122196880503296 +1662122196922504192 +1662122196967505152 +1662122197015506176 +1662122197057507072 +1662122197099507968 +1662122197138508800 +1662122197180509696 +1662122197222510592 +1662122197264511488 +1662122197309512448 +1662122197351513344 +1662122197393514240 +1662122197441515264 +1662122197483516160 +1662122197528517120 +1662122197570518016 +1662122197621519104 +1662122197663520000 +1662122197705520896 +1662122197747521792 +1662122197789522688 +1662122197834523648 +1662122197879524608 +1662122197921525504 +1662122197963526400 +1662122198005527296 +1662122198044528128 +1662122198086529024 +1662122198131529984 +1662122198176530944 +1662122198218531840 +1662122198263532800 +1662122198302533632 +1662122198347534592 +1662122198395535616 +1662122198434536448 +1662122198482537472 +1662122198521538304 +1662122198563539200 +1662122198605540096 +1662122198644540928 +1662122198680541696 +1662122198722542592 +1662122198767543552 +1662122198806544384 +1662122198851545344 +1662122198890546176 +1662122198938547200 +1662122198986548224 +1662122199025549056 +1662122199064549888 +1662122199103550720 +1662122199145551616 +1662122199193552640 +1662122199241553664 +1662122199283554560 +1662122199331555584 +1662122199376556544 +1662122199415557376 +1662122199463558400 +1662122199508559360 +1662122199553560320 +1662122199601561344 +1662122199640562176 +1662122199682563072 +1662122199727564032 +1662122199769564928 +1662122199814565888 +1662122199862566912 +1662122199904567808 +1662122199943568640 +1662122199994569728 +1662122200033570560 +1662122200078571520 +1662122200120572416 +1662122200159573248 +1662122200204574208 +1662122200240574976 +1662122200285575936 +1662122200330576896 +1662122200369577728 +1662122200420578816 +1662122200459579648 +1662122200498580480 +1662122200540581376 +1662122200582582272 +1662122200621583104 +1662122200666584064 +1662122200708584960 +1662122200753585920 +1662122200795586816 +1662122200834587648 +1662122200876588544 +1662122200918589440 diff --git a/Examples/Stereo/stereo_mimir.cc b/Examples/Stereo/stereo_mimir.cc new file mode 100644 index 0000000000..1c16e2e53e --- /dev/null +++ b/Examples/Stereo/stereo_mimir.cc @@ -0,0 +1,212 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + +#include +#include +#include +#include +#include + +#include + +#include + +using namespace std; + +void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes, + vector &vstrImageLeft, vector &vstrImageRight, vector &vTimeStamps); + +int main(int argc, char **argv) +{ + if(argc < 5) + { + cerr << endl << "Usage: ./stereo_euroc path_to_vocabulary path_to_settings path_to_sequence_folder_1 path_to_times_file_1 (path_to_image_folder_2 path_to_times_file_2 ... path_to_image_folder_N path_to_times_file_N) (trajectory_file_name)" << endl; + cerr << endl << "Example: ./Examples/Monocular/stereo_mimir /home/olaya/dev/ORB_SLAM3/Vocabulary/ORBvoc.txt /home/olaya/dev/ORB_SLAM3/Examples/Stereo/MIMIR.yaml /home/olaya/Datasets/MIMIR/SeaFloor/track0 /home/olaya/Datasets/MIMIR/SeaFloor/track0/auv0/ORB_timestamps.txt /home/olaya/Datasets/MIMIR/SeaFloor/track0 /home/olaya/Datasets/MIMIR/SeaFloor/track0/auv0/ORB_timestamps.txt seafloor_track1.txt" << endl; + return 1; + } + + const int num_seq = (argc-3)/2; + cout << "num_seq = " << num_seq << endl; + bool bFileName= (((argc-3) % 2) == 1); + string file_name; + if (bFileName) + { + file_name = string(argv[argc-1]); + cout << "file name: " << file_name << endl; + } + + // Load all sequences: + int seq; + vector< vector > vstrImageLeft; + vector< vector > vstrImageRight; + vector< vector > vTimestampsCam; + vector nImages; + + vstrImageLeft.resize(num_seq); + vstrImageRight.resize(num_seq); + vTimestampsCam.resize(num_seq); + nImages.resize(num_seq); + + int tot_images = 0; + for (seq = 0; seq vTimesTrack; + vTimesTrack.resize(tot_images); + + cout << endl << "-------" << endl; + cout.precision(17); + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::STEREO, true); + + cv::Mat imLeft, imRight; + for (seq = 0; seq(), vstrImageLeft[seq][ni]); + + #ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); + #else + std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now(); + #endif + +#ifdef REGISTER_TIMES + t_track = t_resize + t_rect + std::chrono::duration_cast >(t2 - t1).count(); + SLAM.InsertTrackTime(t_track); +#endif + + double ttrack= std::chrono::duration_cast >(t2 - t1).count(); + + vTimesTrack[ni]=ttrack; + + // Wait to load the next frame + double T=0; + if(ni0) + T = tframe-vTimestampsCam[seq][ni-1]; + + if(ttrack &vstrImageLeft, vector &vstrImageRight, vector &vTimeStamps) +{ + ifstream fTimes; + fTimes.open(strPathTimes.c_str()); + vTimeStamps.reserve(5000); + vstrImageLeft.reserve(5000); + vstrImageRight.reserve(5000); + while(!fTimes.eof()) + { + string s; + getline(fTimes,s); + if(!s.empty()) + { + stringstream ss; + ss << s; + vstrImageLeft.push_back(strPathLeft + "/" + ss.str() + ".png"); + vstrImageRight.push_back(strPathRight + "/" + ss.str() + ".png"); + double t; + ss >> t; + vTimeStamps.push_back(t/1e9); + + } + } +} From 6928f8c95e6a13ed31710e2dd1dbe9b8df061bf2 Mon Sep 17 00:00:00 2001 From: olayasturias Date: Thu, 24 Nov 2022 12:19:11 +0100 Subject: [PATCH 13/17] changing ts location --- .../MIMIR_TimeStamps/{ => SeaFloor/track0}/SeaFloor_track0.txt | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename Examples/Monocular/MIMIR_TimeStamps/{ => SeaFloor/track0}/SeaFloor_track0.txt (100%) diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track0.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor/track0/SeaFloor_track0.txt similarity index 100% rename from Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track0.txt rename to Examples/Monocular/MIMIR_TimeStamps/SeaFloor/track0/SeaFloor_track0.txt From 21176fb6a3e05c6044e39bddb93ffc74b8ea6fda Mon Sep 17 00:00:00 2001 From: olayasturias Date: Thu, 24 Nov 2022 14:46:30 +0100 Subject: [PATCH 14/17] formatting TS files for easier automation --- .../{MH01.txt => MH_01_easy.txt} | 0 .../{MH04.txt => MH_04_difficult.txt} | 0 .../OceanFloor_track0_dark.txt | 2405 ------- .../OceanFloor_track0_light.txt | 2421 ------- .../OceanFloor_track1_light.txt | 6263 ----------------- .../MIMIR_TimeStamps/SandPipe_track0_dark.txt | 2741 -------- .../SandPipe_track0_light.txt | 2605 ------- .../SeaFloor/track0/SeaFloor_track0.txt | 2847 -------- .../SeaFloor_Algae_track0.txt | 2934 -------- .../SeaFloor_Algae_track1.txt | 2076 ------ .../SeaFloor_Algae_track2.txt | 2489 ------- .../MIMIR_TimeStamps/SeaFloor_track1.txt | 2030 ------ .../MIMIR_TimeStamps/SeaFloor_track2.txt | 2537 ------- 13 files changed, 31348 deletions(-) rename Examples/Monocular/EuRoC_TimeStamps/{MH01.txt => MH_01_easy.txt} (100%) rename Examples/Monocular/EuRoC_TimeStamps/{MH04.txt => MH_04_difficult.txt} (100%) delete mode 100644 Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_dark.txt delete mode 100644 Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_light.txt delete mode 100644 Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track1_light.txt delete mode 100644 Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_dark.txt delete mode 100644 Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_light.txt delete mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor/track0/SeaFloor_track0.txt delete mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt delete mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt delete mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt delete mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track1.txt delete mode 100644 Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track2.txt diff --git a/Examples/Monocular/EuRoC_TimeStamps/MH01.txt b/Examples/Monocular/EuRoC_TimeStamps/MH_01_easy.txt similarity index 100% rename from Examples/Monocular/EuRoC_TimeStamps/MH01.txt rename to Examples/Monocular/EuRoC_TimeStamps/MH_01_easy.txt diff --git a/Examples/Monocular/EuRoC_TimeStamps/MH04.txt b/Examples/Monocular/EuRoC_TimeStamps/MH_04_difficult.txt similarity index 100% rename from Examples/Monocular/EuRoC_TimeStamps/MH04.txt rename to Examples/Monocular/EuRoC_TimeStamps/MH_04_difficult.txt diff --git a/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_dark.txt b/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_dark.txt deleted file mode 100644 index e14794a331..0000000000 --- a/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_dark.txt +++ /dev/null @@ -1,2405 +0,0 @@ -1662138209585822464 -1662138209624823296 -1662138209666824192 -1662138209705825024 -1662138209747825920 -1662138209789826816 -1662138209831827712 -1662138209873828608 -1662138209918829568 -1662138209972830720 -1662138210017831680 -1662138210065832704 -1662138210110833664 -1662138210155834624 -1662138210197835520 -1662138210242836480 -1662138210287837440 -1662138210329838336 -1662138210374839296 -1662138210416840192 -1662138210467841280 -1662138210515842304 -1662138210563843328 -1662138210605844224 -1662138210647845120 -1662138210698846208 -1662138210740847104 -1662138210782848000 -1662138210824848896 -1662138210869849856 -1662138210914850816 -1662138210959851776 -1662138211001852672 -1662138211046853632 -1662138211088854528 -1662138211130855424 -1662138211181856512 -1662138211223857408 -1662138211262858240 -1662138211304859136 -1662138211349860096 -1662138211391860992 -1662138211436861952 -1662138211475862784 -1662138211517863680 -1662138211562864640 -1662138211607865600 -1662138211652866560 -1662138211697867520 -1662138211745868544 -1662138211787869440 -1662138211829870336 -1662138211874871296 -1662138211925872384 -1662138211967873280 -1662138212012874240 -1662138212060875264 -1662138212102876160 -1662138212141876992 -1662138212180877824 -1662138212222878720 -1662138212270879744 -1662138212318880768 -1662138212363881728 -1662138212411882752 -1662138212465883904 -1662138212507884800 -1662138212552885760 -1662138212597886720 -1662138212639887616 -1662138212684888576 -1662138212732889600 -1662138212771890432 -1662138212813891328 -1662138212855892224 -1662138212897893120 -1662138212939894016 -1662138212981894912 -1662138213026895872 -1662138213068896768 -1662138213116897792 -1662138213161898752 -1662138213206899712 -1662138213248900608 -1662138213290901504 -1662138213332902400 -1662138213374903296 -1662138213416904192 -1662138213461905152 -1662138213509906176 -1662138213551907072 -1662138213599908096 -1662138213641908992 -1662138213695910144 -1662138213737911040 -1662138213788912128 -1662138213833913088 -1662138213881914112 -1662138213929915136 -1662138213971916032 -1662138214019917056 -1662138214061917952 -1662138214109918976 -1662138214157920000 -1662138214208921088 -1662138214250921984 -1662138214298923008 -1662138214337923840 -1662138214382924800 -1662138214430925824 -1662138214478926848 -1662138214520927744 -1662138214562928640 -1662138214604929536 -1662138214649930496 -1662138214691931392 -1662138214733932288 -1662138214775933184 -1662138214820934144 -1662138214859934976 -1662138214904935936 -1662138214955937024 -1662138214997937920 -1662138215042938880 -1662138215084939776 -1662138215132940800 -1662138215171941632 -1662138215210942464 -1662138215255943424 -1662138215300944384 -1662138215342945280 -1662138215387946240 -1662138215429947136 -1662138215468947968 -1662138215513948928 -1662138215561949952 -1662138215606950912 -1662138215648951808 -1662138215690952704 -1662138215738953728 -1662138215780954624 -1662138215828955648 -1662138215870956544 -1662138215909957376 -1662138215957958400 -1662138215999959296 -1662138216041960192 -1662138216083961088 -1662138216122961920 -1662138216164962816 -1662138216212963840 -1662138216257964800 -1662138216299965696 -1662138216341966592 -1662138216383967488 -1662138216431968512 -1662138216470969344 -1662138216512970240 -1662138216554971136 -1662138216596972032 -1662138216641972992 -1662138216689974016 -1662138216737975040 -1662138216782976000 -1662138216824976896 -1662138216866977792 -1662138216905978624 -1662138216947979520 -1662138216992980480 -1662138217034981376 -1662138217085982464 -1662138217133983488 -1662138217175984384 -1662138217214985216 -1662138217259986176 -1662138217301987072 -1662138217349988096 -1662138217391988992 -1662138217433989888 -1662138217475990784 -1662138217517991680 -1662138217559992576 -1662138217607993600 -1662138217652994560 -1662138217700995584 -1662138217742996480 -1662138217787997440 -1662138217829998336 -1662138217871999232 -1662138217914000128 -1662138217956001024 -1662138217998001920 -1662138218040002816 -1662138218085003776 -1662138218130004736 -1662138218175005696 -1662138218217006592 -1662138218256007424 -1662138218298008320 -1662138218343009280 -1662138218385010176 -1662138218427011072 -1662138218469011968 -1662138218517012992 -1662138218559013888 -1662138218601014784 -1662138218646015744 -1662138218694016768 -1662138218739017728 -1662138218781018624 -1662138218823019520 -1662138218865020416 -1662138218907021312 -1662138218949022208 -1662138218997023232 -1662138219036024064 -1662138219081025024 -1662138219123025920 -1662138219162026752 -1662138219207027712 -1662138219249028608 -1662138219294029568 -1662138219339030528 -1662138219381031424 -1662138219423032320 -1662138219474033408 -1662138219519034368 -1662138219567035392 -1662138219612036352 -1662138219660037376 -1662138219708038400 -1662138219756039424 -1662138219798040320 -1662138219846041344 -1662138219888042240 -1662138219933043200 -1662138219987044352 -1662138220035045376 -1662138220080046336 -1662138220128047360 -1662138220173048320 -1662138220218049280 -1662138220263050240 -1662138220305051136 -1662138220350052096 -1662138220395053056 -1662138220434053888 -1662138220479054848 -1662138220524055808 -1662138220569056768 -1662138220611057664 -1662138220650058496 -1662138220692059392 -1662138220734060288 -1662138220779061248 -1662138220824062208 -1662138220869063168 -1662138220917064192 -1662138220962065152 -1662138221007066112 -1662138221049067008 -1662138221091067904 -1662138221133068800 -1662138221178069760 -1662138221220070656 -1662138221265071616 -1662138221307072512 -1662138221349073408 -1662138221403074560 -1662138221445075456 -1662138221493076480 -1662138221535077376 -1662138221580078336 -1662138221628079360 -1662138221670080256 -1662138221712081152 -1662138221757082112 -1662138221799083008 -1662138221838083840 -1662138221880084736 -1662138221922085632 -1662138221961086464 -1662138222009087488 -1662138222051088384 -1662138222102089472 -1662138222150090496 -1662138222195091456 -1662138222240092416 -1662138222288093440 -1662138222336094464 -1662138222381095424 -1662138222429096448 -1662138222471097344 -1662138222513098240 -1662138222558099200 -1662138222600100096 -1662138222648101120 -1662138222687101952 -1662138222732102912 -1662138222777103872 -1662138222822104832 -1662138222870105856 -1662138222912106752 -1662138222960107776 -1662138223002108672 -1662138223044109568 -1662138223086110464 -1662138223131111424 -1662138223173112320 -1662138223221113344 -1662138223266114304 -1662138223311115264 -1662138223359116288 -1662138223401117184 -1662138223437117952 -1662138223479118848 -1662138223527119872 -1662138223569120768 -1662138223611121664 -1662138223656122624 -1662138223701123584 -1662138223749124608 -1662138223791125504 -1662138223839126528 -1662138223881127424 -1662138223926128384 -1662138223968129280 -1662138224019130368 -1662138224058131200 -1662138224112132352 -1662138224160133376 -1662138224208134400 -1662138224247135232 -1662138224289136128 -1662138224334137088 -1662138224376137984 -1662138224418138880 -1662138224463139840 -1662138224511140864 -1662138224553141760 -1662138224598142720 -1662138224643143680 -1662138224688144640 -1662138224733145600 -1662138224784146688 -1662138224826147584 -1662138224868148480 -1662138224910149376 -1662138224952150272 -1662138224994151168 -1662138225039152128 -1662138225084153088 -1662138225132154112 -1662138225174155008 -1662138225219155968 -1662138225267156992 -1662138225315158016 -1662138225360158976 -1662138225405159936 -1662138225450160896 -1662138225501161984 -1662138225546162944 -1662138225588163840 -1662138225633164800 -1662138225678165760 -1662138225723166720 -1662138225765167616 -1662138225810168576 -1662138225858169600 -1662138225900170496 -1662138225948171520 -1662138225993172480 -1662138226035173376 -1662138226077174272 -1662138226122175232 -1662138226167176192 -1662138226212177152 -1662138226254178048 -1662138226302179072 -1662138226344179968 -1662138226392180992 -1662138226431181824 -1662138226473182720 -1662138226521183744 -1662138226566184704 -1662138226608185600 -1662138226650186496 -1662138226689187328 -1662138226743188480 -1662138226794189568 -1662138226839190528 -1662138226881191424 -1662138226923192320 -1662138226971193344 -1662138227013194240 -1662138227058195200 -1662138227103196160 -1662138227148197120 -1662138227193198080 -1662138227241199104 -1662138227286200064 -1662138227337201152 -1662138227391202304 -1662138227433203200 -1662138227475204096 -1662138227517204992 -1662138227559205888 -1662138227604206848 -1662138227652207872 -1662138227694208768 -1662138227739209728 -1662138227784210688 -1662138227826211584 -1662138227868212480 -1662138227910213376 -1662138227955214336 -1662138227997215232 -1662138228039216128 -1662138228084217088 -1662138228126217984 -1662138228171218944 -1662138228225220096 -1662138228267220992 -1662138228318222080 -1662138228363223040 -1662138228405223936 -1662138228456225024 -1662138228504226048 -1662138228549227008 -1662138228594227968 -1662138228642228992 -1662138228684229888 -1662138228729230848 -1662138228783232000 -1662138228828232960 -1662138228870233856 -1662138228918234880 -1662138228966235904 -1662138229008236800 -1662138229056237824 -1662138229095238656 -1662138229143239680 -1662138229185240576 -1662138229227241472 -1662138229269242368 -1662138229317243392 -1662138229359244288 -1662138229401245184 -1662138229449246208 -1662138229503247360 -1662138229545248256 -1662138229590249216 -1662138229632250112 -1662138229674251008 -1662138229716251904 -1662138229764252928 -1662138229806253824 -1662138229851254784 -1662138229893255680 -1662138229941256704 -1662138229986257664 -1662138230028258560 -1662138230073259520 -1662138230127260672 -1662138230169261568 -1662138230217262592 -1662138230262263552 -1662138230304264448 -1662138230349265408 -1662138230394266368 -1662138230436267264 -1662138230481268224 -1662138230526269184 -1662138230574270208 -1662138230613271040 -1662138230658272000 -1662138230706273024 -1662138230748273920 -1662138230790274816 -1662138230835275776 -1662138230877276672 -1662138230919277568 -1662138230961278464 -1662138231006279424 -1662138231048280320 -1662138231099281408 -1662138231141282304 -1662138231186283264 -1662138231228284160 -1662138231279285248 -1662138231324286208 -1662138231372287232 -1662138231414288128 -1662138231468289280 -1662138231510290176 -1662138231552291072 -1662138231594291968 -1662138231633292800 -1662138231675293696 -1662138231714294528 -1662138231759295488 -1662138231810296576 -1662138231852297472 -1662138231894298368 -1662138231942299392 -1662138231984300288 -1662138232023301120 -1662138232068302080 -1662138232113303040 -1662138232155303936 -1662138232203304960 -1662138232248305920 -1662138232290306816 -1662138232338307840 -1662138232386308864 -1662138232428309760 -1662138232467310592 -1662138232515311616 -1662138232557312512 -1662138232614313728 -1662138232656314624 -1662138232695315456 -1662138232737316352 -1662138232782317312 -1662138232833318400 -1662138232875319296 -1662138232917320192 -1662138232959321088 -1662138233001321984 -1662138233046322944 -1662138233088323840 -1662138233136324864 -1662138233187325952 -1662138233232326912 -1662138233280327936 -1662138233322328832 -1662138233364329728 -1662138233409330688 -1662138233451331584 -1662138233493332480 -1662138233535333376 -1662138233580334336 -1662138233625335296 -1662138233667336192 -1662138233715337216 -1662138233757338112 -1662138233805339136 -1662138233856340224 -1662138233895341056 -1662138233940342016 -1662138233979342848 -1662138234021343744 -1662138234066344704 -1662138234108345600 -1662138234153346560 -1662138234192347392 -1662138234237348352 -1662138234282349312 -1662138234324350208 -1662138234366351104 -1662138234408352000 -1662138234453352960 -1662138234504354048 -1662138234549355008 -1662138234591355904 -1662138234645357056 -1662138234690358016 -1662138234735358976 -1662138234780359936 -1662138234828360960 -1662138234870361856 -1662138234912362752 -1662138234957363712 -1662138235002364672 -1662138235050365696 -1662138235095366656 -1662138235143367680 -1662138235194368768 -1662138235236369664 -1662138235275370496 -1662138235317371392 -1662138235359372288 -1662138235407373312 -1662138235452374272 -1662138235497375232 -1662138235545376256 -1662138235596377344 -1662138235644378368 -1662138235686379264 -1662138235728380160 -1662138235773381120 -1662138235812381952 -1662138235854382848 -1662138235905383936 -1662138235947384832 -1662138235989385728 -1662138236037386752 -1662138236079387648 -1662138236121388544 -1662138236163389440 -1662138236211390464 -1662138236256391424 -1662138236298392320 -1662138236340393216 -1662138236388394240 -1662138236430395136 -1662138236475396096 -1662138236520397056 -1662138236565398016 -1662138236607398912 -1662138236652399872 -1662138236706401024 -1662138236748401920 -1662138236796402944 -1662138236844403968 -1662138236886404864 -1662138236931405824 -1662138236976406784 -1662138237018407680 -1662138237066408704 -1662138237108409600 -1662138237150410496 -1662138237201411584 -1662138237246412544 -1662138237288413440 -1662138237336414464 -1662138237378415360 -1662138237423416320 -1662138237471417344 -1662138237513418240 -1662138237555419136 -1662138237597420032 -1662138237642420992 -1662138237687421952 -1662138237729422848 -1662138237771423744 -1662138237813424640 -1662138237852425472 -1662138237894426368 -1662138237939427328 -1662138237981428224 -1662138238023429120 -1662138238065430016 -1662138238110430976 -1662138238152431872 -1662138238197432832 -1662138238248433920 -1662138238299435008 -1662138238350436096 -1662138238392436992 -1662138238434437888 -1662138238476438784 -1662138238515439616 -1662138238563440640 -1662138238608441600 -1662138238653442560 -1662138238695443456 -1662138238737444352 -1662138238779445248 -1662138238821446144 -1662138238863447040 -1662138238905447936 -1662138238956449024 -1662138239001449984 -1662138239049451008 -1662138239091451904 -1662138239130452736 -1662138239169453568 -1662138239211454464 -1662138239259455488 -1662138239304456448 -1662138239349457408 -1662138239400458496 -1662138239451459584 -1662138239499460608 -1662138239541461504 -1662138239586462464 -1662138239640463616 -1662138239682464512 -1662138239733465600 -1662138239778466560 -1662138239823467520 -1662138239865468416 -1662138239910469376 -1662138239961470464 -1662138240006471424 -1662138240048472320 -1662138240096473344 -1662138240141474304 -1662138240183475200 -1662138240225476096 -1662138240270477056 -1662138240315478016 -1662138240357478912 -1662138240402479872 -1662138240447480832 -1662138240492481792 -1662138240534482688 -1662138240576483584 -1662138240618484480 -1662138240663485440 -1662138240717486592 -1662138240762487552 -1662138240810488576 -1662138240849489408 -1662138240897490432 -1662138240945491456 -1662138240987492352 -1662138241032493312 -1662138241077494272 -1662138241122495232 -1662138241167496192 -1662138241209497088 -1662138241257498112 -1662138241299499008 -1662138241344499968 -1662138241389500928 -1662138241434501888 -1662138241479502848 -1662138241527503872 -1662138241569504768 -1662138241608505600 -1662138241650506496 -1662138241695507456 -1662138241743508480 -1662138241785509376 -1662138241830510336 -1662138241878511360 -1662138241923512320 -1662138241974513408 -1662138242019514368 -1662138242061515264 -1662138242106516224 -1662138242151517184 -1662138242193518080 -1662138242235518976 -1662138242277519872 -1662138242319520768 -1662138242361521664 -1662138242406522624 -1662138242454523648 -1662138242499524608 -1662138242538525440 -1662138242580526336 -1662138242622527232 -1662138242667528192 -1662138242712529152 -1662138242754530048 -1662138242796530944 -1662138242844531968 -1662138242889532928 -1662138242931533824 -1662138242982534912 -1662138243030535936 -1662138243072536832 -1662138243114537728 -1662138243159538688 -1662138243204539648 -1662138243249540608 -1662138243294541568 -1662138243336542464 -1662138243381543424 -1662138243423544320 -1662138243465545216 -1662138243510546176 -1662138243552547072 -1662138243594547968 -1662138243639548928 -1662138243681549824 -1662138243723550720 -1662138243765551616 -1662138243810552576 -1662138243861553664 -1662138243900554496 -1662138243948555520 -1662138243996556544 -1662138244044557568 -1662138244086558464 -1662138244131559424 -1662138244173560320 -1662138244218561280 -1662138244260562176 -1662138244308563200 -1662138244350564096 -1662138244392564992 -1662138244431565824 -1662138244473566720 -1662138244515567616 -1662138244557568512 -1662138244599569408 -1662138244641570304 -1662138244689571328 -1662138244737572352 -1662138244782573312 -1662138244824574208 -1662138244866575104 -1662138244914576128 -1662138244965577216 -1662138245010578176 -1662138245058579200 -1662138245106580224 -1662138245151581184 -1662138245196582144 -1662138245244583168 -1662138245292584192 -1662138245337585152 -1662138245391586304 -1662138245442587392 -1662138245487588352 -1662138245535589376 -1662138245577590272 -1662138245619591168 -1662138245667592192 -1662138245706593024 -1662138245754594048 -1662138245796594944 -1662138245847596032 -1662138245895597056 -1662138245937597952 -1662138245982598912 -1662138246027599872 -1662138246078600960 -1662138246123601920 -1662138246174603008 -1662138246216603904 -1662138246258604800 -1662138246300605696 -1662138246345606656 -1662138246387607552 -1662138246435608576 -1662138246480609536 -1662138246522610432 -1662138246567611392 -1662138246609612288 -1662138246654613248 -1662138246699614208 -1662138246744615168 -1662138246786616064 -1662138246825616896 -1662138246876617984 -1662138246918618880 -1662138246960619776 -1662138247011620864 -1662138247053621760 -1662138247104622848 -1662138247149623808 -1662138247191624704 -1662138247233625600 -1662138247284626688 -1662138247329627648 -1662138247371628544 -1662138247419629568 -1662138247461630464 -1662138247509631488 -1662138247554632448 -1662138247599633408 -1662138247650634496 -1662138247692635392 -1662138247740636416 -1662138247782637312 -1662138247833638400 -1662138247875639296 -1662138247917640192 -1662138247959641088 -1662138248007642112 -1662138248049643008 -1662138248097644032 -1662138248139644928 -1662138248181645824 -1662138248229646848 -1662138248268647680 -1662138248313648640 -1662138248355649536 -1662138248400650496 -1662138248442651392 -1662138248487652352 -1662138248532653312 -1662138248571654144 -1662138248616655104 -1662138248655655936 -1662138248697656832 -1662138248739657728 -1662138248784658688 -1662138248832659712 -1662138248874660608 -1662138248919661568 -1662138248967662592 -1662138249015663616 -1662138249057664512 -1662138249105665536 -1662138249150666496 -1662138249198667520 -1662138249240668416 -1662138249282669312 -1662138249324670208 -1662138249366671104 -1662138249411672064 -1662138249456673024 -1662138249501673984 -1662138249546674944 -1662138249594675968 -1662138249636676864 -1662138249678677760 -1662138249726678784 -1662138249768679680 -1662138249810680576 -1662138249855681536 -1662138249897682432 -1662138249942683392 -1662138249990684416 -1662138250032685312 -1662138250080686336 -1662138250122687232 -1662138250170688256 -1662138250215689216 -1662138250257690112 -1662138250305691136 -1662138250347692032 -1662138250398693120 -1662138250440694016 -1662138250485694976 -1662138250527695872 -1662138250569696768 -1662138250614697728 -1662138250662698752 -1662138250707699712 -1662138250752700672 -1662138250800701696 -1662138250845702656 -1662138250887703552 -1662138250938704640 -1662138250980705536 -1662138251022706432 -1662138251067707392 -1662138251112708352 -1662138251154709248 -1662138251196710144 -1662138251238711040 -1662138251280711936 -1662138251322712832 -1662138251364713728 -1662138251409714688 -1662138251451715584 -1662138251493716480 -1662138251541717504 -1662138251583718400 -1662138251628719360 -1662138251676720384 -1662138251715721216 -1662138251757722112 -1662138251808723200 -1662138251853724160 -1662138251898725120 -1662138251937725952 -1662138251985726976 -1662138252027727872 -1662138252072728832 -1662138252114729728 -1662138252156730624 -1662138252198731520 -1662138252246732544 -1662138252285733376 -1662138252327734272 -1662138252372735232 -1662138252420736256 -1662138252459737088 -1662138252501737984 -1662138252546738944 -1662138252591739904 -1662138252633740800 -1662138252690742016 -1662138252735742976 -1662138252783744000 -1662138252831745024 -1662138252873745920 -1662138252915746816 -1662138252957747712 -1662138252996748544 -1662138253041749504 -1662138253083750400 -1662138253125751296 -1662138253167752192 -1662138253215753216 -1662138253263754240 -1662138253314755328 -1662138253353756160 -1662138253398757120 -1662138253443758080 -1662138253494759168 -1662138253536760064 -1662138253581761024 -1662138253629762048 -1662138253683763200 -1662138253725764096 -1662138253770765056 -1662138253818766080 -1662138253857766912 -1662138253899767808 -1662138253953768960 -1662138254001769984 -1662138254043770880 -1662138254088771840 -1662138254136772864 -1662138254181773824 -1662138254223774720 -1662138254265775616 -1662138254310776576 -1662138254361777664 -1662138254406778624 -1662138254451779584 -1662138254496780544 -1662138254532781312 -1662138254577782272 -1662138254622783232 -1662138254670784256 -1662138254709785088 -1662138254751785984 -1662138254799787008 -1662138254841787904 -1662138254883788800 -1662138254931789824 -1662138254979790848 -1662138255024791808 -1662138255069792768 -1662138255111793664 -1662138255153794560 -1662138255195795456 -1662138255237796352 -1662138255282797312 -1662138255333798400 -1662138255378799360 -1662138255423800320 -1662138255462801152 -1662138255507802112 -1662138255549803008 -1662138255588803840 -1662138255633804800 -1662138255675805696 -1662138255717806592 -1662138255759807488 -1662138255801808384 -1662138255846809344 -1662138255894810368 -1662138255936811264 -1662138255981812224 -1662138256023813120 -1662138256065814016 -1662138256113815040 -1662138256161816064 -1662138256206817024 -1662138256242817792 -1662138256281818624 -1662138256329819648 -1662138256371820544 -1662138256419821568 -1662138256464822528 -1662138256506823424 -1662138256554824448 -1662138256596825344 -1662138256638826240 -1662138256683827200 -1662138256725828096 -1662138256770829056 -1662138256812829952 -1662138256860830976 -1662138256911832064 -1662138256956833024 -1662138257001833984 -1662138257052835072 -1662138257094835968 -1662138257139836928 -1662138257184837888 -1662138257235838976 -1662138257277839872 -1662138257328840960 -1662138257370841856 -1662138257412842752 -1662138257454843648 -1662138257496844544 -1662138257544845568 -1662138257586846464 -1662138257628847360 -1662138257670848256 -1662138257724849408 -1662138257769850368 -1662138257811851264 -1662138257853852160 -1662138257895853056 -1662138257937853952 -1662138257979854848 -1662138258021855744 -1662138258069856768 -1662138258117857792 -1662138258156858624 -1662138258201859584 -1662138258246860544 -1662138258294861568 -1662138258342862592 -1662138258387863552 -1662138258429864448 -1662138258471865344 -1662138258516866304 -1662138258567867392 -1662138258609868288 -1662138258654869248 -1662138258696870144 -1662138258741871104 -1662138258786872064 -1662138258825872896 -1662138258867873792 -1662138258912874752 -1662138258957875712 -1662138259005876736 -1662138259047877632 -1662138259095878656 -1662138259149879808 -1662138259200880896 -1662138259242881792 -1662138259287882752 -1662138259335883776 -1662138259386884864 -1662138259428885760 -1662138259470886656 -1662138259512887552 -1662138259560888576 -1662138259602889472 -1662138259647890432 -1662138259689891328 -1662138259734892288 -1662138259776893184 -1662138259824894208 -1662138259866895104 -1662138259911896064 -1662138259956897024 -1662138259998897920 -1662138260040898816 -1662138260088899840 -1662138260133900800 -1662138260175901696 -1662138260226902784 -1662138260268903680 -1662138260316904704 -1662138260364905728 -1662138260406906624 -1662138260448907520 -1662138260490908416 -1662138260529909248 -1662138260574910208 -1662138260616911104 -1662138260667912192 -1662138260721913344 -1662138260769914368 -1662138260814915328 -1662138260856916224 -1662138260898917120 -1662138260937917952 -1662138260985918976 -1662138261036920064 -1662138261081921024 -1662138261120921856 -1662138261165922816 -1662138261207923712 -1662138261252924672 -1662138261300925696 -1662138261342926592 -1662138261384927488 -1662138261441928704 -1662138261483929600 -1662138261528930560 -1662138261573931520 -1662138261618932480 -1662138261666933504 -1662138261708934400 -1662138261753935360 -1662138261801936384 -1662138261849937408 -1662138261900938496 -1662138261945939456 -1662138261987940352 -1662138262026941184 -1662138262074942208 -1662138262116943104 -1662138262164944128 -1662138262209945088 -1662138262254946048 -1662138262296946944 -1662138262350948096 -1662138262395949056 -1662138262437949952 -1662138262482950912 -1662138262533952000 -1662138262575952896 -1662138262617953792 -1662138262668954880 -1662138262716955904 -1662138262767956992 -1662138262815958016 -1662138262857958912 -1662138262905959936 -1662138262950960896 -1662138262992961792 -1662138263043962880 -1662138263088963840 -1662138263130964736 -1662138263178965760 -1662138263220966656 -1662138263265967616 -1662138263304968448 -1662138263355969536 -1662138263400970496 -1662138263451971584 -1662138263493972480 -1662138263544973568 -1662138263592974592 -1662138263634975488 -1662138263673976320 -1662138263718977280 -1662138263763978240 -1662138263811979264 -1662138263859980288 -1662138263901981184 -1662138263949982208 -1662138263991983104 -1662138264036984064 -1662138264087985152 -1662138264129986048 -1662138264174987008 -1662138264219987968 -1662138264258988800 -1662138264303989760 -1662138264354990848 -1662138264399991808 -1662138264444992768 -1662138264483993600 -1662138264525994496 -1662138264573995520 -1662138264618996480 -1662138264660997376 -1662138264702998272 -1662138264762999552 -1662138264808000512 -1662138264850001408 -1662138264898002432 -1662138264943003392 -1662138264985004288 -1662138265030005248 -1662138265072006144 -1662138265114007040 -1662138265159008000 -1662138265207009024 -1662138265249009920 -1662138265300011008 -1662138265348012032 -1662138265390012928 -1662138265432013824 -1662138265477014784 -1662138265522015744 -1662138265564016640 -1662138265606017536 -1662138265651018496 -1662138265696019456 -1662138265744020480 -1662138265786021376 -1662138265831022336 -1662138265873023232 -1662138265918024192 -1662138265966025216 -1662138266008026112 -1662138266050027008 -1662138266095027968 -1662138266146029056 -1662138266188029952 -1662138266239031040 -1662138266284032000 -1662138266332033024 -1662138266371033856 -1662138266413034752 -1662138266455035648 -1662138266497036544 -1662138266542037504 -1662138266587038464 -1662138266629039360 -1662138266674040320 -1662138266725041408 -1662138266770042368 -1662138266821043456 -1662138266863044352 -1662138266908045312 -1662138266950046208 -1662138266992047104 -1662138267037048064 -1662138267079048960 -1662138267121049856 -1662138267166050816 -1662138267208051712 -1662138267253052672 -1662138267298053632 -1662138267343054592 -1662138267391055616 -1662138267433056512 -1662138267475057408 -1662138267520058368 -1662138267568059392 -1662138267610060288 -1662138267649061120 -1662138267694062080 -1662138267739063040 -1662138267778063872 -1662138267820064768 -1662138267862065664 -1662138267907066624 -1662138267952067584 -1662138267994068480 -1662138268039069440 -1662138268078070272 -1662138268117071104 -1662138268165072128 -1662138268210073088 -1662138268264074240 -1662138268306075136 -1662138268348076032 -1662138268387076864 -1662138268429077760 -1662138268471078656 -1662138268519079680 -1662138268564080640 -1662138268606081536 -1662138268657082624 -1662138268696083456 -1662138268744084480 -1662138268792085504 -1662138268831086336 -1662138268879087360 -1662138268924088320 -1662138268972089344 -1662138269017090304 -1662138269068091392 -1662138269107092224 -1662138269152093184 -1662138269194094080 -1662138269236094976 -1662138269290096128 -1662138269335097088 -1662138269377097984 -1662138269419098880 -1662138269464099840 -1662138269506100736 -1662138269548101632 -1662138269590102528 -1662138269632103424 -1662138269680104448 -1662138269731105536 -1662138269776106496 -1662138269818107392 -1662138269863108352 -1662138269905109248 -1662138269956110336 -1662138269998111232 -1662138270040112128 -1662138270085113088 -1662138270130114048 -1662138270172114944 -1662138270217115904 -1662138270262116864 -1662138270304117760 -1662138270352118784 -1662138270394119680 -1662138270442120704 -1662138270484121600 -1662138270529122560 -1662138270571123456 -1662138270613124352 -1662138270661125376 -1662138270703126272 -1662138270745127168 -1662138270790128128 -1662138270841129216 -1662138270886130176 -1662138270928131072 -1662138270973132032 -1662138271015132928 -1662138271063133952 -1662138271108134912 -1662138271156135936 -1662138271201136896 -1662138271243137792 -1662138271294138880 -1662138271336139776 -1662138271384140800 -1662138271426141696 -1662138271477142784 -1662138271519143680 -1662138271558144512 -1662138271600145408 -1662138271645146368 -1662138271690147328 -1662138271729148160 -1662138271777149184 -1662138271819150080 -1662138271864151040 -1662138271912152064 -1662138271954152960 -1662138271996153856 -1662138272038154752 -1662138272080155648 -1662138272125156608 -1662138272173157632 -1662138272215158528 -1662138272260159488 -1662138272305160448 -1662138272347161344 -1662138272389162240 -1662138272434163200 -1662138272485164288 -1662138272530165248 -1662138272572166144 -1662138272614167040 -1662138272659168000 -1662138272716169216 -1662138272758170112 -1662138272803171072 -1662138272848172032 -1662138272893172992 -1662138272935173888 -1662138272983174912 -1662138273028175872 -1662138273070176768 -1662138273118177792 -1662138273172178944 -1662138273217179904 -1662138273265180928 -1662138273313181952 -1662138273358182912 -1662138273406183936 -1662138273448184832 -1662138273490185728 -1662138273538186752 -1662138273583187712 -1662138273634188800 -1662138273676189696 -1662138273721190656 -1662138273766191616 -1662138273808192512 -1662138273850193408 -1662138273892194304 -1662138273931195136 -1662138273970195968 -1662138274012196864 -1662138274057197824 -1662138274099198720 -1662138274141199616 -1662138274183200512 -1662138274231201536 -1662138274279202560 -1662138274324203520 -1662138274372204544 -1662138274414205440 -1662138274459206400 -1662138274501207296 -1662138274549208320 -1662138274591209216 -1662138274633210112 -1662138274681211136 -1662138274729212160 -1662138274771213056 -1662138274813213952 -1662138274855214848 -1662138274897215744 -1662138274939216640 -1662138274981217536 -1662138275026218496 -1662138275071219456 -1662138275113220352 -1662138275155221248 -1662138275197222144 -1662138275242223104 -1662138275287224064 -1662138275332225024 -1662138275380226048 -1662138275425227008 -1662138275473228032 -1662138275518228992 -1662138275563229952 -1662138275602230784 -1662138275647231744 -1662138275689232640 -1662138275734233600 -1662138275776234496 -1662138275821235456 -1662138275863236352 -1662138275905237248 -1662138275953238272 -1662138275998239232 -1662138276040240128 -1662138276085241088 -1662138276133242112 -1662138276178243072 -1662138276220243968 -1662138276265244928 -1662138276307245824 -1662138276355246848 -1662138276394247680 -1662138276445248768 -1662138276487249664 -1662138276529250560 -1662138276577251584 -1662138276622252544 -1662138276673253632 -1662138276718254592 -1662138276760255488 -1662138276802256384 -1662138276850257408 -1662138276892258304 -1662138276940259328 -1662138276982260224 -1662138277030261248 -1662138277072262144 -1662138277120263168 -1662138277165264128 -1662138277210265088 -1662138277252265984 -1662138277303267072 -1662138277342267904 -1662138277384268800 -1662138277423269632 -1662138277465270528 -1662138277507271424 -1662138277555272448 -1662138277600273408 -1662138277645274368 -1662138277696275456 -1662138277741276416 -1662138277783277312 -1662138277825278208 -1662138277864279040 -1662138277906279936 -1662138277951280896 -1662138277999281920 -1662138278044282880 -1662138278086283776 -1662138278125284608 -1662138278179285760 -1662138278224286720 -1662138278266287616 -1662138278308288512 -1662138278350289408 -1662138278398290432 -1662138278443291392 -1662138278485292288 -1662138278524293120 -1662138278566294016 -1662138278608294912 -1662138278662296064 -1662138278710297088 -1662138278752297984 -1662138278800299008 -1662138278845299968 -1662138278887300864 -1662138278929301760 -1662138278971302656 -1662138279016303616 -1662138279058304512 -1662138279100305408 -1662138279151306496 -1662138279196307456 -1662138279244308480 -1662138279295309568 -1662138279343310592 -1662138279385311488 -1662138279430312448 -1662138279475313408 -1662138279526314496 -1662138279571315456 -1662138279634316800 -1662138279673317632 -1662138279721318656 -1662138279766319616 -1662138279820320768 -1662138279862321664 -1662138279907322624 -1662138279952323584 -1662138279994324480 -1662138280039325440 -1662138280081326336 -1662138280126327296 -1662138280174328320 -1662138280222329344 -1662138280264330240 -1662138280306331136 -1662138280348332032 -1662138280390332928 -1662138280438333952 -1662138280483334912 -1662138280525335808 -1662138280567336704 -1662138280615337728 -1662138280663338752 -1662138280705339648 -1662138280747340544 -1662138280792341504 -1662138280834342400 -1662138280879343360 -1662138280921344256 -1662138280966345216 -1662138281011346176 -1662138281056347136 -1662138281104348160 -1662138281152349184 -1662138281194350080 -1662138281242351104 -1662138281287352064 -1662138281338353152 -1662138281380354048 -1662138281419354880 -1662138281461355776 -1662138281503356672 -1662138281557357824 -1662138281599358720 -1662138281644359680 -1662138281689360640 -1662138281731361536 -1662138281782362624 -1662138281824363520 -1662138281878364672 -1662138281926365696 -1662138281971366656 -1662138282022367744 -1662138282064368640 -1662138282106369536 -1662138282148370432 -1662138282190371328 -1662138282232372224 -1662138282271373056 -1662138282313373952 -1662138282352374784 -1662138282397375744 -1662138282442376704 -1662138282484377600 -1662138282532378624 -1662138282574379520 -1662138282619380480 -1662138282661381376 -1662138282703382272 -1662138282745383168 -1662138282787384064 -1662138282829384960 -1662138282889386240 -1662138282934387200 -1662138282976388096 -1662138283024389120 -1662138283066390016 -1662138283108390912 -1662138283153391872 -1662138283195392768 -1662138283237393664 -1662138283279394560 -1662138283330395648 -1662138283375396608 -1662138283426397696 -1662138283477398784 -1662138283519399680 -1662138283561400576 -1662138283603401472 -1662138283645402368 -1662138283687403264 -1662138283729404160 -1662138283768404992 -1662138283810405888 -1662138283855406848 -1662138283900407808 -1662138283942408704 -1662138283987409664 -1662138284032410624 -1662138284077411584 -1662138284122412544 -1662138284167413504 -1662138284212414464 -1662138284254415360 -1662138284302416384 -1662138284350417408 -1662138284404418560 -1662138284446419456 -1662138284488420352 -1662138284536421376 -1662138284584422400 -1662138284626423296 -1662138284668424192 -1662138284728425472 -1662138284770426368 -1662138284812427264 -1662138284854428160 -1662138284896429056 -1662138284941430016 -1662138284992431104 -1662138285037432064 -1662138285082433024 -1662138285130434048 -1662138285178435072 -1662138285229436160 -1662138285271437056 -1662138285319438080 -1662138285370439168 -1662138285418440192 -1662138285460441088 -1662138285502441984 -1662138285550443008 -1662138285601444096 -1662138285655445248 -1662138285694446080 -1662138285742447104 -1662138285784448000 -1662138285826448896 -1662138285880450048 -1662138285928451072 -1662138285970451968 -1662138286012452864 -1662138286057453824 -1662138286108454912 -1662138286165456128 -1662138286207457024 -1662138286249457920 -1662138286297458944 -1662138286342459904 -1662138286390460928 -1662138286435461888 -1662138286480462848 -1662138286519463680 -1662138286564464640 -1662138286609465600 -1662138286660466688 -1662138286711467776 -1662138286756468736 -1662138286804469760 -1662138286852470784 -1662138286891471616 -1662138286933472512 -1662138286975473408 -1662138287020474368 -1662138287071475456 -1662138287113476352 -1662138287152477184 -1662138287197478144 -1662138287239479040 -1662138287281479936 -1662138287320480768 -1662138287362481664 -1662138287416482816 -1662138287458483712 -1662138287500484608 -1662138287545485568 -1662138287587486464 -1662138287629487360 -1662138287677488384 -1662138287719489280 -1662138287761490176 -1662138287806491136 -1662138287851492096 -1662138287893492992 -1662138287938493952 -1662138287983494912 -1662138288025495808 -1662138288067496704 -1662138288118497792 -1662138288157498624 -1662138288199499520 -1662138288238500352 -1662138288283501312 -1662138288325502208 -1662138288373503232 -1662138288418504192 -1662138288460505088 -1662138288502505984 -1662138288547506944 -1662138288592507904 -1662138288634508800 -1662138288676509696 -1662138288718510592 -1662138288763511552 -1662138288814512640 -1662138288856513536 -1662138288898514432 -1662138288940515328 -1662138288985516288 -1662138289027517184 -1662138289075518208 -1662138289117519104 -1662138289159520000 -1662138289201520896 -1662138289246521856 -1662138289291522816 -1662138289336523776 -1662138289384524800 -1662138289435525888 -1662138289480526848 -1662138289528527872 -1662138289576528896 -1662138289621529856 -1662138289663530752 -1662138289711531776 -1662138289759532800 -1662138289810533888 -1662138289852534784 -1662138289897535744 -1662138289942536704 -1662138289981537536 -1662138290026538496 -1662138290068539392 -1662138290122540544 -1662138290167541504 -1662138290215542528 -1662138290260543488 -1662138290302544384 -1662138290350545408 -1662138290392546304 -1662138290446547456 -1662138290494548480 -1662138290539549440 -1662138290584550400 -1662138290626551296 -1662138290674552320 -1662138290725553408 -1662138290767554304 -1662138290815555328 -1662138290857556224 -1662138290899557120 -1662138290944558080 -1662138290995559168 -1662138291037560064 -1662138291082561024 -1662138291124561920 -1662138291166562816 -1662138291208563712 -1662138291253564672 -1662138291304565760 -1662138291352566784 -1662138291394567680 -1662138291439568640 -1662138291484569600 -1662138291532570624 -1662138291574571520 -1662138291622572544 -1662138291667573504 -1662138291712574464 -1662138291760575488 -1662138291802576384 -1662138291844577280 -1662138291889578240 -1662138291931579136 -1662138291979580160 -1662138292021581056 -1662138292063581952 -1662138292105582848 -1662138292147583744 -1662138292198584832 -1662138292243585792 -1662138292288586752 -1662138292333587712 -1662138292378588672 -1662138292429589760 -1662138292471590656 -1662138292510591488 -1662138292552592384 -1662138292597593344 -1662138292645594368 -1662138292687595264 -1662138292726596096 -1662138292768596992 -1662138292813597952 -1662138292861598976 -1662138292903599872 -1662138292948600832 -1662138292990601728 -1662138293032602624 -1662138293077603584 -1662138293125604608 -1662138293170605568 -1662138293218606592 -1662138293266607616 -1662138293311608576 -1662138293359609600 -1662138293404610560 -1662138293446611456 -1662138293488612352 -1662138293533613312 -1662138293581614336 -1662138293623615232 -1662138293665616128 -1662138293710617088 -1662138293755618048 -1662138293800619008 -1662138293845619968 -1662138293887620864 -1662138293929621760 -1662138293989623040 -1662138294037624064 -1662138294085625088 -1662138294127625984 -1662138294172626944 -1662138294214627840 -1662138294265628928 -1662138294307629824 -1662138294349630720 -1662138294394631680 -1662138294436632576 -1662138294481633536 -1662138294526634496 -1662138294574635520 -1662138294619636480 -1662138294661637376 -1662138294706638336 -1662138294751639296 -1662138294796640256 -1662138294841641216 -1662138294886642176 -1662138294931643136 -1662138294973644032 -1662138295018644992 -1662138295063645952 -1662138295105646848 -1662138295153647872 -1662138295195648768 -1662138295246649856 -1662138295288650752 -1662138295339651840 -1662138295384652800 -1662138295426653696 -1662138295480654848 -1662138295531655936 -1662138295573656832 -1662138295618657792 -1662138295663658752 -1662138295708659712 -1662138295765660928 -1662138295810661888 -1662138295852662784 -1662138295897663744 -1662138295936664576 -1662138295975665408 -1662138296026666496 -1662138296068667392 -1662138296110668288 -1662138296155669248 -1662138296200670208 -1662138296242671104 -1662138296284672000 -1662138296329672960 -1662138296380674048 -1662138296419674880 -1662138296470675968 -1662138296512676864 -1662138296554677760 -1662138296602678784 -1662138296644679680 -1662138296686680576 -1662138296737681664 -1662138296779682560 -1662138296821683456 -1662138296872684544 -1662138296917685504 -1662138296959686400 -1662138297016687616 -1662138297061688576 -1662138297109689600 -1662138297154690560 -1662138297193691392 -1662138297235692288 -1662138297289693440 -1662138297337694464 -1662138297382695424 -1662138297424696320 -1662138297466697216 -1662138297508698112 -1662138297559699200 -1662138297601700096 -1662138297646701056 -1662138297697702144 -1662138297742703104 -1662138297784704000 -1662138297823704832 -1662138297862705664 -1662138297901706496 -1662138297952707584 -1662138298000708608 -1662138298045709568 -1662138298090710528 -1662138298141711616 -1662138298183712512 -1662138298225713408 -1662138298270714368 -1662138298315715328 -1662138298360716288 -1662138298405717248 -1662138298447718144 -1662138298492719104 -1662138298534720000 -1662138298576720896 -1662138298618721792 -1662138298660722688 -1662138298702723584 -1662138298744724480 -1662138298798725632 -1662138298840726528 -1662138298888727552 -1662138298936728576 -1662138298981729536 -1662138299023730432 -1662138299065731328 -1662138299107732224 -1662138299155733248 -1662138299197734144 -1662138299239735040 -1662138299287736064 -1662138299329736960 -1662138299374737920 -1662138299428739072 -1662138299479740160 -1662138299527741184 -1662138299578742272 -1662138299620743168 -1662138299662744064 -1662138299707745024 -1662138299749745920 -1662138299803747072 -1662138299848748032 -1662138299902749184 -1662138299944750080 -1662138299986750976 -1662138300028751872 -1662138300073752832 -1662138300118753792 -1662138300160754688 -1662138300199755520 -1662138300241756416 -1662138300286757376 -1662138300331758336 -1662138300373759232 -1662138300421760256 -1662138300463761152 -1662138300505762048 -1662138300559763200 -1662138300601764096 -1662138300643764992 -1662138300691766016 -1662138300730766848 -1662138300781767936 -1662138300823768832 -1662138300865769728 -1662138300904770560 -1662138300949771520 -1662138300997772544 -1662138301039773440 -1662138301087774464 -1662138301129775360 -1662138301174776320 -1662138301222777344 -1662138301264778240 -1662138301306779136 -1662138301351780096 -1662138301399781120 -1662138301441782016 -1662138301489783040 -1662138301531783936 -1662138301573784832 -1662138301621785856 -1662138301666786816 -1662138301708787712 -1662138301753788672 -1662138301795789568 -1662138301837790464 -1662138301879791360 -1662138301927792384 -1662138301978793472 -1662138302023794432 -1662138302065795328 -1662138302116796416 -1662138302167797504 -1662138302215798528 -1662138302266799616 -1662138302308800512 -1662138302356801536 -1662138302398802432 -1662138302446803456 -1662138302488804352 -1662138302533805312 -1662138302587806464 -1662138302629807360 -1662138302671808256 -1662138302713809152 -1662138302758810112 -1662138302803811072 -1662138302851812096 -1662138302896813056 -1662138302938813952 -1662138302983814912 -1662138303025815808 -1662138303073816832 -1662138303118817792 -1662138303163818752 -1662138303208819712 -1662138303256820736 -1662138303298821632 -1662138303340822528 -1662138303391823616 -1662138303439824640 -1662138303487825664 -1662138303532826624 -1662138303577827584 -1662138303625828608 -1662138303667829504 -1662138303709830400 -1662138303754831360 -1662138303799832320 -1662138303844833280 -1662138303886834176 -1662138303937835264 -1662138303982836224 -1662138304024837120 -1662138304066838016 -1662138304114839040 -1662138304171840256 -1662138304213841152 -1662138304264842240 -1662138304309843200 -1662138304357844224 -1662138304405845248 -1662138304450846208 -1662138304492847104 -1662138304540848128 -1662138304585849088 -1662138304627849984 -1662138304675851008 -1662138304720851968 -1662138304765852928 -1662138304813853952 -1662138304855854848 -1662138304903855872 -1662138304948856832 -1662138304999857920 -1662138305047858944 -1662138305089859840 -1662138305140860928 -1662138305194862080 -1662138305239863040 -1662138305278863872 -1662138305326864896 -1662138305374865920 -1662138305419866880 -1662138305461867776 -1662138305509868800 -1662138305557869824 -1662138305599870720 -1662138305647871744 -1662138305689872640 -1662138305734873600 -1662138305776874496 -1662138305830875648 -1662138305878876672 -1662138305929877760 -1662138305974878720 -1662138306019879680 -1662138306073880832 -1662138306115881728 -1662138306160882688 -1662138306202883584 -1662138306250884608 -1662138306292885504 -1662138306334886400 -1662138306376887296 -1662138306421888256 -1662138306463889152 -1662138306505890048 -1662138306565891328 -1662138306610892288 -1662138306652893184 -1662138306694894080 -1662138306742895104 -1662138306787896064 -1662138306838897152 -1662138306880898048 -1662138306925899008 -1662138306970899968 -1662138307021901056 -1662138307060901888 -1662138307105902848 -1662138307147903744 -1662138307192904704 -1662138307237905664 -1662138307288906752 -1662138307327907584 -1662138307375908608 -1662138307420909568 -1662138307468910592 -1662138307516911616 -1662138307561912576 -1662138307612913664 -1662138307654914560 -1662138307705915648 -1662138307753916672 -1662138307801917696 -1662138307852918784 -1662138307900919808 -1662138307948920832 -1662138307990921728 -1662138308032922624 -1662138308080923648 -1662138308125924608 -1662138308176925696 -1662138308221926656 -1662138308266927616 -1662138308308928512 -1662138308356929536 -1662138308401930496 -1662138308446931456 -1662138308494932480 -1662138308545933568 -1662138308584934400 -1662138308623935232 -1662138308668936192 -1662138308713937152 -1662138308758938112 -1662138308800939008 -1662138308845939968 -1662138308887940864 -1662138308929941760 -1662138308980942848 -1662138309022943744 -1662138309064944640 -1662138309109945600 -1662138309157946624 -1662138309205947648 -1662138309256948736 -1662138309301949696 -1662138309352950784 -1662138309397951744 -1662138309442952704 -1662138309493953792 -1662138309535954688 -1662138309583955712 -1662138309634956800 -1662138309676957696 -1662138309718958592 -1662138309763959552 -1662138309805960448 -1662138309859961600 -1662138309907962624 -1662138309949963520 -1662138310006964736 -1662138310048965632 -1662138310090966528 -1662138310138967552 -1662138310183968512 -1662138310225969408 -1662138310282970624 -1662138310321971456 -1662138310363972352 -1662138310411973376 -1662138310456974336 -1662138310501975296 -1662138310552976384 -1662138310594977280 -1662138310639978240 -1662138310684979200 -1662138310729980160 -1662138310771981056 -1662138310819982080 -1662138310861982976 -1662138310909984000 -1662138310960985088 -1662138311011986176 -1662138311065987328 -1662138311110988288 -1662138311152989184 -1662138311194990080 -1662138311239991040 -1662138311284992000 -1662138311332993024 -1662138311380994048 -1662138311428995072 -1662138311479996160 -1662138311530997248 -1662138311578998272 -1662138311623999232 -1662138311675000320 -1662138311717001216 -1662138311759002112 -1662138311804003072 -1662138311855004160 -1662138311906005248 -1662138311951006208 -1662138311993007104 -1662138312044008192 -1662138312089009152 -1662138312134010112 -1662138312179011072 -1662138312224012032 -1662138312266012928 -1662138312314013952 -1662138312362014976 -1662138312407015936 -1662138312449016832 -1662138312497017856 -1662138312536018688 -1662138312593019904 -1662138312638020864 -1662138312686021888 -1662138312731022848 -1662138312782023936 -1662138312830024960 -1662138312878025984 -1662138312920026880 -1662138312962027776 -1662138313010028800 -1662138313064029952 -1662138313112030976 -1662138313163032064 -1662138313208033024 -1662138313253033984 -1662138313301035008 -1662138313343035904 -1662138313388036864 -1662138313427037696 -1662138313472038656 -1662138313517039616 -1662138313565040640 -1662138313610041600 -1662138313658042624 -1662138313703043584 -1662138313748044544 -1662138313787045376 -1662138313841046528 -1662138313886047488 -1662138313931048448 -1662138313976049408 -1662138314021050368 -1662138314063051264 -1662138314111052288 -1662138314156053248 -1662138314201054208 -1662138314258055424 -1662138314303056384 -1662138314345057280 -1662138314387058176 -1662138314432059136 -1662138314474060032 -1662138314516060928 -1662138314564061952 -1662138314612062976 -1662138314657063936 -1662138314696064768 -1662138314738065664 -1662138314783066624 -1662138314783066624 -1662138314828067584 -1662138314873068544 -1662138314915069440 -1662138314957070336 -1662138314999071232 -1662138315041072128 -1662138315080072960 -1662138315128073984 -1662138315176075008 -1662138315224076032 -1662138315269076992 -1662138315317078016 -1662138315362078976 -1662138315410080000 -1662138315461081088 -1662138315509082112 -1662138315551083008 -1662138315599084032 -1662138315641084928 -1662138315683085824 -1662138315728086784 -1662138315770087680 -1662138315815088640 -1662138315854089472 -1662138315905090560 -1662138315947091456 -1662138315992092416 -1662138316037093376 -1662138316082094336 -1662138316133095424 -1662138316178096384 -1662138316223097344 -1662138316265098240 -1662138316310099200 -1662138316358100224 -1662138316397101056 -1662138316442102016 -1662138316493103104 -1662138316538104064 -1662138316583105024 -1662138316625105920 -1662138316676107008 -1662138316727108096 -1662138316772109056 -1662138316814109952 -1662138316859110912 -1662138316901111808 -1662138316946112768 -1662138316994113792 -1662138317036114688 -1662138317081115648 -1662138317123116544 -1662138317165117440 diff --git a/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_light.txt b/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_light.txt deleted file mode 100644 index cca6f70bc4..0000000000 --- a/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track0_light.txt +++ /dev/null @@ -1,2421 +0,0 @@ -1662135911410189568 -1662135911452190464 -1662135911491191296 -1662135911539192320 -1662135911584193280 -1662135911638194432 -1662135911683195392 -1662135911731196416 -1662135911776197376 -1662135911824198400 -1662135911866199296 -1662135911908200192 -1662135911953201152 -1662135912001202176 -1662135912052203264 -1662135912094204160 -1662135912136205056 -1662135912181206016 -1662135912232207104 -1662135912280208128 -1662135912322209024 -1662135912370210048 -1662135912412210944 -1662135912454211840 -1662135912496212736 -1662135912538213632 -1662135912583214592 -1662135912625215488 -1662135912667216384 -1662135912712217344 -1662135912754218240 -1662135912796219136 -1662135912844220160 -1662135912889221120 -1662135912928221952 -1662135912970222848 -1662135913015223808 -1662135913057224704 -1662135913108225792 -1662135913159226880 -1662135913210227968 -1662135913249228800 -1662135913306230016 -1662135913351230976 -1662135913396231936 -1662135913441232896 -1662135913492233984 -1662135913540235008 -1662135913585235968 -1662135913639237120 -1662135913681238016 -1662135913729239040 -1662135913774240000 -1662135913825241088 -1662135913867241984 -1662135913909242880 -1662135913951243776 -1662135913993244672 -1662135914041245696 -1662135914086246656 -1662135914131247616 -1662135914173248512 -1662135914218249472 -1662135914260250368 -1662135914302251264 -1662135914350252288 -1662135914392253184 -1662135914437254144 -1662135914491255296 -1662135914530256128 -1662135914569256960 -1662135914611257856 -1662135914653258752 -1662135914698259712 -1662135914740260608 -1662135914782261504 -1662135914824262400 -1662135914866263296 -1662135914908264192 -1662135914953265152 -1662135914998266112 -1662135915046267136 -1662135915091268096 -1662135915136269056 -1662135915181270016 -1662135915223270912 -1662135915277272064 -1662135915325273088 -1662135915364273920 -1662135915415275008 -1662135915457275904 -1662135915499276800 -1662135915544277760 -1662135915586278656 -1662135915628279552 -1662135915676280576 -1662135915718281472 -1662135915772282624 -1662135915811283456 -1662135915853284352 -1662135915907285504 -1662135915949286400 -1662135915994287360 -1662135916039288320 -1662135916093289472 -1662135916135290368 -1662135916177291264 -1662135916222292224 -1662135916267293184 -1662135916309294080 -1662135916351294976 -1662135916393295872 -1662135916438296832 -1662135916486297856 -1662135916531298816 -1662135916573299712 -1662135916621300736 -1662135916669301760 -1662135916714302720 -1662135916759303680 -1662135916807304704 -1662135916849305600 -1662135916891306496 -1662135916933307392 -1662135916984308480 -1662135917035309568 -1662135917080310528 -1662135917125311488 -1662135917167312384 -1662135917212313344 -1662135917257314304 -1662135917311315456 -1662135917356316416 -1662135917395317248 -1662135917437318144 -1662135917482319104 -1662135917524320000 -1662135917569320960 -1662135917623322112 -1662135917668323072 -1662135917716324096 -1662135917758324992 -1662135917800325888 -1662135917839326720 -1662135917887327744 -1662135917929328640 -1662135917971329536 -1662135918013330432 -1662135918052331264 -1662135918094332160 -1662135918136333056 -1662135918178333952 -1662135918220334848 -1662135918262335744 -1662135918307336704 -1662135918361337856 -1662135918406338816 -1662135918448339712 -1662135918508340992 -1662135918550341888 -1662135918592342784 -1662135918643343872 -1662135918685344768 -1662135918733345792 -1662135918775346688 -1662135918817347584 -1662135918856348416 -1662135918898349312 -1662135918946350336 -1662135918994351360 -1662135919036352256 -1662135919078353152 -1662135919120354048 -1662135919159354880 -1662135919201355776 -1662135919246356736 -1662135919294357760 -1662135919342358784 -1662135919387359744 -1662135919429360640 -1662135919474361600 -1662135919513362432 -1662135919555363328 -1662135919597364224 -1662135919645365248 -1662135919690366208 -1662135919732367104 -1662135919774368000 -1662135919816368896 -1662135919861369856 -1662135919906370816 -1662135919951371776 -1662135920005372928 -1662135920047373824 -1662135920095374848 -1662135920140375808 -1662135920185376768 -1662135920230377728 -1662135920272378624 -1662135920314379520 -1662135920356380416 -1662135920398381312 -1662135920440382208 -1662135920488383232 -1662135920536384256 -1662135920578385152 -1662135920617385984 -1662135920659386880 -1662135920704387840 -1662135920749388800 -1662135920797389824 -1662135920851390976 -1662135920896391936 -1662135920941392896 -1662135920983393792 -1662135921025394688 -1662135921070395648 -1662135921115396608 -1662135921154397440 -1662135921196398336 -1662135921250399488 -1662135921292400384 -1662135921358401792 -1662135921406402816 -1662135921448403712 -1662135921496404736 -1662135921544405760 -1662135921595406848 -1662135921640407808 -1662135921685408768 -1662135921724409600 -1662135921775410688 -1662135921823411712 -1662135921865412608 -1662135921907413504 -1662135921952414464 -1662135921997415424 -1662135922039416320 -1662135922081417216 -1662135922123418112 -1662135922165419008 -1662135922207419904 -1662135922249420800 -1662135922300421888 -1662135922345422848 -1662135922390423808 -1662135922435424768 -1662135922480425728 -1662135922522426624 -1662135922567427584 -1662135922609428480 -1662135922654429440 -1662135922705430528 -1662135922750431488 -1662135922792432384 -1662135922840433408 -1662135922897434624 -1662135922942435584 -1662135922987436544 -1662135923029437440 -1662135923071438336 -1662135923113439232 -1662135923155440128 -1662135923203441152 -1662135923245442048 -1662135923284442880 -1662135923326443776 -1662135923365444608 -1662135923407445504 -1662135923449446400 -1662135923491447296 -1662135923533448192 -1662135923578449152 -1662135923620450048 -1662135923674451200 -1662135923716452096 -1662135923758452992 -1662135923800453888 -1662135923848454912 -1662135923890455808 -1662135923932456704 -1662135923983457792 -1662135924025458688 -1662135924079459840 -1662135924121460736 -1662135924163461632 -1662135924208462592 -1662135924268463872 -1662135924310464768 -1662135924355465728 -1662135924394466560 -1662135924436467456 -1662135924481468416 -1662135924532469504 -1662135924577470464 -1662135924616471296 -1662135924667472384 -1662135924709473280 -1662135924751474176 -1662135924793475072 -1662135924835475968 -1662135924883476992 -1662135924925477888 -1662135924973478912 -1662135925015479808 -1662135925057480704 -1662135925099481600 -1662135925147482624 -1662135925186483456 -1662135925228484352 -1662135925273485312 -1662135925315486208 -1662135925360487168 -1662135925408488192 -1662135925453489152 -1662135925495490048 -1662135925540491008 -1662135925582491904 -1662135925624492800 -1662135925663493632 -1662135925708494592 -1662135925750495488 -1662135925798496512 -1662135925846497536 -1662135925888498432 -1662135925930499328 -1662135925987500544 -1662135926035501568 -1662135926077502464 -1662135926122503424 -1662135926164504320 -1662135926209505280 -1662135926263506432 -1662135926311507456 -1662135926353508352 -1662135926401509376 -1662135926449510400 -1662135926488511232 -1662135926530512128 -1662135926578513152 -1662135926620514048 -1662135926665515008 -1662135926707515904 -1662135926749516800 -1662135926791517696 -1662135926833518592 -1662135926875519488 -1662135926914520320 -1662135926959521280 -1662135927001522176 -1662135927055523328 -1662135927097524224 -1662135927148525312 -1662135927199526400 -1662135927238527232 -1662135927280528128 -1662135927322529024 -1662135927367529984 -1662135927406530816 -1662135927445531648 -1662135927487532544 -1662135927538533632 -1662135927580534528 -1662135927622535424 -1662135927664536320 -1662135927709537280 -1662135927760538368 -1662135927802539264 -1662135927850540288 -1662135927892541184 -1662135927937542144 -1662135927988543232 -1662135928030544128 -1662135928075545088 -1662135928120546048 -1662135928162546944 -1662135928207547904 -1662135928255548928 -1662135928303549952 -1662135928345550848 -1662135928393551872 -1662135928435552768 -1662135928477553664 -1662135928519554560 -1662135928561555456 -1662135928603556352 -1662135928645557248 -1662135928687558144 -1662135928729559040 -1662135928774560000 -1662135928822561024 -1662135928864561920 -1662135928912562944 -1662135928954563840 -1662135929002564864 -1662135929041565696 -1662135929083566592 -1662135929125567488 -1662135929167568384 -1662135929212569344 -1662135929257570304 -1662135929299571200 -1662135929341572096 -1662135929386573056 -1662135929428573952 -1662135929467574784 -1662135929512575744 -1662135929566576896 -1662135929608577792 -1662135929659578880 -1662135929707579904 -1662135929749580800 -1662135929800581888 -1662135929842582784 -1662135929884583680 -1662135929926584576 -1662135929968585472 -1662135930010586368 -1662135930061587456 -1662135930103588352 -1662135930154589440 -1662135930199590400 -1662135930241591296 -1662135930283592192 -1662135930328593152 -1662135930367593984 -1662135930415595008 -1662135930460595968 -1662135930511597056 -1662135930553597952 -1662135930598598912 -1662135930640599808 -1662135930685600768 -1662135930730601728 -1662135930778602752 -1662135930820603648 -1662135930865604608 -1662135930907605504 -1662135930952606464 -1662135930997607424 -1662135931039608320 -1662135931081609216 -1662135931135610368 -1662135931180611328 -1662135931222612224 -1662135931270613248 -1662135931321614336 -1662135931372615424 -1662135931420616448 -1662135931465617408 -1662135931507618304 -1662135931549619200 -1662135931591620096 -1662135931639621120 -1662135931684622080 -1662135931726622976 -1662135931774624000 -1662135931819624960 -1662135931870626048 -1662135931912626944 -1662135931960627968 -1662135932002628864 -1662135932065630208 -1662135932107631104 -1662135932149632000 -1662135932209633280 -1662135932254634240 -1662135932299635200 -1662135932350636288 -1662135932392637184 -1662135932434638080 -1662135932482639104 -1662135932524640000 -1662135932566640896 -1662135932608641792 -1662135932650642688 -1662135932695643648 -1662135932743644672 -1662135932785645568 -1662135932830646528 -1662135932875647488 -1662135932917648384 -1662135932959649280 -1662135933004650240 -1662135933049651200 -1662135933091652096 -1662135933133652992 -1662135933178653952 -1662135933223654912 -1662135933268655872 -1662135933310656768 -1662135933358657792 -1662135933403658752 -1662135933454659840 -1662135933499660800 -1662135933541661696 -1662135933589662720 -1662135933631663616 -1662135933679664640 -1662135933718665472 -1662135933757666304 -1662135933802667264 -1662135933853668352 -1662135933898669312 -1662135933940670208 -1662135933979671040 -1662135934024672000 -1662135934066672896 -1662135934111673856 -1662135934156674816 -1662135934210675968 -1662135934255676928 -1662135934297677824 -1662135934345678848 -1662135934387679744 -1662135934429680640 -1662135934468681472 -1662135934513682432 -1662135934555683328 -1662135934600684288 -1662135934642685184 -1662135934684686080 -1662135934729687040 -1662135934771687936 -1662135934816688896 -1662135934858689792 -1662135934900690688 -1662135934942691584 -1662135934990692608 -1662135935032693504 -1662135935077694464 -1662135935119695360 -1662135935158696192 -1662135935209697280 -1662135935251698176 -1662135935293699072 -1662135935344700160 -1662135935389701120 -1662135935431702016 -1662135935482703104 -1662135935524704000 -1662135935572705024 -1662135935620706048 -1662135935668707072 -1662135935713708032 -1662135935758708992 -1662135935803709952 -1662135935845710848 -1662135935887711744 -1662135935932712704 -1662135935974713600 -1662135936019714560 -1662135936067715584 -1662135936106716416 -1662135936154717440 -1662135936196718336 -1662135936235719168 -1662135936277720064 -1662135936325721088 -1662135936367721984 -1662135936415723008 -1662135936457723904 -1662135936499724800 -1662135936544725760 -1662135936592726784 -1662135936631727616 -1662135936679728640 -1662135936727729664 -1662135936772730624 -1662135936814731520 -1662135936856732416 -1662135936907733504 -1662135936949734400 -1662135936997735424 -1662135937045736448 -1662135937093737472 -1662135937135738368 -1662135937180739328 -1662135937222740224 -1662135937267741184 -1662135937306742016 -1662135937351742976 -1662135937396743936 -1662135937435744768 -1662135937477745664 -1662135937522746624 -1662135937567747584 -1662135937609748480 -1662135937660749568 -1662135937705750528 -1662135937756751616 -1662135937804752640 -1662135937846753536 -1662135937903754752 -1662135937942755584 -1662135937984756480 -1662135938032757504 -1662135938071758336 -1662135938119759360 -1662135938161760256 -1662135938212761344 -1662135938254762240 -1662135938308763392 -1662135938350764288 -1662135938395765248 -1662135938452766464 -1662135938500767488 -1662135938539768320 -1662135938584769280 -1662135938629770240 -1662135938671771136 -1662135938716772096 -1662135938764773120 -1662135938815774208 -1662135938863775232 -1662135938905776128 -1662135938953777152 -1662135939001778176 -1662135939043779072 -1662135939094780160 -1662135939142781184 -1662135939187782144 -1662135939235783168 -1662135939274784000 -1662135939322785024 -1662135939367785984 -1662135939409786880 -1662135939460787968 -1662135939502788864 -1662135939541789696 -1662135939592790784 -1662135939637791744 -1662135939688792832 -1662135939736793856 -1662135939778794752 -1662135939820795648 -1662135939865796608 -1662135939919797760 -1662135939961798656 -1662135940006799616 -1662135940045800448 -1662135940093801472 -1662135940135802368 -1662135940180803328 -1662135940228804352 -1662135940282805504 -1662135940327806464 -1662135940372807424 -1662135940426808576 -1662135940468809472 -1662135940510810368 -1662135940552811264 -1662135940603812352 -1662135940642813184 -1662135940681814016 -1662135940723814912 -1662135940765815808 -1662135940807816704 -1662135940849817600 -1662135940888818432 -1662135940930819328 -1662135940978820352 -1662135941023821312 -1662135941065822208 -1662135941107823104 -1662135941149824000 -1662135941188824832 -1662135941233825792 -1662135941281826816 -1662135941323827712 -1662135941365828608 -1662135941413829632 -1662135941455830528 -1662135941500831488 -1662135941542832384 -1662135941581833216 -1662135941623834112 -1662135941665835008 -1662135941707835904 -1662135941746836736 -1662135941791837696 -1662135941833838592 -1662135941878839552 -1662135941929840640 -1662135941977841664 -1662135942025842688 -1662135942061843456 -1662135942103844352 -1662135942145845248 -1662135942199846400 -1662135942247847424 -1662135942292848384 -1662135942334849280 -1662135942388850432 -1662135942433851392 -1662135942478852352 -1662135942520853248 -1662135942562854144 -1662135942613855232 -1662135942658856192 -1662135942700857088 -1662135942751858176 -1662135942793859072 -1662135942835859968 -1662135942883860992 -1662135942925861888 -1662135942967862784 -1662135943006863616 -1662135943048864512 -1662135943093865472 -1662135943138866432 -1662135943186867456 -1662135943234868480 -1662135943276869376 -1662135943321870336 -1662135943369871360 -1662135943408872192 -1662135943456873216 -1662135943501874176 -1662135943543875072 -1662135943582875904 -1662135943627876864 -1662135943669877760 -1662135943720878848 -1662135943762879744 -1662135943804880640 -1662135943849881600 -1662135943894882560 -1662135943945883648 -1662135943996884736 -1662135944038885632 -1662135944083886592 -1662135944134887680 -1662135944182888704 -1662135944224889600 -1662135944275890688 -1662135944317891584 -1662135944362892544 -1662135944410893568 -1662135944452894464 -1662135944497895424 -1662135944551896576 -1662135944593897472 -1662135944635898368 -1662135944680899328 -1662135944731900416 -1662135944776901376 -1662135944824902400 -1662135944878903552 -1662135944923904512 -1662135944965905408 -1662135945010906368 -1662135945058907392 -1662135945100908288 -1662135945142909184 -1662135945190910208 -1662135945235911168 -1662135945289912320 -1662135945331913216 -1662135945376914176 -1662135945421915136 -1662135945466916096 -1662135945508916992 -1662135945550917888 -1662135945595918848 -1662135945634919680 -1662135945679920640 -1662135945727921664 -1662135945775922688 -1662135945817923584 -1662135945862924544 -1662135945904925440 -1662135945949926400 -1662135945991927296 -1662135946036928256 -1662135946081929216 -1662135946123930112 -1662135946165931008 -1662135946216932096 -1662135946261933056 -1662135946306934016 -1662135946351934976 -1662135946393935872 -1662135946438936832 -1662135946477937664 -1662135946519938560 -1662135946564939520 -1662135946609940480 -1662135946651941376 -1662135946690942208 -1662135946735943168 -1662135946783944192 -1662135946825945088 -1662135946867945984 -1662135946918947072 -1662135946963948032 -1662135947005948928 -1662135947047949824 -1662135947095950848 -1662135947134951680 -1662135947188952832 -1662135947236953856 -1662135947278954752 -1662135947320955648 -1662135947368956672 -1662135947410957568 -1662135947452958464 -1662135947494959360 -1662135947539960320 -1662135947578961152 -1662135947623962112 -1662135947665963008 -1662135947716964096 -1662135947758964992 -1662135947800965888 -1662135947842966784 -1662135947890967808 -1662135947941968896 -1662135947989969920 -1662135948031970816 -1662135948079971840 -1662135948121972736 -1662135948163973632 -1662135948211974656 -1662135948253975552 -1662135948292976384 -1662135948337977344 -1662135948382978304 -1662135948430979328 -1662135948472980224 -1662135948514981120 -1662135948553981952 -1662135948595982848 -1662135948637983744 -1662135948685984768 -1662135948730985728 -1662135948772986624 -1662135948814987520 -1662135948856988416 -1662135948895989248 -1662135948937990144 -1662135948982991104 -1662135949033992192 -1662135949078993152 -1662135949120994048 -1662135949174995200 -1662135949216996096 -1662135949261997056 -1662135949306998016 -1662135949348998912 -1662135949393999872 -1662135949439000832 -1662135949481001728 -1662135949529002752 -1662135949568003584 -1662135949616004608 -1662135949667005696 -1662135949709006592 -1662135949754007552 -1662135949796008448 -1662135949838009344 -1662135949886010368 -1662135949928011264 -1662135949970012160 -1662135950012013056 -1662135950057014016 -1662135950099014912 -1662135950144015872 -1662135950186016768 -1662135950240017920 -1662135950285018880 -1662135950327019776 -1662135950375020800 -1662135950417021696 -1662135950468022784 -1662135950510023680 -1662135950558024704 -1662135950600025600 -1662135950642026496 -1662135950690027520 -1662135950735028480 -1662135950777029376 -1662135950822030336 -1662135950870031360 -1662135950918032384 -1662135950960033280 -1662135951002034176 -1662135951047035136 -1662135951089036032 -1662135951146037248 -1662135951188038144 -1662135951230039040 -1662135951272039936 -1662135951317040896 -1662135951368041984 -1662135951413042944 -1662135951455043840 -1662135951494044672 -1662135951545045760 -1662135951587046656 -1662135951632047616 -1662135951674048512 -1662135951722049536 -1662135951770050560 -1662135951815051520 -1662135951860052480 -1662135951902053376 -1662135951944054272 -1662135951986055168 -1662135952028056064 -1662135952067056896 -1662135952112057856 -1662135952154058752 -1662135952196059648 -1662135952238060544 -1662135952280061440 -1662135952337062656 -1662135952379063552 -1662135952424064512 -1662135952466065408 -1662135952517066496 -1662135952559067392 -1662135952616068608 -1662135952661069568 -1662135952709070592 -1662135952763071744 -1662135952808072704 -1662135952850073600 -1662135952895074560 -1662135952937075456 -1662135952982076416 -1662135953033077504 -1662135953075078400 -1662135953117079296 -1662135953159080192 -1662135953201081088 -1662135953243081984 -1662135953291083008 -1662135953333083904 -1662135953384084992 -1662135953426085888 -1662135953471086848 -1662135953513087744 -1662135953555088640 -1662135953603089664 -1662135953651090688 -1662135953693091584 -1662135953741092608 -1662135953786093568 -1662135953828094464 -1662135953870095360 -1662135953912096256 -1662135953957097216 -1662135953999098112 -1662135954044099072 -1662135954092100096 -1662135954134100992 -1662135954176101888 -1662135954218102784 -1662135954260103680 -1662135954308104704 -1662135954353105664 -1662135954392106496 -1662135954431107328 -1662135954479108352 -1662135954518109184 -1662135954566110208 -1662135954611111168 -1662135954656112128 -1662135954704113152 -1662135954746114048 -1662135954791115008 -1662135954833115904 -1662135954878116864 -1662135954923117824 -1662135954965118720 -1662135955016119808 -1662135955058120704 -1662135955097121536 -1662135955136122368 -1662135955178123264 -1662135955217124096 -1662135955259124992 -1662135955304125952 -1662135955346126848 -1662135955391127808 -1662135955436128768 -1662135955487129856 -1662135955526130688 -1662135955568131584 -1662135955610132480 -1662135955655133440 -1662135955697134336 -1662135955739135232 -1662135955781136128 -1662135955826137088 -1662135955868137984 -1662135955913138944 -1662135955964140032 -1662135956009140992 -1662135956057142016 -1662135956105143040 -1662135956153144064 -1662135956195144960 -1662135956240145920 -1662135956288146944 -1662135956336147968 -1662135956381148928 -1662135956426149888 -1662135956468150784 -1662135956513151744 -1662135956555152640 -1662135956600153600 -1662135956648154624 -1662135956690155520 -1662135956732156416 -1662135956774157312 -1662135956828158464 -1662135956876159488 -1662135956921160448 -1662135956963161344 -1662135957008162304 -1662135957056163328 -1662135957104164352 -1662135957146165248 -1662135957188166144 -1662135957230167040 -1662135957266167808 -1662135957308168704 -1662135957350169600 -1662135957392170496 -1662135957437171456 -1662135957479172352 -1662135957521173248 -1662135957566174208 -1662135957608175104 -1662135957650176000 -1662135957695176960 -1662135957734177792 -1662135957785178880 -1662135957827179776 -1662135957869180672 -1662135957911181568 -1662135957956182528 -1662135958001183488 -1662135958046184448 -1662135958088185344 -1662135958130186240 -1662135958175187200 -1662135958226188288 -1662135958268189184 -1662135958310190080 -1662135958352190976 -1662135958394191872 -1662135958445192960 -1662135958487193856 -1662135958529194752 -1662135958565195520 -1662135958610196480 -1662135958652197376 -1662135958694198272 -1662135958739199232 -1662135958781200128 -1662135958826201088 -1662135958868201984 -1662135958910202880 -1662135958952203776 -1662135958994204672 -1662135959039205632 -1662135959084206592 -1662135959129207552 -1662135959174208512 -1662135959216209408 -1662135959261210368 -1662135959306211328 -1662135959351212288 -1662135959396213248 -1662135959438214144 -1662135959483215104 -1662135959531216128 -1662135959573217024 -1662135959615217920 -1662135959654218752 -1662135959696219648 -1662135959738220544 -1662135959780221440 -1662135959825222400 -1662135959870223360 -1662135959909224192 -1662135959951225088 -1662135959999226112 -1662135960041227008 -1662135960083227904 -1662135960125228800 -1662135960167229696 -1662135960218230784 -1662135960260231680 -1662135960299232512 -1662135960347233536 -1662135960392234496 -1662135960440235520 -1662135960485236480 -1662135960539237632 -1662135960584238592 -1662135960635239680 -1662135960680240640 -1662135960725241600 -1662135960776242688 -1662135960818243584 -1662135960863244544 -1662135960908245504 -1662135960950246400 -1662135961001247488 -1662135961043248384 -1662135961085249280 -1662135961127250176 -1662135961178251264 -1662135961220252160 -1662135961265253120 -1662135961307254016 -1662135961352254976 -1662135961400256000 -1662135961448257024 -1662135961490257920 -1662135961535258880 -1662135961580259840 -1662135961619260672 -1662135961658261504 -1662135961700262400 -1662135961742263296 -1662135961784264192 -1662135961826265088 -1662135961868265984 -1662135961907266816 -1662135961949267712 -1662135961991268608 -1662135962039269632 -1662135962081270528 -1662135962123271424 -1662135962165272320 -1662135962210273280 -1662135962252274176 -1662135962303275264 -1662135962345276160 -1662135962387277056 -1662135962432278016 -1662135962477278976 -1662135962528280064 -1662135962570280960 -1662135962615281920 -1662135962657282816 -1662135962699283712 -1662135962741284608 -1662135962792285696 -1662135962837286656 -1662135962882287616 -1662135962924288512 -1662135962972289536 -1662135963014290432 -1662135963065291520 -1662135963113292544 -1662135963164293632 -1662135963212294656 -1662135963254295552 -1662135963299296512 -1662135963341297408 -1662135963386298368 -1662135963425299200 -1662135963467300096 -1662135963512301056 -1662135963554301952 -1662135963596302848 -1662135963644303872 -1662135963686304768 -1662135963728305664 -1662135963773306624 -1662135963815307520 -1662135963857308416 -1662135963902309376 -1662135963947310336 -1662135963995311360 -1662135964040312320 -1662135964088313344 -1662135964139314432 -1662135964181315328 -1662135964223316224 -1662135964271317248 -1662135964313318144 -1662135964358319104 -1662135964406320128 -1662135964445320960 -1662135964487321856 -1662135964532322816 -1662135964574323712 -1662135964619324672 -1662135964667325696 -1662135964709326592 -1662135964754327552 -1662135964796328448 -1662135964835329280 -1662135964883330304 -1662135964928331264 -1662135964970332160 -1662135965012333056 -1662135965057334016 -1662135965108335104 -1662135965144335872 -1662135965186336768 -1662135965234337792 -1662135965276338688 -1662135965327339776 -1662135965369340672 -1662135965414341632 -1662135965459342592 -1662135965507343616 -1662135965549344512 -1662135965591345408 -1662135965633346304 -1662135965678347264 -1662135965720348160 -1662135965765349120 -1662135965810350080 -1662135965852350976 -1662135965894351872 -1662135965933352704 -1662135965972353536 -1662135966017354496 -1662135966065355520 -1662135966107356416 -1662135966152357376 -1662135966191358208 -1662135966239359232 -1662135966284360192 -1662135966329361152 -1662135966371362048 -1662135966419363072 -1662135966464364032 -1662135966512365056 -1662135966551365888 -1662135966596366848 -1662135966638367744 -1662135966680368640 -1662135966719369472 -1662135966761370368 -1662135966803371264 -1662135966848372224 -1662135966890373120 -1662135966932374016 -1662135966974374912 -1662135967025376000 -1662135967067376896 -1662135967115377920 -1662135967160378880 -1662135967202379776 -1662135967250380800 -1662135967295381760 -1662135967340382720 -1662135967382383616 -1662135967424384512 -1662135967466385408 -1662135967505386240 -1662135967550387200 -1662135967592388096 -1662135967646389248 -1662135967685390080 -1662135967733391104 -1662135967775392000 -1662135967817392896 -1662135967874394112 -1662135967919395072 -1662135967961395968 -1662135968012397056 -1662135968054397952 -1662135968096398848 -1662135968141399808 -1662135968186400768 -1662135968225401600 -1662135968264402432 -1662135968312403456 -1662135968360404480 -1662135968402405376 -1662135968447406336 -1662135968492407296 -1662135968534408192 -1662135968582409216 -1662135968624410112 -1662135968666411008 -1662135968708411904 -1662135968747412736 -1662135968789413632 -1662135968834414592 -1662135968879415552 -1662135968921416448 -1662135968963417344 -1662135969008418304 -1662135969050419200 -1662135969092420096 -1662135969137421056 -1662135969182422016 -1662135969227422976 -1662135969269423872 -1662135969311424768 -1662135969356425728 -1662135969404426752 -1662135969452427776 -1662135969497428736 -1662135969548429824 -1662135969596430848 -1662135969641431808 -1662135969695432960 -1662135969740433920 -1662135969779434752 -1662135969821435648 -1662135969863436544 -1662135969908437504 -1662135969953438464 -1662135970004439552 -1662135970043440384 -1662135970088441344 -1662135970130442240 -1662135970178443264 -1662135970223444224 -1662135970265445120 -1662135970307446016 -1662135970358447104 -1662135970400448000 -1662135970445448960 -1662135970487449856 -1662135970526450688 -1662135970565451520 -1662135970607452416 -1662135970649453312 -1662135970691454208 -1662135970736455168 -1662135970781456128 -1662135970829457152 -1662135970871458048 -1662135970913458944 -1662135970958459904 -1662135971006460928 -1662135971063462144 -1662135971105463040 -1662135971150464000 -1662135971198465024 -1662135971240465920 -1662135971285466880 -1662135971336467968 -1662135971381468928 -1662135971426469888 -1662135971468470784 -1662135971510471680 -1662135971552472576 -1662135971600473600 -1662135971642474496 -1662135971690475520 -1662135971741476608 -1662135971786477568 -1662135971831478528 -1662135971876479488 -1662135971918480384 -1662135971960481280 -1662135972014482432 -1662135972068483584 -1662135972116484608 -1662135972164485632 -1662135972209486592 -1662135972254487552 -1662135972296488448 -1662135972344489472 -1662135972395490560 -1662135972443491584 -1662135972488492544 -1662135972533493504 -1662135972575494400 -1662135972620495360 -1662135972662496256 -1662135972704497152 -1662135972749498112 -1662135972797499136 -1662135972842500096 -1662135972887501056 -1662135972926501888 -1662135972974502912 -1662135973016503808 -1662135973070504960 -1662135973115505920 -1662135973160506880 -1662135973205507840 -1662135973262509056 -1662135973304509952 -1662135973346510848 -1662135973391511808 -1662135973433512704 -1662135973472513536 -1662135973514514432 -1662135973556515328 -1662135973598516224 -1662135973649517312 -1662135973700518400 -1662135973748519424 -1662135973793520384 -1662135973835521280 -1662135973883522304 -1662135973928523264 -1662135973976524288 -1662135974018525184 -1662135974060526080 -1662135974108527104 -1662135974150528000 -1662135974192528896 -1662135974237529856 -1662135974282530816 -1662135974324531712 -1662135974369532672 -1662135974411533568 -1662135974456534528 -1662135974501535488 -1662135974543536384 -1662135974585537280 -1662135974627538176 -1662135974681539328 -1662135974729540352 -1662135974771541248 -1662135974813542144 -1662135974858543104 -1662135974906544128 -1662135974945544960 -1662135974987545856 -1662135975035546880 -1662135975083547904 -1662135975134548992 -1662135975176549888 -1662135975218550784 -1662135975263551744 -1662135975311552768 -1662135975359553792 -1662135975401554688 -1662135975452555776 -1662135975494556672 -1662135975542557696 -1662135975587558656 -1662135975632559616 -1662135975677560576 -1662135975725561600 -1662135975767562496 -1662135975818563584 -1662135975866564608 -1662135975908565504 -1662135975950566400 -1662135975995567360 -1662135976040568320 -1662135976085569280 -1662135976127570176 -1662135976169571072 -1662135976211571968 -1662135976256572928 -1662135976295573760 -1662135976340574720 -1662135976385575680 -1662135976430576640 -1662135976472577536 -1662135976520578560 -1662135976559579392 -1662135976607580416 -1662135976649581312 -1662135976697582336 -1662135976745583360 -1662135976787584256 -1662135976829585152 -1662135976871586048 -1662135976913586944 -1662135976955587840 -1662135977006588928 -1662135977048589824 -1662135977093590784 -1662135977138591744 -1662135977183592704 -1662135977228593664 -1662135977276594688 -1662135977318595584 -1662135977360596480 -1662135977405597440 -1662135977453598464 -1662135977495599360 -1662135977540600320 -1662135977582601216 -1662135977624602112 -1662135977681603328 -1662135977723604224 -1662135977765605120 -1662135977810606080 -1662135977858607104 -1662135977900608000 -1662135977945608960 -1662135977996610048 -1662135978041611008 -1662135978086611968 -1662135978131612928 -1662135978173613824 -1662135978212614656 -1662135978257615616 -1662135978299616512 -1662135978341617408 -1662135978383618304 -1662135978425619200 -1662135978470620160 -1662135978509620992 -1662135978563622144 -1662135978608623104 -1662135978650624000 -1662135978698625024 -1662135978737625856 -1662135978785626880 -1662135978824627712 -1662135978869628672 -1662135978911629568 -1662135978956630528 -1662135978998631424 -1662135979043632384 -1662135979091633408 -1662135979133634304 -1662135979175635200 -1662135979220636160 -1662135979262637056 -1662135979304637952 -1662135979346638848 -1662135979388639744 -1662135979439640832 -1662135979484641792 -1662135979529642752 -1662135979571643648 -1662135979613644544 -1662135979658645504 -1662135979700646400 -1662135979742647296 -1662135979784648192 -1662135979829649152 -1662135979877650176 -1662135979919651072 -1662135979964652032 -1662135980009652992 -1662135980054653952 -1662135980105655040 -1662135980147655936 -1662135980189656832 -1662135980234657792 -1662135980276658688 -1662135980318659584 -1662135980363660544 -1662135980408661504 -1662135980465662720 -1662135980507663616 -1662135980549664512 -1662135980606665728 -1662135980651666688 -1662135980696667648 -1662135980738668544 -1662135980780669440 -1662135980822670336 -1662135980867671296 -1662135980909672192 -1662135980954673152 -1662135980996674048 -1662135981041675008 -1662135981083675904 -1662135981131676928 -1662135981179677952 -1662135981221678848 -1662135981293680384 -1662135981335681280 -1662135981383682304 -1662135981425683200 -1662135981470684160 -1662135981515685120 -1662135981560686080 -1662135981608687104 -1662135981659688192 -1662135981701689088 -1662135981740689920 -1662135981782690816 -1662135981824691712 -1662135981869692672 -1662135981920693760 -1662135981965694720 -1662135982016695808 -1662135982058696704 -1662135982100697600 -1662135982142698496 -1662135982184699392 -1662135982226700288 -1662135982271701248 -1662135982319702272 -1662135982361703168 -1662135982400704000 -1662135982442704896 -1662135982490705920 -1662135982541707008 -1662135982583707904 -1662135982625708800 -1662135982667709696 -1662135982715710720 -1662135982757711616 -1662135982796712448 -1662135982841713408 -1662135982883714304 -1662135982922715136 -1662135982967716096 -1662135983009716992 -1662135983048717824 -1662135983093718784 -1662135983135719680 -1662135983183720704 -1662135983228721664 -1662135983270722560 -1662135983321723648 -1662135983366724608 -1662135983408725504 -1662135983456726528 -1662135983501727488 -1662135983549728512 -1662135983594729472 -1662135983642730496 -1662135983687731456 -1662135983729732352 -1662135983771733248 -1662135983819734272 -1662135983864735232 -1662135983909736192 -1662135983954737152 -1662135983999738112 -1662135984041739008 -1662135984083739904 -1662135984125740800 -1662135984179741952 -1662135984224742912 -1662135984269743872 -1662135984317744896 -1662135984362745856 -1662135984404746752 -1662135984446747648 -1662135984491748608 -1662135984533749504 -1662135984572750336 -1662135984614751232 -1662135984656752128 -1662135984701753088 -1662135984743753984 -1662135984782754816 -1662135984833755904 -1662135984884756992 -1662135984929757952 -1662135984980759040 -1662135985031760128 -1662135985076761088 -1662135985115761920 -1662135985166763008 -1662135985217764096 -1662135985265765120 -1662135985304765952 -1662135985346766848 -1662135985388767744 -1662135985427768576 -1662135985469769472 -1662135985508770304 -1662135985547771136 -1662135985589772032 -1662135985634772992 -1662135985676773888 -1662135985721774848 -1662135985769775872 -1662135985817776896 -1662135985865777920 -1662135985907778816 -1662135985955779840 -1662135986003780864 -1662135986051781888 -1662135986096782848 -1662135986141783808 -1662135986186784768 -1662135986234785792 -1662135986279786752 -1662135986321787648 -1662135986363788544 -1662135986414789632 -1662135986462790656 -1662135986501791488 -1662135986546792448 -1662135986591793408 -1662135986636794368 -1662135986687795456 -1662135986729796352 -1662135986780797440 -1662135986828798464 -1662135986876799488 -1662135986918800384 -1662135986963801344 -1662135987014802432 -1662135987059803392 -1662135987107804416 -1662135987152805376 -1662135987197806336 -1662135987245807360 -1662135987290808320 -1662135987332809216 -1662135987374810112 -1662135987416811008 -1662135987461811968 -1662135987500812800 -1662135987542813696 -1662135987584814592 -1662135987632815616 -1662135987674816512 -1662135987716817408 -1662135987758818304 -1662135987803819264 -1662135987845820160 -1662135987890821120 -1662135987935822080 -1662135987980823040 -1662135988022823936 -1662135988067824896 -1662135988112825856 -1662135988154826752 -1662135988196827648 -1662135988235828480 -1662135988277829376 -1662135988319830272 -1662135988361831168 -1662135988406832128 -1662135988448833024 -1662135988493833984 -1662135988535834880 -1662135988583835904 -1662135988625836800 -1662135988670837760 -1662135988715838720 -1662135988760839680 -1662135988799840512 -1662135988838841344 -1662135988880842240 -1662135988919843072 -1662135988961843968 -1662135989003844864 -1662135989042845696 -1662135989084846592 -1662135989129847552 -1662135989171848448 -1662135989210849280 -1662135989258850304 -1662135989300851200 -1662135989342852096 -1662135989384852992 -1662135989429853952 -1662135989468854784 -1662135989510855680 -1662135989552856576 -1662135989594857472 -1662135989639858432 -1662135989681859328 -1662135989723860224 -1662135989765861120 -1662135989807862016 -1662135989852862976 -1662135989897863936 -1662135989942864896 -1662135989984865792 -1662135990029866752 -1662135990065867520 -1662135990113868544 -1662135990161869568 -1662135990203870464 -1662135990245871360 -1662135990287872256 -1662135990329873152 -1662135990374874112 -1662135990422875136 -1662135990464876032 -1662135990509876992 -1662135990551877888 -1662135990605879040 -1662135990650880000 -1662135990695880960 -1662135990743881984 -1662135990785882880 -1662135990836883968 -1662135990884884992 -1662135990935886080 -1662135990980887040 -1662135991025888000 -1662135991067888896 -1662135991109889792 -1662135991151890688 -1662135991199891712 -1662135991238892544 -1662135991283893504 -1662135991328894464 -1662135991370895360 -1662135991415896320 -1662135991457897216 -1662135991502898176 -1662135991544899072 -1662135991586899968 -1662135991628900864 -1662135991670901760 -1662135991712902656 -1662135991760903680 -1662135991802904576 -1662135991844905472 -1662135991889906432 -1662135991931907328 -1662135991979908352 -1662135992021909248 -1662135992075910400 -1662135992114911232 -1662135992156912128 -1662135992195912960 -1662135992240913920 -1662135992282914816 -1662135992330915840 -1662135992378916864 -1662135992417917696 -1662135992462918656 -1662135992510919680 -1662135992552920576 -1662135992603921664 -1662135992645922560 -1662135992687923456 -1662135992729924352 -1662135992771925248 -1662135992813926144 -1662135992855927040 -1662135992909928192 -1662135992951929088 -1662135992990929920 -1662135993032930816 -1662135993083931904 -1662135993128932864 -1662135993182934016 -1662135993224934912 -1662135993281936128 -1662135993329937152 -1662135993371938048 -1662135993413938944 -1662135993458939904 -1662135993503940864 -1662135993545941760 -1662135993590942720 -1662135993632943616 -1662135993677944576 -1662135993722945536 -1662135993761946368 -1662135993806947328 -1662135993851948288 -1662135993893949184 -1662135993935950080 -1662135993980951040 -1662135994025952000 -1662135994070952960 -1662135994112953856 -1662135994157954816 -1662135994202955776 -1662135994253956864 -1662135994298957824 -1662135994340958720 -1662135994382959616 -1662135994427960576 -1662135994469961472 -1662135994514962432 -1662135994565963520 -1662135994610964480 -1662135994655965440 -1662135994694966272 -1662135994739967232 -1662135994781968128 -1662135994838969344 -1662135994883970304 -1662135994931971328 -1662135994976972288 -1662135995018973184 -1662135995060974080 -1662135995111975168 -1662135995156976128 -1662135995201977088 -1662135995243977984 -1662135995291979008 -1662135995333979904 -1662135995381980928 -1662135995429981952 -1662135995480983040 -1662135995525984000 -1662135995573985024 -1662135995615985920 -1662135995672987136 -1662135995717988096 -1662135995777989376 -1662135995822990336 -1662135995864991232 -1662135995918992384 -1662135995960993280 -1662135995999994112 -1662135996044995072 -1662135996086995968 -1662135996128996864 -1662135996179997952 -1662135996224998912 -1662135996266999808 -1662135996315000832 -1662135996357001728 -1662135996402002688 -1662135996444003584 -1662135996489004544 -1662135996528005376 -1662135996579006464 -1662135996621007360 -1662135996666008320 -1662135996705009152 -1662135996747010048 -1662135996789010944 -1662135996837011968 -1662135996888013056 -1662135996939014144 -1662135996990015232 -1662135997038016256 -1662135997086017280 -1662135997128018176 -1662135997176019200 -1662135997218020096 -1662135997260020992 -1662135997305021952 -1662135997350022912 -1662135997398023936 -1662135997437024768 -1662135997479025664 -1662135997521026560 -1662135997572027648 -1662135997620028672 -1662135997659029504 -1662135997710030592 -1662135997752031488 -1662135997794032384 -1662135997836033280 -1662135997878034176 -1662135997920035072 -1662135997965036032 -1662135998007036928 -1662135998052037888 -1662135998097038848 -1662135998139039744 -1662135998184040704 -1662135998226041600 -1662135998271042560 -1662135998316043520 -1662135998361044480 -1662135998412045568 -1662135998457046528 -1662135998499047424 -1662135998550048512 -1662135998595049472 -1662135998640050432 -1662135998682051328 -1662135998727052288 -1662135998772053248 -1662135998820054272 -1662135998865055232 -1662135998907056128 -1662135998949057024 -1662135998997058048 -1662135999039058944 -1662135999081059840 -1662135999123060736 -1662135999168061696 -1662135999216062720 -1662135999264063744 -1662135999309064704 -1662135999360065792 -1662135999402066688 -1662135999447067648 -1662135999489068544 -1662135999528069376 -1662135999579070464 -1662135999630071552 -1662135999678072576 -1662135999720073472 -1662135999759074304 -1662135999804075264 -1662135999846076160 -1662135999894077184 -1662135999939078144 -1662135999981079040 -1662136000029080064 -1662136000077081088 -1662136000125082112 -1662136000173083136 -1662136000215084032 -1662136000257084928 -1662136000299085824 -1662136000341086720 -1662136000383087616 -1662136000425088512 -1662136000473089536 -1662136000518090496 -1662136000557091328 -1662136000605092352 -1662136000650093312 -1662136000701094400 -1662136000740095232 -1662136000782096128 -1662136000827097088 -1662136000869097984 -1662136000911098880 -1662136000953099776 -1662136000992100608 -1662136001034101504 -1662136001088102656 -1662136001130103552 -1662136001172104448 -1662136001217105408 -1662136001256106240 -1662136001307107328 -1662136001352108288 -1662136001400109312 -1662136001442110208 -1662136001490111232 -1662136001535112192 -1662136001580113152 -1662136001622114048 -1662136001670115072 -1662136001709115904 -1662136001751116800 -1662136001796117760 -1662136001841118720 -1662136001895119872 -1662136001946120960 -1662136001991121920 -1662136002042123008 -1662136002084123904 -1662136002132124928 -1662136002180125952 -1662136002222126848 -1662136002267127808 -1662136002306128640 -1662136002348129536 -1662136002396130560 -1662136002441131520 -1662136002495132672 -1662136002540133632 -1662136002585134592 -1662136002633135616 -1662136002678136576 -1662136002723137536 -1662136002768138496 -1662136002813139456 -1662136002852140288 -1662136002894141184 -1662136002939142144 -1662136002990143232 -1662136003041144320 -1662136003083145216 -1662136003128146176 -1662136003179147264 -1662136003239148544 -1662136003284149504 -1662136003323150336 -1662136003371151360 -1662136003416152320 -1662136003458153216 -1662136003503154176 -1662136003545155072 -1662136003590156032 -1662136003638157056 -1662136003680157952 -1662136003722158848 -1662136003761159680 -1662136003803160576 -1662136003848161536 -1662136003899162624 -1662136003941163520 -1662136003992164608 -1662136004034165504 -1662136004088166656 -1662136004139167744 -1662136004184168704 -1662136004229169664 -1662136004268170496 -1662136004313171456 -1662136004352172288 -1662136004400173312 -1662136004439174144 -1662136004484175104 -1662136004529176064 -1662136004571176960 -1662136004619177984 -1662136004658178816 -1662136004703179776 -1662136004748180736 -1662136004793181696 -1662136004835182592 -1662136004880183552 -1662136004928184576 -1662136004985185792 -1662136005030186752 -1662136005072187648 -1662136005120188672 -1662136005168189696 -1662136005213190656 -1662136005255191552 -1662136005297192448 -1662136005339193344 -1662136005381194240 -1662136005426195200 -1662136005465196032 -1662136005507196928 -1662136005552197888 -1662136005594198784 -1662136005639199744 -1662136005681200640 -1662136005729201664 -1662136005774202624 -1662136005816203520 -1662136005861204480 -1662136005903205376 -1662136005945206272 -1662136005984207104 -1662136006029208064 -1662136006080209152 -1662136006131210240 -1662136006185211392 -1662136006230212352 -1662136006272213248 -1662136006317214208 -1662136006359215104 -1662136006401216000 -1662136006452217088 -1662136006494217984 -1662136006539218944 -1662136006581219840 -1662136006632220928 -1662136006668221696 -1662136006713222656 -1662136006755223552 -1662136006800224512 -1662136006845225472 -1662136006887226368 -1662136006929227264 -1662136006971228160 -1662136007016229120 -1662136007067230208 -1662136007118231296 -1662136007160232192 -1662136007202233088 -1662136007244233984 -1662136007286234880 -1662136007328235776 -1662136007373236736 -1662136007421237760 -1662136007466238720 -1662136007517239808 -1662136007562240768 -1662136007604241664 -1662136007652242688 -1662136007697243648 -1662136007739244544 -1662136007781245440 -1662136007826246400 -1662136007868247296 -1662136007910248192 -1662136007952249088 -1662136008000250112 -1662136008042251008 -1662136008084251904 -1662136008126252800 -1662136008174253824 -1662136008216254720 -1662136008261255680 -1662136008303256576 -1662136008342257408 -1662136008384258304 -1662136008426259200 -1662136008468260096 -1662136008513261056 -1662136008561262080 -1662136008603262976 -1662136008648263936 -1662136008696264960 -1662136008741265920 -1662136008783266816 -1662136008831267840 -1662136008873268736 -1662136008918269696 -1662136008960270592 -1662136008999271424 -1662136009041272320 -1662136009089273344 -1662136009140274432 -1662136009182275328 -1662136009224276224 -1662136009266277120 -1662136009311278080 -1662136009356279040 -1662136009395279872 -1662136009440280832 -1662136009482281728 -1662136009527282688 -1662136009578283776 -1662136009617284608 -1662136009662285568 -1662136009704286464 -1662136009752287488 -1662136009797288448 -1662136009842289408 -1662136009884290304 -1662136009926291200 -1662136009974292224 -1662136010016293120 -1662136010061294080 -1662136010109295104 -1662136010154296064 -1662136010196296960 -1662136010235297792 -1662136010280298752 -1662136010322299648 -1662136010364300544 -1662136010409301504 -1662136010451302400 -1662136010499303424 -1662136010547304448 -1662136010592305408 -1662136010637306368 -1662136010676307200 -1662136010718308096 -1662136010760308992 -1662136010808310016 -1662136010850310912 -1662136010892311808 -1662136010934312704 -1662136010982313728 -1662136011027314688 -1662136011072315648 -1662136011114316544 -1662136011159317504 -1662136011201318400 -1662136011243319296 -1662136011285320192 -1662136011327321088 -1662136011372322048 -1662136011420323072 -1662136011462323968 -1662136011507324928 -1662136011549325824 -1662136011591326720 -1662136011633327616 -1662136011687328768 -1662136011732329728 -1662136011780330752 -1662136011822331648 -1662136011870332672 -1662136011918333696 -1662136011960334592 -1662136012002335488 -1662136012047336448 -1662136012092337408 -1662136012134338304 -1662136012176339200 -1662136012218340096 -1662136012260340992 -1662136012302341888 -1662136012350342912 -1662136012395343872 -1662136012437344768 -1662136012482345728 -1662136012527346688 -1662136012575347712 -1662136012614348544 -1662136012656349440 -1662136012701350400 -1662136012740351232 -1662136012782352128 -1662136012824353024 -1662136012866353920 -1662136012914354944 -1662136012959355904 -1662136013004356864 -1662136013046357760 -1662136013091358720 -1662136013136359680 -1662136013178360576 -1662136013223361536 -1662136013262362368 -1662136013307363328 -1662136013352364288 -1662136013394365184 -1662136013436366080 -1662136013481367040 -1662136013523367936 -1662136013565368832 -1662136013607369728 -1662136013652370688 -1662136013694371584 -1662136013736372480 -1662136013790373632 -1662136013832374528 -1662136013874375424 -1662136013916376320 -1662136013961377280 -1662136014006378240 -1662136014051379200 -1662136014096380160 -1662136014144381184 -1662136014189382144 -1662136014231383040 -1662136014276384000 -1662136014321384960 -1662136014369385984 -1662136014411386880 -1662136014453387776 -1662136014501388800 -1662136014543389696 -1662136014591390720 -1662136014630391552 -1662136014672392448 -1662136014717393408 -1662136014765394432 -1662136014807395328 -1662136014858396416 -1662136014903397376 -1662136014948398336 -1662136014996399360 -1662136015041400320 -1662136015086401280 -1662136015128402176 -1662136015170403072 -1662136015218404096 -1662136015263405056 -1662136015305405952 -1662136015347406848 -1662136015404408064 -1662136015449409024 -1662136015500410112 -1662136015545411072 -1662136015584411904 -1662136015629412864 -1662136015671413760 -1662136015716414720 -1662136015761415680 -1662136015806416640 -1662136015848417536 -1662136015893418496 -1662136015938419456 -1662136015986420480 -1662136016028421376 -1662136016076422400 -1662136016121423360 -1662136016163424256 -1662136016208425216 -1662136016253426176 -1662136016295427072 -1662136016340428032 -1662136016382428928 -1662136016427429888 -1662136016484431104 -1662136016529432064 -1662136016574433024 -1662136016625434112 -1662136016667435008 -1662136016715436032 -1662136016760436992 -1662136016808438016 -1662136016850438912 -1662136016892439808 -1662136016937440768 -1662136016985441792 -1662136017027442688 -1662136017075443712 -1662136017129444864 -1662136017174445824 -1662136017222446848 -1662136017264447744 -1662136017309448704 -1662136017351449600 -1662136017402450688 -1662136017441451520 -1662136017486452480 -1662136017534453504 -1662136017579454464 -1662136017624455424 -1662136017663456256 -1662136017708457216 -1662136017750458112 -1662136017792459008 -1662136017843460096 -1662136017882460928 -1662136017924461824 -1662136017966462720 -1662136018011463680 -1662136018056464640 -1662136018107465728 -1662136018152466688 -1662136018200467712 -1662136018248468736 -1662136018290469632 -1662136018332470528 -1662136018377471488 -1662136018425472512 -1662136018467473408 -1662136018509474304 -1662136018557475328 -1662136018605476352 -1662136018647477248 -1662136018689478144 -1662136018737479168 -1662136018791480320 -1662136018833481216 -1662136018878482176 -1662136018920483072 -1662136018962483968 -1662136019010484992 -1662136019052485888 -1662136019097486848 -1662136019136487680 -1662136019190488832 -1662136019232489728 diff --git a/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track1_light.txt b/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track1_light.txt deleted file mode 100644 index fc436ed12e..0000000000 --- a/Examples/Monocular/MIMIR_TimeStamps/OceanFloor_track1_light.txt +++ /dev/null @@ -1,6263 +0,0 @@ -1662129779504666880 -1662129779546667776 -1662129779588668672 -1662129779630669568 -1662129779675670528 -1662129779717671424 -1662129779762672384 -1662129779804673280 -1662129779849674240 -1662129779894675200 -1662129779936676096 -1662129779984677120 -1662129780026678016 -1662129780068678912 -1662129780110679808 -1662129780152680704 -1662129780194681600 -1662129780236682496 -1662129780278683392 -1662129780326684416 -1662129780368685312 -1662129780413686272 -1662129780455687168 -1662129780506688256 -1662129780548689152 -1662129780596690176 -1662129780641691136 -1662129780683692032 -1662129780728692992 -1662129780773693952 -1662129780815694848 -1662129780857695744 -1662129780911696896 -1662129780956697856 -1662129781001698816 -1662129781052699904 -1662129781097700864 -1662129781139701760 -1662129781181702656 -1662129781223703552 -1662129781268704512 -1662129781310705408 -1662129781358706432 -1662129781400707328 -1662129781442708224 -1662129781490709248 -1662129781532710144 -1662129781574711040 -1662129781616711936 -1662129781661712896 -1662129781703713792 -1662129781751714816 -1662129781796715776 -1662129781838716672 -1662129781883717632 -1662129781922718464 -1662129781970719488 -1662129782012720384 -1662129782054721280 -1662129782099722240 -1662129782141723136 -1662129782192724224 -1662129782234725120 -1662129782279726080 -1662129782324727040 -1662129782378728192 -1662129782423729152 -1662129782471730176 -1662129782513731072 -1662129782558732032 -1662129782600732928 -1662129782642733824 -1662129782687734784 -1662129782729735680 -1662129782777736704 -1662129782834737920 -1662129782876738816 -1662129782918739712 -1662129782966740736 -1662129783008741632 -1662129783053742592 -1662129783101743616 -1662129783143744512 -1662129783188745472 -1662129783233746432 -1662129783275747328 -1662129783323748352 -1662129783371749376 -1662129783410750208 -1662129783452751104 -1662129783497752064 -1662129783539752960 -1662129783584753920 -1662129783626754816 -1662129783668755712 -1662129783713756672 -1662129783761757696 -1662129783803758592 -1662129783845759488 -1662129783887760384 -1662129783932761344 -1662129783977762304 -1662129784019763200 -1662129784064764160 -1662129784106765056 -1662129784154766080 -1662129784199767040 -1662129784241767936 -1662129784292769024 -1662129784334769920 -1662129784382770944 -1662129784430771968 -1662129784472772864 -1662129784514773760 -1662129784562774784 -1662129784613775872 -1662129784655776768 -1662129784706777856 -1662129784751778816 -1662129784793779712 -1662129784838780672 -1662129784883781632 -1662129784931782656 -1662129784976783616 -1662129785018784512 -1662129785063785472 -1662129785111786496 -1662129785162787584 -1662129785210788608 -1662129785255789568 -1662129785300790528 -1662129785342791424 -1662129785387792384 -1662129785432793344 -1662129785483794432 -1662129785528795392 -1662129785576796416 -1662129785621797376 -1662129785666798336 -1662129785717799424 -1662129785762800384 -1662129785810801408 -1662129785852802304 -1662129785894803200 -1662129785936804096 -1662129785978804992 -1662129786026806016 -1662129786068806912 -1662129786113807872 -1662129786161808896 -1662129786209809920 -1662129786251810816 -1662129786296811776 -1662129786341812736 -1662129786386813696 -1662129786437814784 -1662129786485815808 -1662129786530816768 -1662129786584817920 -1662129786629818880 -1662129786671819776 -1662129786719820800 -1662129786761821696 -1662129786803822592 -1662129786845823488 -1662129786890824448 -1662129786929825280 -1662129786977826304 -1662129787025827328 -1662129787070828288 -1662129787115829248 -1662129787157830144 -1662129787205831168 -1662129787250832128 -1662129787295833088 -1662129787340834048 -1662129787388835072 -1662129787436836096 -1662129787481837056 -1662129787529838080 -1662129787574839040 -1662129787619840000 -1662129787658840832 -1662129787703841792 -1662129787748842752 -1662129787793843712 -1662129787841844736 -1662129787886845696 -1662129787931846656 -1662129787976847616 -1662129788021848576 -1662129788069849600 -1662129788111850496 -1662129788159851520 -1662129788201852416 -1662129788243853312 -1662129788288854272 -1662129788342855424 -1662129788390856448 -1662129788432857344 -1662129788480858368 -1662129788522859264 -1662129788567860224 -1662129788615861248 -1662129788660862208 -1662129788705863168 -1662129788747864064 -1662129788786864896 -1662129788831865856 -1662129788885867008 -1662129788933868032 -1662129788972868864 -1662129789020869888 -1662129789068870912 -1662129789110871808 -1662129789152872704 -1662129789197873664 -1662129789239874560 -1662129789287875584 -1662129789335876608 -1662129789377877504 -1662129789425878528 -1662129789467879424 -1662129789512880384 -1662129789563881472 -1662129789605882368 -1662129789647883264 -1662129789692884224 -1662129789737885184 -1662129789779886080 -1662129789821886976 -1662129789863887872 -1662129789908888832 -1662129789956889856 -1662129790001890816 -1662129790046891776 -1662129790085892608 -1662129790130893568 -1662129790175894528 -1662129790217895424 -1662129790259896320 -1662129790304897280 -1662129790352898304 -1662129790397899264 -1662129790442900224 -1662129790484901120 -1662129790526902016 -1662129790568902912 -1662129790610903808 -1662129790649904640 -1662129790691905536 -1662129790733906432 -1662129790775907328 -1662129790820908288 -1662129790862909184 -1662129790910910208 -1662129790949911040 -1662129790994912000 -1662129791033912832 -1662129791075913728 -1662129791120914688 -1662129791162915584 -1662129791207916544 -1662129791252917504 -1662129791294918400 -1662129791336919296 -1662129791378920192 -1662129791420921088 -1662129791465922048 -1662129791504922880 -1662129791549923840 -1662129791594924800 -1662129791636925696 -1662129791678926592 -1662129791720927488 -1662129791762928384 -1662129791804929280 -1662129791843930112 -1662129791888931072 -1662129791936932096 -1662129791981933056 -1662129792029934080 -1662129792077935104 -1662129792119936000 -1662129792155936768 -1662129792197937664 -1662129792245938688 -1662129792287939584 -1662129792338940672 -1662129792380941568 -1662129792425942528 -1662129792470943488 -1662129792512944384 -1662129792557945344 -1662129792599946240 -1662129792644947200 -1662129792683948032 -1662129792728948992 -1662129792773949952 -1662129792821950976 -1662129792866951936 -1662129792908952832 -1662129792959953920 -1662129793004954880 -1662129793049955840 -1662129793088956672 -1662129793133957632 -1662129793181958656 -1662129793223959552 -1662129793265960448 -1662129793313961472 -1662129793358962432 -1662129793409963520 -1662129793451964416 -1662129793496965376 -1662129793544966400 -1662129793586967296 -1662129793628968192 -1662129793670969088 -1662129793712969984 -1662129793754970880 -1662129793796971776 -1662129793841972736 -1662129793895973888 -1662129793937974784 -1662129793979975680 -1662129794027976704 -1662129794075977728 -1662129794117978624 -1662129794162979584 -1662129794207980544 -1662129794249981440 -1662129794291982336 -1662129794333983232 -1662129794375984128 -1662129794417985024 -1662129794459985920 -1662129794513987072 -1662129794555987968 -1662129794597988864 -1662129794639989760 -1662129794684990720 -1662129794732991744 -1662129794777992704 -1662129794822993664 -1662129794873994752 -1662129794915995648 -1662129794957996544 -1662129795002997504 -1662129795044998400 -1662129795083999232 -1662129795135000320 -1662129795177001216 -1662129795225002240 -1662129795267003136 -1662129795315004160 -1662129795366005248 -1662129795408006144 -1662129795456007168 -1662129795501008128 -1662129795543009024 -1662129795585009920 -1662129795624010752 -1662129795672011776 -1662129795717012736 -1662129795762013696 -1662129795804014592 -1662129795855015680 -1662129795903016704 -1662129795957017856 -1662129796008018944 -1662129796050019840 -1662129796098020864 -1662129796146021888 -1662129796191022848 -1662129796239023872 -1662129796284024832 -1662129796335025920 -1662129796380026880 -1662129796428027904 -1662129796470028800 -1662129796512029696 -1662129796557030656 -1662129796599031552 -1662129796641032448 -1662129796683033344 -1662129796725034240 -1662129796767035136 -1662129796812036096 -1662129796851036928 -1662129796896037888 -1662129796941038848 -1662129796992039936 -1662129797034040832 -1662129797076041728 -1662129797118042624 -1662129797163043584 -1662129797208044544 -1662129797253045504 -1662129797295046400 -1662129797337047296 -1662129797388048384 -1662129797430049280 -1662129797475050240 -1662129797526051328 -1662129797580052480 -1662129797628053504 -1662129797679054592 -1662129797718055424 -1662129797766056448 -1662129797814057472 -1662129797862058496 -1662129797907059456 -1662129797949060352 -1662129797991061248 -1662129798033062144 -1662129798075063040 -1662129798117063936 -1662129798162064896 -1662129798204065792 -1662129798246066688 -1662129798288067584 -1662129798333068544 -1662129798372069376 -1662129798420070400 -1662129798462071296 -1662129798504072192 -1662129798561073408 -1662129798609074432 -1662129798651075328 -1662129798690076160 -1662129798735077120 -1662129798777078016 -1662129798819078912 -1662129798870080000 -1662129798921081088 -1662129798966082048 -1662129799008082944 -1662129799053083904 -1662129799098084864 -1662129799140085760 -1662129799182086656 -1662129799230087680 -1662129799284088832 -1662129799329089792 -1662129799371090688 -1662129799428091904 -1662129799473092864 -1662129799515093760 -1662129799560094720 -1662129799605095680 -1662129799650096640 -1662129799692097536 -1662129799734098432 -1662129799776099328 -1662129799818100224 -1662129799863101184 -1662129799911102208 -1662129799956103168 -1662129800004104192 -1662129800046105088 -1662129800088105984 -1662129800133106944 -1662129800175107840 -1662129800223108864 -1662129800268109824 -1662129800319110912 -1662129800358111744 -1662129800400112640 -1662129800442113536 -1662129800493114624 -1662129800541115648 -1662129800589116672 -1662129800631117568 -1662129800676118528 -1662129800718119424 -1662129800772120576 -1662129800820121600 -1662129800862122496 -1662129800910123520 -1662129800955124480 -1662129801000125440 -1662129801048126464 -1662129801090127360 -1662129801150128640 -1662129801192129536 -1662129801234130432 -1662129801276131328 -1662129801321132288 -1662129801363133184 -1662129801405134080 -1662129801447134976 -1662129801495136000 -1662129801543137024 -1662129801588137984 -1662129801636139008 -1662129801681139968 -1662129801723140864 -1662129801765141760 -1662129801807142656 -1662129801855143680 -1662129801900144640 -1662129801948145664 -1662129801993146624 -1662129802044147712 -1662129802083148544 -1662129802131149568 -1662129802176150528 -1662129802224151552 -1662129802272152576 -1662129802311153408 -1662129802353154304 -1662129802398155264 -1662129802443156224 -1662129802488157184 -1662129802533158144 -1662129802584159232 -1662129802635160320 -1662129802677161216 -1662129802728162304 -1662129802773163264 -1662129802818164224 -1662129802860165120 -1662129802911166208 -1662129802950167040 -1662129802992167936 -1662129803040168960 -1662129803085169920 -1662129803136171008 -1662129803178171904 -1662129803220172800 -1662129803274173952 -1662129803316174848 -1662129803364175872 -1662129803415176960 -1662129803460177920 -1662129803499178752 -1662129803547179776 -1662129803592180736 -1662129803634181632 -1662129803676182528 -1662129803721183488 -1662129803760184320 -1662129803814185472 -1662129803856186368 -1662129803898187264 -1662129803943188224 -1662129803997189376 -1662129804039190272 -1662129804084191232 -1662129804126192128 -1662129804171193088 -1662129804216194048 -1662129804258194944 -1662129804312196096 -1662129804354196992 -1662129804402198016 -1662129804444198912 -1662129804495200000 -1662129804540200960 -1662129804582201856 -1662129804636203008 -1662129804678203904 -1662129804726204928 -1662129804768205824 -1662129804813206784 -1662129804855207680 -1662129804900208640 -1662129804951209728 -1662129804996210688 -1662129805041211648 -1662129805089212672 -1662129805140213760 -1662129805182214656 -1662129805227215616 -1662129805272216576 -1662129805314217472 -1662129805356218368 -1662129805398219264 -1662129805449220352 -1662129805494221312 -1662129805533222144 -1662129805575223040 -1662129805620224000 -1662129805662224896 -1662129805707225856 -1662129805764227072 -1662129805803227904 -1662129805842228736 -1662129805893229824 -1662129805938230784 -1662129805989231872 -1662129806031232768 -1662129806076233728 -1662129806124234752 -1662129806166235648 -1662129806205236480 -1662129806256237568 -1662129806295238400 -1662129806337239296 -1662129806379240192 -1662129806433241344 -1662129806475242240 -1662129806520243200 -1662129806565244160 -1662129806610245120 -1662129806652246016 -1662129806691246848 -1662129806736247808 -1662129806787248896 -1662129806826249728 -1662129806871250688 -1662129806916251648 -1662129806970252800 -1662129807012253696 -1662129807054254592 -1662129807096255488 -1662129807144256512 -1662129807189257472 -1662129807234258432 -1662129807282259456 -1662129807336260608 -1662129807378261504 -1662129807432262656 -1662129807480263680 -1662129807528264704 -1662129807576265728 -1662129807618266624 -1662129807657267456 -1662129807702268416 -1662129807753269504 -1662129807798270464 -1662129807840271360 -1662129807885272320 -1662129807927273216 -1662129807978274304 -1662129808017275136 -1662129808059276032 -1662129808104276992 -1662129808146277888 -1662129808197278976 -1662129808239279872 -1662129808278280704 -1662129808323281664 -1662129808374282752 -1662129808419283712 -1662129808470284800 -1662129808515285760 -1662129808557286656 -1662129808602287616 -1662129808644288512 -1662129808689289472 -1662129808734290432 -1662129808779291392 -1662129808824292352 -1662129808878293504 -1662129808920294400 -1662129808965295360 -1662129809007296256 -1662129809052297216 -1662129809094298112 -1662129809142299136 -1662129809190300160 -1662129809232301056 -1662129809277302016 -1662129809322302976 -1662129809367303936 -1662129809418305024 -1662129809460305920 -1662129809508306944 -1662129809553307904 -1662129809598308864 -1662129809646309888 -1662129809688310784 -1662129809733311744 -1662129809784312832 -1662129809832313856 -1662129809877314816 -1662129809925315840 -1662129809967316736 -1662129810012317696 -1662129810057318656 -1662129810099319552 -1662129810144320512 -1662129810186321408 -1662129810231322368 -1662129810276323328 -1662129810318324224 -1662129810360325120 -1662129810405326080 -1662129810447326976 -1662129810489327872 -1662129810543329024 -1662129810588329984 -1662129810639331072 -1662129810687332096 -1662129810732333056 -1662129810780334080 -1662129810819334912 -1662129810864335872 -1662129810909336832 -1662129810954337792 -1662129810999338752 -1662129811041339648 -1662129811086340608 -1662129811128341504 -1662129811170342400 -1662129811209343232 -1662129811263344384 -1662129811308345344 -1662129811359346432 -1662129811401347328 -1662129811446348288 -1662129811491349248 -1662129811533350144 -1662129811578351104 -1662129811626352128 -1662129811668353024 -1662129811710353920 -1662129811752354816 -1662129811794355712 -1662129811839356672 -1662129811881357568 -1662129811923358464 -1662129811974359552 -1662129812019360512 -1662129812067361536 -1662129812109362432 -1662129812151363328 -1662129812193364224 -1662129812235365120 -1662129812277366016 -1662129812322366976 -1662129812364367872 -1662129812409368832 -1662129812451369728 -1662129812499370752 -1662129812547371776 -1662129812589372672 -1662129812634373632 -1662129812679374592 -1662129812724375552 -1662129812778376704 -1662129812829377792 -1662129812874378752 -1662129812922379776 -1662129812967380736 -1662129813009381632 -1662129813057382656 -1662129813099383552 -1662129813147384576 -1662129813189385472 -1662129813231386368 -1662129813273387264 -1662129813318388224 -1662129813357389056 -1662129813402390016 -1662129813444390912 -1662129813489391872 -1662129813531392768 -1662129813579393792 -1662129813624394752 -1662129813666395648 -1662129813705396480 -1662129813747397376 -1662129813792398336 -1662129813834399232 -1662129813876400128 -1662129813918401024 -1662129813966402048 -1662129814011403008 -1662129814059404032 -1662129814104404992 -1662129814146405888 -1662129814191406848 -1662129814242407936 -1662129814284408832 -1662129814332409856 -1662129814371410688 -1662129814416411648 -1662129814467412736 -1662129814509413632 -1662129814551414528 -1662129814593415424 -1662129814635416320 -1662129814674417152 -1662129814722418176 -1662129814764419072 -1662129814818420224 -1662129814863421184 -1662129814908422144 -1662129814953423104 -1662129815001424128 -1662129815046425088 -1662129815091426048 -1662129815136427008 -1662129815181427968 -1662129815223428864 -1662129815265429760 -1662129815310430720 -1662129815352431616 -1662129815394432512 -1662129815436433408 -1662129815481434368 -1662129815526435328 -1662129815574436352 -1662129815625437440 -1662129815676438528 -1662129815721439488 -1662129815769440512 -1662129815814441472 -1662129815856442368 -1662129815910443520 -1662129815952444416 -1662129815997445376 -1662129816039446272 -1662129816087447296 -1662129816129448192 -1662129816171449088 -1662129816216450048 -1662129816264451072 -1662129816315452160 -1662129816360453120 -1662129816411454208 -1662129816456455168 -1662129816498456064 -1662129816540456960 -1662129816582457856 -1662129816627458816 -1662129816669459712 -1662129816717460736 -1662129816759461632 -1662129816813462784 -1662129816858463744 -1662129816900464640 -1662129816945465600 -1662129816996466688 -1662129817041467648 -1662129817083468544 -1662129817125469440 -1662129817179470592 -1662129817218471424 -1662129817266472448 -1662129817311473408 -1662129817359474432 -1662129817401475328 -1662129817443476224 -1662129817485477120 -1662129817527478016 -1662129817569478912 -1662129817611479808 -1662129817668481024 -1662129817713481984 -1662129817764483072 -1662129817812484096 -1662129817866485248 -1662129817908486144 -1662129817950487040 -1662129817992487936 -1662129818043489024 -1662129818094490112 -1662129818139491072 -1662129818181491968 -1662129818223492864 -1662129818268493824 -1662129818313494784 -1662129818367495936 -1662129818412496896 -1662129818454497792 -1662129818499498752 -1662129818544499712 -1662129818586500608 -1662129818631501568 -1662129818673502464 -1662129818718503424 -1662129818760504320 -1662129818802505216 -1662129818850506240 -1662129818892507136 -1662129818934508032 -1662129818982509056 -1662129819030510080 -1662129819075511040 -1662129819120512000 -1662129819162512896 -1662129819207513856 -1662129819261515008 -1662129819306515968 -1662129819354516992 -1662129819399517952 -1662129819447518976 -1662129819495520000 -1662129819534520832 -1662129819579521792 -1662129819621522688 -1662129819669523712 -1662129819714524672 -1662129819756525568 -1662129819801526528 -1662129819846527488 -1662129819888528384 -1662129819933529344 -1662129819978530304 -1662129820020531200 -1662129820062532096 -1662129820104532992 -1662129820152534016 -1662129820197534976 -1662129820239535872 -1662129820281536768 -1662129820323537664 -1662129820365538560 -1662129820410539520 -1662129820458540544 -1662129820500541440 -1662129820542542336 -1662129820587543296 -1662129820638544384 -1662129820689545472 -1662129820737546496 -1662129820782547456 -1662129820830548480 -1662129820881549568 -1662129820932550656 -1662129820983551744 -1662129821028552704 -1662129821070553600 -1662129821112554496 -1662129821157555456 -1662129821205556480 -1662129821256557568 -1662129821301558528 -1662129821343559424 -1662129821394560512 -1662129821451561728 -1662129821493562624 -1662129821535563520 -1662129821589564672 -1662129821634565632 -1662129821682566656 -1662129821724567552 -1662129821778568704 -1662129821826569728 -1662129821871570688 -1662129821913571584 -1662129821955572480 -1662129821997573376 -1662129822039574272 -1662129822084575232 -1662129822144576512 -1662129822192577536 -1662129822234578432 -1662129822276579328 -1662129822318580224 -1662129822363581184 -1662129822411582208 -1662129822453583104 -1662129822498584064 -1662129822540584960 -1662129822582585856 -1662129822624586752 -1662129822669587712 -1662129822708588544 -1662129822750589440 -1662129822792590336 -1662129822843591424 -1662129822885592320 -1662129822939593472 -1662129822981594368 -1662129823023595264 -1662129823062596096 -1662129823101596928 -1662129823143597824 -1662129823185598720 -1662129823233599744 -1662129823278600704 -1662129823332601856 -1662129823380602880 -1662129823425603840 -1662129823473604864 -1662129823521605888 -1662129823560606720 -1662129823605607680 -1662129823650608640 -1662129823698609664 -1662129823740610560 -1662129823791611648 -1662129823836612608 -1662129823878613504 -1662129823923614464 -1662129823971615488 -1662129824016616448 -1662129824067617536 -1662129824112618496 -1662129824154619392 -1662129824208620544 -1662129824253621504 -1662129824298622464 -1662129824340623360 -1662129824388624384 -1662129824430625280 -1662129824475626240 -1662129824514627072 -1662129824556627968 -1662129824607629056 -1662129824655630080 -1662129824703631104 -1662129824745632000 -1662129824790632960 -1662129824832633856 -1662129824880634880 -1662129824925635840 -1662129824970636800 -1662129825018637824 -1662129825063638784 -1662129825108639744 -1662129825153640704 -1662129825195641600 -1662129825249642752 -1662129825300643840 -1662129825345644800 -1662129825387645696 -1662129825435646720 -1662129825477647616 -1662129825522648576 -1662129825570649600 -1662129825615650560 -1662129825660651520 -1662129825702652416 -1662129825747653376 -1662129825792654336 -1662129825837655296 -1662129825876656128 -1662129825918657024 -1662129825960657920 -1662129826005658880 -1662129826047659776 -1662129826104660992 -1662129826152662016 -1662129826197662976 -1662129826236663808 -1662129826278664704 -1662129826323665664 -1662129826365666560 -1662129826416667648 -1662129826458668544 -1662129826506669568 -1662129826551670528 -1662129826599671552 -1662129826644672512 -1662129826695673600 -1662129826743674624 -1662129826785675520 -1662129826836676608 -1662129826887677696 -1662129826941678848 -1662129826992679936 -1662129827031680768 -1662129827079681792 -1662129827121682688 -1662129827166683648 -1662129827217684736 -1662129827262685696 -1662129827304686592 -1662129827349687552 -1662129827400688640 -1662129827451689728 -1662129827490690560 -1662129827544691712 -1662129827589692672 -1662129827631693568 -1662129827676694528 -1662129827730695680 -1662129827769696512 -1662129827811697408 -1662129827856698368 -1662129827901699328 -1662129827943700224 -1662129827985701120 -1662129828027702016 -1662129828072702976 -1662129828114703872 -1662129828162704896 -1662129828204705792 -1662129828246706688 -1662129828303707904 -1662129828345708800 -1662129828387709696 -1662129828432710656 -1662129828471711488 -1662129828513712384 -1662129828558713344 -1662129828612714496 -1662129828657715456 -1662129828699716352 -1662129828738717184 -1662129828780718080 -1662129828831719168 -1662129828876720128 -1662129828918721024 -1662129828963721984 -1662129829008722944 -1662129829050723840 -1662129829095724800 -1662129829134725632 -1662129829176726528 -1662129829224727552 -1662129829266728448 -1662129829311729408 -1662129829350730240 -1662129829392731136 -1662129829437732096 -1662129829479732992 -1662129829533734144 -1662129829578735104 -1662129829620736000 -1662129829671737088 -1662129829719738112 -1662129829761739008 -1662129829806739968 -1662129829854740992 -1662129829899741952 -1662129829947742976 -1662129829989743872 -1662129830034744832 -1662129830079745792 -1662129830121746688 -1662129830163747584 -1662129830205748480 -1662129830247749376 -1662129830289750272 -1662129830328751104 -1662129830376752128 -1662129830427753216 -1662129830469754112 -1662129830514755072 -1662129830565756160 -1662129830610757120 -1662129830652758016 -1662129830703759104 -1662129830745760000 -1662129830793761024 -1662129830844762112 -1662129830886763008 -1662129830928763904 -1662129830973764864 -1662129831015765760 -1662129831057766656 -1662129831099767552 -1662129831144768512 -1662129831186769408 -1662129831231770368 -1662129831276771328 -1662129831318772224 -1662129831357773056 -1662129831405774080 -1662129831447774976 -1662129831495776000 -1662129831537776896 -1662129831591778048 -1662129831636779008 -1662129831681779968 -1662129831729780992 -1662129831786782208 -1662129831834783232 -1662129831882784256 -1662129831921785088 -1662129831963785984 -1662129832005786880 -1662129832050787840 -1662129832101788928 -1662129832149789952 -1662129832188790784 -1662129832233791744 -1662129832275792640 -1662129832323793664 -1662129832368794624 -1662129832410795520 -1662129832452796416 -1662129832494797312 -1662129832536798208 -1662129832581799168 -1662129832626800128 -1662129832668801024 -1662129832710801920 -1662129832758802944 -1662129832800803840 -1662129832854804992 -1662129832896805888 -1662129832941806848 -1662129832989807872 -1662129833034808832 -1662129833076809728 -1662129833124810752 -1662129833166811648 -1662129833223812864 -1662129833265813760 -1662129833310814720 -1662129833355815680 -1662129833406816768 -1662129833448817664 -1662129833493818624 -1662129833541819648 -1662129833583820544 -1662129833628821504 -1662129833673822464 -1662129833715823360 -1662129833760824320 -1662129833799825152 -1662129833841826048 -1662129833889827072 -1662129833937828096 -1662129833985829120 -1662129834030830080 -1662129834069830912 -1662129834117831936 -1662129834162832896 -1662129834210833920 -1662129834255834880 -1662129834303835904 -1662129834348836864 -1662129834387837696 -1662129834432838656 -1662129834480839680 -1662129834528840704 -1662129834570841600 -1662129834609842432 -1662129834651843328 -1662129834693844224 -1662129834735845120 -1662129834786846208 -1662129834834847232 -1662129834876848128 -1662129834924849152 -1662129834966850048 -1662129835011851008 -1662129835056851968 -1662129835101852928 -1662129835158854144 -1662129835200855040 -1662129835245856000 -1662129835287856896 -1662129835341858048 -1662129835383858944 -1662129835428859904 -1662129835476860928 -1662129835521861888 -1662129835566862848 -1662129835605863680 -1662129835647864576 -1662129835698865664 -1662129835746866688 -1662129835788867584 -1662129835836868608 -1662129835878869504 -1662129835920870400 -1662129835965871360 -1662129836013872384 -1662129836052873216 -1662129836094874112 -1662129836142875136 -1662129836190876160 -1662129836238877184 -1662129836280878080 -1662129836328879104 -1662129836367879936 -1662129836415880960 -1662129836457881856 -1662129836499882752 -1662129836544883712 -1662129836586884608 -1662129836628885504 -1662129836679886592 -1662129836730887680 -1662129836772888576 -1662129836817889536 -1662129836862890496 -1662129836913891584 -1662129836958892544 -1662129837006893568 -1662129837057894656 -1662129837096895488 -1662129837135896320 -1662129837177897216 -1662129837219898112 -1662129837264899072 -1662129837309900032 -1662129837351900928 -1662129837393901824 -1662129837444902912 -1662129837483903744 -1662129837528904704 -1662129837573905664 -1662129837615906560 -1662129837657907456 -1662129837702908416 -1662129837747909376 -1662129837792910336 -1662129837843911424 -1662129837885912320 -1662129837930913280 -1662129837975914240 -1662129838020915200 -1662129838062916096 -1662129838104916992 -1662129838149917952 -1662129838191918848 -1662129838236919808 -1662129838278920704 -1662129838320921600 -1662129838374922752 -1662129838419923712 -1662129838464924672 -1662129838512925696 -1662129838554926592 -1662129838596927488 -1662129838638928384 -1662129838686929408 -1662129838728930304 -1662129838770931200 -1662129838812932096 -1662129838854932992 -1662129838896933888 -1662129838941934848 -1662129838983935744 -1662129839028936704 -1662129839070937600 -1662129839112938496 -1662129839154939392 -1662129839199940352 -1662129839244941312 -1662129839286942208 -1662129839328943104 -1662129839370944000 -1662129839421945088 -1662129839463945984 -1662129839508946944 -1662129839550947840 -1662129839589948672 -1662129839631949568 -1662129839673950464 -1662129839715951360 -1662129839757952256 -1662129839802953216 -1662129839844954112 -1662129839895955200 -1662129839940956160 -1662129839982957056 -1662129840024957952 -1662129840075959040 -1662129840126960128 -1662129840171961088 -1662129840213961984 -1662129840255962880 -1662129840297963776 -1662129840339964672 -1662129840381965568 -1662129840426966528 -1662129840468967424 -1662129840513968384 -1662129840564969472 -1662129840609970432 -1662129840660971520 -1662129840708972544 -1662129840759973632 -1662129840801974528 -1662129840843975424 -1662129840888976384 -1662129840933977344 -1662129840975978240 -1662129841020979200 -1662129841071980288 -1662129841116981248 -1662129841164982272 -1662129841203983104 -1662129841248984064 -1662129841302985216 -1662129841344986112 -1662129841392987136 -1662129841434988032 -1662129841479988992 -1662129841527990016 -1662129841569990912 -1662129841617991936 -1662129841662992896 -1662129841707993856 -1662129841749994752 -1662129841791995648 -1662129841833996544 -1662129841875997440 -1662129841914998272 -1662129841956999168 -1662129841999000064 -1662129842041000960 -1662129842086001920 -1662129842131002880 -1662129842188004096 -1662129842233005056 -1662129842278006016 -1662129842326007040 -1662129842368007936 -1662129842419009024 -1662129842458009856 -1662129842500010752 -1662129842542011648 -1662129842584012544 -1662129842626013440 -1662129842680014592 -1662129842719015424 -1662129842773016576 -1662129842818017536 -1662129842860018432 -1662129842905019392 -1662129842947020288 -1662129842992021248 -1662129843040022272 -1662129843079023104 -1662129843121024000 -1662129843166024960 -1662129843208025856 -1662129843250026752 -1662129843292027648 -1662129843337028608 -1662129843382029568 -1662129843433030656 -1662129843481031680 -1662129843526032640 -1662129843574033664 -1662129843625034752 -1662129843667035648 -1662129843709036544 -1662129843751037440 -1662129843793038336 -1662129843835039232 -1662129843880040192 -1662129843922041088 -1662129843973042176 -1662129844018043136 -1662129844066044160 -1662129844108045056 -1662129844150045952 -1662129844204047104 -1662129844255048192 -1662129844297049088 -1662129844339049984 -1662129844381050880 -1662129844423051776 -1662129844462052608 -1662129844504053504 -1662129844552054528 -1662129844597055488 -1662129844642056448 -1662129844687057408 -1662129844732058368 -1662129844771059200 -1662129844813060096 -1662129844855060992 -1662129844906062080 -1662129844948062976 -1662129844996064000 -1662129845035064832 -1662129845083065856 -1662129845137067008 -1662129845179067904 -1662129845227068928 -1662129845272069888 -1662129845314070784 -1662129845356071680 -1662129845401072640 -1662129845443073536 -1662129845485074432 -1662129845527075328 -1662129845572076288 -1662129845617077248 -1662129845662078208 -1662129845704079104 -1662129845746080000 -1662129845788080896 -1662129845836081920 -1662129845878082816 -1662129845926083840 -1662129845974084864 -1662129846019085824 -1662129846067086848 -1662129846112087808 -1662129846157088768 -1662129846202089728 -1662129846244090624 -1662129846286091520 -1662129846328092416 -1662129846385093632 -1662129846424094464 -1662129846469095424 -1662129846508096256 -1662129846553097216 -1662129846598098176 -1662129846649099264 -1662129846697100288 -1662129846739101184 -1662129846787102208 -1662129846832103168 -1662129846874104064 -1662129846919105024 -1662129846964105984 -1662129847006106880 -1662129847051107840 -1662129847105108992 -1662129847156110080 -1662129847201111040 -1662129847246112000 -1662129847288112896 -1662129847336113920 -1662129847384114944 -1662129847423115776 -1662129847468116736 -1662129847519117824 -1662129847567118848 -1662129847612119808 -1662129847654120704 -1662129847702121728 -1662129847744122624 -1662129847783123456 -1662129847831124480 -1662129847873125376 -1662129847921126400 -1662129847963127296 -1662129848005128192 -1662129848053129216 -1662129848107130368 -1662129848152131328 -1662129848197132288 -1662129848242133248 -1662129848284134144 -1662129848332135168 -1662129848380136192 -1662129848422137088 -1662129848467138048 -1662129848509138944 -1662129848551139840 -1662129848593140736 -1662129848632141568 -1662129848674142464 -1662129848719143424 -1662129848764144384 -1662129848812145408 -1662129848857146368 -1662129848896147200 -1662129848941148160 -1662129848992149248 -1662129849034150144 -1662129849076151040 -1662129849127152128 -1662129849169153024 -1662129849223154176 -1662129849277155328 -1662129849325156352 -1662129849367157248 -1662129849418158336 -1662129849466159360 -1662129849514160384 -1662129849556161280 -1662129849604162304 -1662129849652163328 -1662129849694164224 -1662129849736165120 -1662129849781166080 -1662129849832167168 -1662129849877168128 -1662129849922169088 -1662129849964169984 -1662129850009170944 -1662129850051171840 -1662129850093172736 -1662129850138173696 -1662129850180174592 -1662129850222175488 -1662129850264176384 -1662129850315177472 -1662129850360178432 -1662129850399179264 -1662129850444180224 -1662129850489181184 -1662129850531182080 -1662129850576183040 -1662129850621184000 -1662129850669185024 -1662129850714185984 -1662129850759186944 -1662129850804187904 -1662129850846188800 -1662129850894189824 -1662129850936190720 -1662129850987191808 -1662129851029192704 -1662129851074193664 -1662129851119194624 -1662129851164195584 -1662129851209196544 -1662129851254197504 -1662129851299198464 -1662129851338199296 -1662129851380200192 -1662129851422201088 -1662129851470202112 -1662129851515203072 -1662129851554203904 -1662129851596204800 -1662129851647205888 -1662129851695206912 -1662129851737207808 -1662129851785208832 -1662129851830209792 -1662129851872210688 -1662129851917211648 -1662129851959212544 -1662129852001213440 -1662129852049214464 -1662129852100215552 -1662129852148216576 -1662129852190217472 -1662129852229218304 -1662129852271219200 -1662129852313220096 -1662129852355220992 -1662129852409222144 -1662129852451223040 -1662129852496224000 -1662129852538224896 -1662129852583225856 -1662129852625226752 -1662129852676227840 -1662129852724228864 -1662129852766229760 -1662129852811230720 -1662129852859231744 -1662129852907232768 -1662129852955233792 -1662129852997234688 -1662129853042235648 -1662129853090236672 -1662129853138237696 -1662129853189238784 -1662129853237239808 -1662129853279240704 -1662129853324241664 -1662129853366242560 -1662129853408243456 -1662129853453244416 -1662129853501245440 -1662129853543246336 -1662129853591247360 -1662129853636248320 -1662129853678249216 -1662129853723250176 -1662129853771251200 -1662129853816252160 -1662129853873253376 -1662129853924254464 -1662129853969255424 -1662129854011256320 -1662129854056257280 -1662129854098258176 -1662129854140259072 -1662129854185260032 -1662129854233261056 -1662129854284262144 -1662129854329263104 -1662129854374264064 -1662129854422265088 -1662129854473266176 -1662129854521267200 -1662129854560268032 -1662129854605268992 -1662129854644269824 -1662129854686270720 -1662129854728271616 -1662129854782272768 -1662129854827273728 -1662129854869274624 -1662129854911275520 -1662129854962276608 -1662129855010277632 -1662129855055278592 -1662129855100279552 -1662129855142280448 -1662129855187281408 -1662129855235282432 -1662129855283283456 -1662129855328284416 -1662129855370285312 -1662129855409286144 -1662129855454287104 -1662129855499288064 -1662129855541288960 -1662129855580289792 -1662129855625290752 -1662129855670291712 -1662129855712292608 -1662129855754293504 -1662129855799294464 -1662129855841295360 -1662129855886296320 -1662129855937297408 -1662129855976298240 -1662129856018299136 -1662129856066300160 -1662129856111301120 -1662129856156302080 -1662129856204303104 -1662129856255304192 -1662129856297305088 -1662129856339305984 -1662129856381306880 -1662129856426307840 -1662129856465308672 -1662129856507309568 -1662129856549310464 -1662129856594311424 -1662129856636312320 -1662129856678313216 -1662129856720314112 -1662129856768315136 -1662129856813316096 -1662129856855316992 -1662129856897317888 -1662129856939318784 -1662129856984319744 -1662129857029320704 -1662129857074321664 -1662129857122322688 -1662129857167323648 -1662129857215324672 -1662129857260325632 -1662129857302326528 -1662129857350327552 -1662129857395328512 -1662129857437329408 -1662129857479330304 -1662129857521331200 -1662129857566332160 -1662129857614333184 -1662129857656334080 -1662129857698334976 -1662129857743335936 -1662129857785336832 -1662129857827337728 -1662129857875338752 -1662129857917339648 -1662129857959340544 -1662129858001341440 -1662129858049342464 -1662129858088343296 -1662129858127344128 -1662129858169345024 -1662129858211345920 -1662129858259346944 -1662129858301347840 -1662129858352348928 -1662129858403350016 -1662129858448350976 -1662129858496352000 -1662129858541352960 -1662129858589353984 -1662129858637355008 -1662129858688356096 -1662129858727356928 -1662129858769357824 -1662129858814358784 -1662129858856359680 -1662129858898360576 -1662129858943361536 -1662129858985362432 -1662129859042363648 -1662129859087364608 -1662129859126365440 -1662129859171366400 -1662129859213367296 -1662129859255368192 -1662129859300369152 -1662129859342370048 -1662129859390371072 -1662129859432371968 -1662129859477372928 -1662129859528374016 -1662129859570374912 -1662129859615375872 -1662129859657376768 -1662129859699377664 -1662129859750378752 -1662129859792379648 -1662129859834380544 -1662129859879381504 -1662129859921382400 -1662129859963383296 -1662129860008384256 -1662129860053385216 -1662129860095386112 -1662129860140387072 -1662129860182387968 -1662129860233389056 -1662129860275389952 -1662129860320390912 -1662129860368391936 -1662129860419393024 -1662129860464393984 -1662129860506394880 -1662129860548395776 -1662129860590396672 -1662129860641397760 -1662129860683398656 -1662129860731399680 -1662129860776400640 -1662129860818401536 -1662129860869402624 -1662129860917403648 -1662129860959404544 -1662129861007405568 -1662129861055406592 -1662129861097407488 -1662129861142408448 -1662129861184409344 -1662129861229410304 -1662129861274411264 -1662129861319412224 -1662129861364413184 -1662129861415414272 -1662129861457415168 -1662129861496416000 -1662129861538416896 -1662129861586417920 -1662129861625418752 -1662129861667419648 -1662129861712420608 -1662129861754421504 -1662129861796422400 -1662129861838423296 -1662129861886424320 -1662129861937425408 -1662129861982426368 -1662129862024427264 -1662129862066428160 -1662129862114429184 -1662129862159430144 -1662129862201431040 -1662129862243431936 -1662129862291432960 -1662129862336433920 -1662129862378434816 -1662129862423435776 -1662129862465436672 -1662129862516437760 -1662129862561438720 -1662129862603439616 -1662129862648440576 -1662129862687441408 -1662129862729442304 -1662129862777443328 -1662129862825444352 -1662129862867445248 -1662129862912446208 -1662129862960447232 -1662129863005448192 -1662129863056449280 -1662129863101450240 -1662129863140451072 -1662129863182451968 -1662129863224452864 -1662129863266453760 -1662129863317454848 -1662129863359455744 -1662129863407456768 -1662129863455457792 -1662129863497458688 -1662129863542459648 -1662129863584460544 -1662129863626461440 -1662129863674462464 -1662129863722463488 -1662129863764464384 -1662129863806465280 -1662129863845466112 -1662129863890467072 -1662129863932467968 -1662129863977468928 -1662129864019469824 -1662129864061470720 -1662129864106471680 -1662129864154472704 -1662129864202473728 -1662129864244474624 -1662129864286475520 -1662129864331476480 -1662129864382477568 -1662129864427478528 -1662129864472479488 -1662129864517480448 -1662129864559481344 -1662129864601482240 -1662129864646483200 -1662129864694484224 -1662129864733485056 -1662129864778486016 -1662129864829487104 -1662129864880488192 -1662129864922489088 -1662129864964489984 -1662129865006490880 -1662129865054491904 -1662129865099492864 -1662129865141493760 -1662129865183494656 -1662129865222495488 -1662129865270496512 -1662129865312497408 -1662129865351498240 -1662129865393499136 -1662129865438500096 -1662129865489501184 -1662129865534502144 -1662129865579503104 -1662129865624504064 -1662129865666504960 -1662129865708505856 -1662129865753506816 -1662129865804507904 -1662129865846508800 -1662129865894509824 -1662129865939510784 -1662129865981511680 -1662129866023512576 -1662129866077513728 -1662129866125514752 -1662129866167515648 -1662129866212516608 -1662129866257517568 -1662129866308518656 -1662129866353519616 -1662129866398520576 -1662129866440521472 -1662129866485522432 -1662129866530523392 -1662129866578524416 -1662129866620525312 -1662129866662526208 -1662129866707527168 -1662129866752528128 -1662129866794529024 -1662129866836529920 -1662129866875530752 -1662129866920531712 -1662129866974532864 -1662129867022533888 -1662129867064534784 -1662129867106535680 -1662129867151536640 -1662129867190537472 -1662129867244538624 -1662129867289539584 -1662129867331540480 -1662129867385541632 -1662129867427542528 -1662129867472543488 -1662129867517544448 -1662129867562545408 -1662129867607546368 -1662129867649547264 -1662129867697548288 -1662129867742549248 -1662129867787550208 -1662129867829551104 -1662129867868551936 -1662129867916552960 -1662129867961553920 -1662129868009554944 -1662129868054555904 -1662129868096556800 -1662129868150557952 -1662129868192558848 -1662129868234559744 -1662129868279560704 -1662129868327561728 -1662129868378562816 -1662129868423563776 -1662129868465564672 -1662129868507565568 -1662129868549566464 -1662129868591567360 -1662129868633568256 -1662129868675569152 -1662129868723570176 -1662129868768571136 -1662129868822572288 -1662129868867573248 -1662129868909574144 -1662129868957575168 -1662129869002576128 -1662129869050577152 -1662129869092578048 -1662129869137579008 -1662129869182579968 -1662129869224580864 -1662129869266581760 -1662129869314582784 -1662129869356583680 -1662129869401584640 -1662129869449585664 -1662129869491586560 -1662129869533587456 -1662129869575588352 -1662129869614589184 -1662129869659590144 -1662129869701591040 -1662129869749592064 -1662129869788592896 -1662129869830593792 -1662129869875594752 -1662129869917595648 -1662129869962596608 -1662129870010597632 -1662129870055598592 -1662129870097599488 -1662129870142600448 -1662129870184601344 -1662129870226602240 -1662129870271603200 -1662129870316604160 -1662129870355604992 -1662129870409606144 -1662129870451607040 -1662129870502608128 -1662129870541608960 -1662129870586609920 -1662129870628610816 -1662129870673611776 -1662129870718612736 -1662129870763613696 -1662129870808614656 -1662129870850615552 -1662129870892616448 -1662129870943617536 -1662129870985618432 -1662129871033619456 -1662129871078620416 -1662129871129621504 -1662129871171622400 -1662129871216623360 -1662129871258624256 -1662129871306625280 -1662129871348626176 -1662129871390627072 -1662129871432627968 -1662129871474628864 -1662129871525629952 -1662129871573630976 -1662129871615631872 -1662129871657632768 -1662129871702633728 -1662129871744634624 -1662129871789635584 -1662129871837636608 -1662129871885637632 -1662129871930638592 -1662129871972639488 -1662129872020640512 -1662129872065641472 -1662129872107642368 -1662129872149643264 -1662129872191644160 -1662129872239645184 -1662129872287646208 -1662129872332647168 -1662129872374648064 -1662129872419649024 -1662129872464649984 -1662129872509650944 -1662129872557651968 -1662129872602652928 -1662129872644653824 -1662129872689654784 -1662129872731655680 -1662129872773656576 -1662129872827657728 -1662129872875658752 -1662129872926659840 -1662129872977660928 -1662129873025661952 -1662129873070662912 -1662129873124664064 -1662129873178665216 -1662129873223666176 -1662129873271667200 -1662129873328668416 -1662129873370669312 -1662129873415670272 -1662129873460671232 -1662129873505672192 -1662129873547673088 -1662129873592674048 -1662129873634674944 -1662129873679675904 -1662129873721676800 -1662129873763677696 -1662129873808678656 -1662129873853679616 -1662129873898680576 -1662129873940681472 -1662129873982682368 -1662129874024683264 -1662129874072684288 -1662129874123685376 -1662129874168686336 -1662129874210687232 -1662129874255688192 -1662129874297689088 -1662129874348690176 -1662129874393691136 -1662129874435692032 -1662129874477692928 -1662129874522693888 -1662129874567694848 -1662129874609695744 -1662129874651696640 -1662129874693697536 -1662129874735698432 -1662129874780699392 -1662129874822700288 -1662129874867701248 -1662129874921702400 -1662129874966703360 -1662129875011704320 -1662129875053705216 -1662129875095706112 -1662129875137707008 -1662129875179707904 -1662129875221708800 -1662129875266709760 -1662129875311710720 -1662129875356711680 -1662129875395712512 -1662129875437713408 -1662129875482714368 -1662129875524715264 -1662129875569716224 -1662129875611717120 -1662129875650717952 -1662129875692718848 -1662129875743719936 -1662129875788720896 -1662129875830721792 -1662129875872722688 -1662129875917723648 -1662129875959724544 -1662129876001725440 -1662129876052726528 -1662129876103727616 -1662129876148728576 -1662129876190729472 -1662129876238730496 -1662129876286731520 -1662129876328732416 -1662129876373733376 -1662129876415734272 -1662129876463735296 -1662129876508736256 -1662129876550737152 -1662129876592738048 -1662129876634738944 -1662129876679739904 -1662129876727740928 -1662129876775741952 -1662129876817742848 -1662129876859743744 -1662129876904744704 -1662129876943745536 -1662129876985746432 -1662129877030747392 -1662129877075748352 -1662129877120749312 -1662129877165750272 -1662129877222751488 -1662129877270752512 -1662129877312753408 -1662129877357754368 -1662129877399755264 -1662129877441756160 -1662129877483757056 -1662129877528758016 -1662129877567758848 -1662129877609759744 -1662129877651760640 -1662129877696761600 -1662129877735762432 -1662129877783763456 -1662129877831764480 -1662129877873765376 -1662129877924766464 -1662129877969767424 -1662129878014768384 -1662129878053769216 -1662129878095770112 -1662129878140771072 -1662129878185772032 -1662129878227772928 -1662129878266773760 -1662129878311774720 -1662129878353775616 -1662129878401776640 -1662129878446777600 -1662129878488778496 -1662129878530779392 -1662129878578780416 -1662129878617781248 -1662129878665782272 -1662129878707783168 -1662129878752784128 -1662129878794785024 -1662129878845786112 -1662129878890787072 -1662129878932787968 -1662129878974788864 -1662129879025789952 -1662129879073790976 -1662129879115791872 -1662129879166792960 -1662129879214793984 -1662129879256794880 -1662129879295795712 -1662129879337796608 -1662129879382797568 -1662129879427798528 -1662129879469799424 -1662129879514800384 -1662129879559801344 -1662129879604802304 -1662129879652803328 -1662129879700804352 -1662129879742805248 -1662129879784806144 -1662129879832807168 -1662129879877808128 -1662129879925809152 -1662129879967810048 -1662129880009810944 -1662129880060812032 -1662129880105812992 -1662129880144813824 -1662129880189814784 -1662129880231815680 -1662129880279816704 -1662129880321817600 -1662129880366818560 -1662129880408819456 -1662129880456820480 -1662129880498821376 -1662129880540822272 -1662129880585823232 -1662129880624824064 -1662129880669825024 -1662129880711825920 -1662129880756826880 -1662129880801827840 -1662129880843828736 -1662129880885829632 -1662129880933830656 -1662129880981831680 -1662129881029832704 -1662129881074833664 -1662129881116834560 -1662129881158835456 -1662129881203836416 -1662129881245837312 -1662129881293838336 -1662129881335839232 -1662129881383840256 -1662129881425841152 -1662129881470842112 -1662129881524843264 -1662129881569844224 -1662129881611845120 -1662129881656846080 -1662129881704847104 -1662129881749848064 -1662129881794849024 -1662129881836849920 -1662129881887851008 -1662129881929851904 -1662129881977852928 -1662129882019853824 -1662129882064854784 -1662129882118855936 -1662129882163856896 -1662129882211857920 -1662129882253858816 -1662129882298859776 -1662129882340860672 -1662129882382861568 -1662129882421862400 -1662129882463863296 -1662129882508864256 -1662129882553865216 -1662129882601866240 -1662129882643867136 -1662129882685868032 -1662129882733869056 -1662129882781870080 -1662129882826871040 -1662129882871872000 -1662129882913872896 -1662129882955873792 -1662129882997874688 -1662129883036875520 -1662129883078876416 -1662129883132877568 -1662129883174878464 -1662129883216879360 -1662129883267880448 -1662129883309881344 -1662129883351882240 -1662129883399883264 -1662129883444884224 -1662129883483885056 -1662129883525885952 -1662129883576887040 -1662129883624888064 -1662129883675889152 -1662129883723890176 -1662129883762891008 -1662129883810892032 -1662129883861893120 -1662129883903894016 -1662129883948894976 -1662129883996896000 -1662129884038896896 -1662129884092898048 -1662129884137899008 -1662129884185900032 -1662129884230900992 -1662129884281902080 -1662129884320902912 -1662129884368903936 -1662129884407904768 -1662129884452905728 -1662129884497906688 -1662129884548907776 -1662129884593908736 -1662129884635909632 -1662129884686910720 -1662129884737911808 -1662129884782912768 -1662129884827913728 -1662129884872914688 -1662129884923915776 -1662129884968916736 -1662129885010917632 -1662129885049918464 -1662129885091919360 -1662129885142920448 -1662129885187921408 -1662129885229922304 -1662129885277923328 -1662129885322924288 -1662129885367925248 -1662129885409926144 -1662129885454927104 -1662129885505928192 -1662129885550929152 -1662129885595930112 -1662129885643931136 -1662129885685932032 -1662129885730932992 -1662129885772933888 -1662129885826935040 -1662129885877936128 -1662129885919937024 -1662129885961937920 -1662129886006938880 -1662129886060940032 -1662129886105940992 -1662129886147941888 -1662129886192942848 -1662129886234943744 -1662129886276944640 -1662129886318945536 -1662129886378946816 -1662129886423947776 -1662129886465948672 -1662129886510949632 -1662129886558950656 -1662129886603951616 -1662129886645952512 -1662129886687953408 -1662129886732954368 -1662129886777955328 -1662129886819956224 -1662129886861957120 -1662129886909958144 -1662129886951959040 -1662129886996960000 -1662129887038960896 -1662129887080961792 -1662129887134962944 -1662129887173963776 -1662129887218964736 -1662129887263965696 -1662129887308966656 -1662129887353967616 -1662129887398968576 -1662129887449969664 -1662129887491970560 -1662129887533971456 -1662129887578972416 -1662129887623973376 -1662129887665974272 -1662129887710975232 -1662129887758976256 -1662129887797977088 -1662129887839977984 -1662129887881978880 -1662129887929979904 -1662129887974980864 -1662129888019981824 -1662129888061982720 -1662129888112983808 -1662129888151984640 -1662129888199985664 -1662129888244986624 -1662129888286987520 -1662129888331988480 -1662129888376989440 -1662129888418990336 -1662129888460991232 -1662129888508992256 -1662129888553993216 -1662129888595994112 -1662129888637995008 -1662129888679995904 -1662129888721996800 -1662129888763997696 -1662129888808998656 -1662129888850999552 -1662129888893000448 -1662129888935001344 -1662129888980002304 -1662129889025003264 -1662129889064004096 -1662129889112005120 -1662129889157006080 -1662129889202007040 -1662129889241007872 -1662129889289008896 -1662129889331009792 -1662129889376010752 -1662129889424011776 -1662129889466012672 -1662129889508013568 -1662129889559014656 -1662129889604015616 -1662129889643016448 -1662129889685017344 -1662129889730018304 -1662129889772019200 -1662129889826020352 -1662129889865021184 -1662129889904022016 -1662129889952023040 -1662129889997024000 -1662129890039024896 -1662129890081025792 -1662129890123026688 -1662129890171027712 -1662129890213028608 -1662129890255029504 -1662129890297030400 -1662129890339031296 -1662129890381032192 -1662129890423033088 -1662129890471034112 -1662129890513035008 -1662129890558035968 -1662129890603036928 -1662129890648037888 -1662129890702039040 -1662129890750040064 -1662129890789040896 -1662129890840041984 -1662129890882042880 -1662129890927043840 -1662129890972044800 -1662129891020045824 -1662129891062046720 -1662129891116047872 -1662129891164048896 -1662129891209049856 -1662129891257050880 -1662129891299051776 -1662129891344052736 -1662129891386053632 -1662129891428054528 -1662129891467055360 -1662129891509056256 -1662129891554057216 -1662129891599058176 -1662129891644059136 -1662129891686060032 -1662129891743061248 -1662129891785062144 -1662129891824062976 -1662129891863063808 -1662129891911064832 -1662129891956065792 -1662129891998066688 -1662129892040067584 -1662129892088068608 -1662129892133069568 -1662129892175070464 -1662129892217071360 -1662129892259072256 -1662129892304073216 -1662129892346074112 -1662129892391075072 -1662129892436076032 -1662129892484077056 -1662129892523077888 -1662129892565078784 -1662129892610079744 -1662129892655080704 -1662129892697081600 -1662129892745082624 -1662129892787083520 -1662129892835084544 -1662129892880085504 -1662129892931086592 -1662129892973087488 -1662129893015088384 -1662129893057089280 -1662129893096090112 -1662129893138091008 -1662129893183091968 -1662129893228092928 -1662129893276093952 -1662129893327095040 -1662129893369095936 -1662129893414096896 -1662129893459097856 -1662129893501098752 -1662129893546099712 -1662129893600100864 -1662129893645101824 -1662129893687102720 -1662129893735103744 -1662129893774104576 -1662129893816105472 -1662129893858106368 -1662129893900107264 -1662129893948108288 -1662129893990109184 -1662129894035110144 -1662129894080111104 -1662129894128112128 -1662129894170113024 -1662129894215113984 -1662129894257114880 -1662129894299115776 -1662129894341116672 -1662129894386117632 -1662129894425118464 -1662129894467119360 -1662129894515120384 -1662129894560121344 -1662129894611122432 -1662129894650123264 -1662129894695124224 -1662129894737125120 -1662129894782126080 -1662129894833127168 -1662129894884128256 -1662129894929129216 -1662129894977130240 -1662129895034131456 -1662129895085132544 -1662129895130133504 -1662129895172134400 -1662129895214135296 -1662129895262136320 -1662129895304137216 -1662129895343138048 -1662129895385138944 -1662129895427139840 -1662129895466140672 -1662129895511141632 -1662129895568142848 -1662129895616143872 -1662129895661144832 -1662129895709145856 -1662129895760146944 -1662129895808147968 -1662129895850148864 -1662129895895149824 -1662129895934150656 -1662129895979151616 -1662129896033152768 -1662129896075153664 -1662129896126154752 -1662129896171155712 -1662129896216156672 -1662129896258157568 -1662129896303158528 -1662129896348159488 -1662129896390160384 -1662129896438161408 -1662129896486162432 -1662129896534163456 -1662129896582164480 -1662129896621165312 -1662129896669166336 -1662129896714167296 -1662129896756168192 -1662129896801169152 -1662129896849170176 -1662129896897171200 -1662129896945172224 -1662129896990173184 -1662129897032174080 -1662129897077175040 -1662129897122176000 -1662129897170177024 -1662129897212177920 -1662129897254178816 -1662129897299179776 -1662129897341180672 -1662129897380181504 -1662129897428182528 -1662129897479183616 -1662129897521184512 -1662129897566185472 -1662129897605186304 -1662129897647187200 -1662129897695188224 -1662129897734189056 -1662129897776189952 -1662129897821190912 -1662129897863191808 -1662129897908192768 -1662129897956193792 -1662129897998194688 -1662129898037195520 -1662129898085196544 -1662129898127197440 -1662129898169198336 -1662129898220199424 -1662129898262200320 -1662129898307201280 -1662129898349202176 -1662129898397203200 -1662129898448204288 -1662129898493205248 -1662129898538206208 -1662129898586207232 -1662129898646208512 -1662129898694209536 -1662129898736210432 -1662129898784211456 -1662129898829212416 -1662129898877213440 -1662129898919214336 -1662129898970215424 -1662129899015216384 -1662129899063217408 -1662129899111218432 -1662129899156219392 -1662129899204220416 -1662129899246221312 -1662129899291222272 -1662129899333223168 -1662129899378224128 -1662129899420225024 -1662129899462225920 -1662129899504226816 -1662129899549227776 -1662129899591228672 -1662129899636229632 -1662129899687230720 -1662129899732231680 -1662129899774232576 -1662129899816233472 -1662129899858234368 -1662129899900235264 -1662129899945236224 -1662129899993237248 -1662129900041238272 -1662129900083239168 -1662129900137240320 -1662129900188241408 -1662129900233242368 -1662129900284243456 -1662129900329244416 -1662129900371245312 -1662129900410246144 -1662129900449246976 -1662129900497248000 -1662129900539248896 -1662129900584249856 -1662129900635250944 -1662129900683251968 -1662129900725252864 -1662129900770253824 -1662129900821254912 -1662129900863255808 -1662129900905256704 -1662129900956257792 -1662129900998258688 -1662129901040259584 -1662129901082260480 -1662129901136261632 -1662129901178262528 -1662129901217263360 -1662129901262264320 -1662129901304265216 -1662129901352266240 -1662129901403267328 -1662129901448268288 -1662129901493269248 -1662129901535270144 -1662129901577271040 -1662129901631272192 -1662129901676273152 -1662129901715273984 -1662129901760274944 -1662129901799275776 -1662129901844276736 -1662129901886277632 -1662129901928278528 -1662129901973279488 -1662129902015280384 -1662129902057281280 -1662129902099282176 -1662129902141283072 -1662129902183283968 -1662129902225284864 -1662129902270285824 -1662129902318286848 -1662129902363287808 -1662129902408288768 -1662129902459289856 -1662129902507290880 -1662129902555291904 -1662129902597292800 -1662129902651293952 -1662129902696294912 -1662129902738295808 -1662129902789296896 -1662129902831297792 -1662129902882298880 -1662129902936300032 -1662129902978300928 -1662129903020301824 -1662129903062302720 -1662129903110303744 -1662129903155304704 -1662129903197305600 -1662129903239306496 -1662129903281307392 -1662129903323308288 -1662129903365309184 -1662129903410310144 -1662129903455311104 -1662129903494311936 -1662129903536312832 -1662129903578313728 -1662129903617314560 -1662129903662315520 -1662129903704316416 -1662129903749317376 -1662129903791318272 -1662129903833319168 -1662129903875320064 -1662129903920321024 -1662129903962321920 -1662129904019323136 -1662129904061324032 -1662129904106324992 -1662129904151325952 -1662129904199326976 -1662129904241327872 -1662129904289328896 -1662129904331329792 -1662129904379330816 -1662129904421331712 -1662129904463332608 -1662129904505333504 -1662129904547334400 -1662129904592335360 -1662129904634336256 -1662129904679337216 -1662129904721338112 -1662129904766339072 -1662129904805339904 -1662129904847340800 -1662129904889341696 -1662129904931342592 -1662129904976343552 -1662129905021344512 -1662129905063345408 -1662129905105346304 -1662129905156347392 -1662129905195348224 -1662129905231348992 -1662129905276349952 -1662129905318350848 -1662129905363351808 -1662129905405352704 -1662129905450353664 -1662129905492354560 -1662129905537355520 -1662129905591356672 -1662129905633357568 -1662129905687358720 -1662129905738359808 -1662129905780360704 -1662129905825361664 -1662129905867362560 -1662129905918363648 -1662129905960364544 -1662129906005365504 -1662129906047366400 -1662129906089367296 -1662129906131368192 -1662129906176369152 -1662129906224370176 -1662129906266371072 -1662129906311372032 -1662129906362373120 -1662129906404374016 -1662129906449374976 -1662129906494375936 -1662129906536376832 -1662129906578377728 -1662129906623378688 -1662129906668379648 -1662129906707380480 -1662129906749381376 -1662129906803382528 -1662129906845383424 -1662129906887384320 -1662129906932385280 -1662129906974386176 -1662129907019387136 -1662129907064388096 -1662129907106388992 -1662129907151389952 -1662129907196390912 -1662129907238391808 -1662129907286392832 -1662129907331393792 -1662129907370394624 -1662129907412395520 -1662129907454396416 -1662129907499397376 -1662129907541398272 -1662129907583399168 -1662129907625400064 -1662129907670401024 -1662129907712401920 -1662129907760402944 -1662129907811404032 -1662129907853404928 -1662129907898405888 -1662129907937406720 -1662129907982407680 -1662129908027408640 -1662129908072409600 -1662129908123410688 -1662129908168411648 -1662129908216412672 -1662129908258413568 -1662129908303414528 -1662129908345415424 -1662129908387416320 -1662129908441417472 -1662129908498418688 -1662129908549419776 -1662129908591420672 -1662129908639421696 -1662129908687422720 -1662129908729423616 -1662129908771424512 -1662129908816425472 -1662129908858426368 -1662129908915427584 -1662129908960428544 -1662129909005429504 -1662129909050430464 -1662129909095431424 -1662129909140432384 -1662129909179433216 -1662129909221434112 -1662129909266435072 -1662129909305435904 -1662129909347436800 -1662129909392437760 -1662129909434438656 -1662129909479439616 -1662129909521440512 -1662129909572441600 -1662129909611442432 -1662129909653443328 -1662129909698444288 -1662129909740445184 -1662129909782446080 -1662129909824446976 -1662129909866447872 -1662129909905448704 -1662129909959449856 -1662129910001450752 -1662129910049451776 -1662129910091452672 -1662129910136453632 -1662129910181454592 -1662129910223455488 -1662129910265456384 -1662129910313457408 -1662129910364458496 -1662129910409459456 -1662129910448460288 -1662129910496461312 -1662129910541462272 -1662129910589463296 -1662129910634464256 -1662129910679465216 -1662129910718466048 -1662129910760466944 -1662129910808467968 -1662129910850468864 -1662129910892469760 -1662129910934470656 -1662129910985471744 -1662129911030472704 -1662129911072473600 -1662129911114474496 -1662129911162475520 -1662129911204476416 -1662129911255477504 -1662129911306478592 -1662129911348479488 -1662129911390480384 -1662129911429481216 -1662129911474482176 -1662129911519483136 -1662129911561484032 -1662129911606484992 -1662129911651485952 -1662129911693486848 -1662129911732487680 -1662129911774488576 -1662129911828489728 -1662129911876490752 -1662129911924491776 -1662129911975492864 -1662129912020493824 -1662129912062494720 -1662129912107495680 -1662129912155496704 -1662129912197497600 -1662129912239498496 -1662129912281499392 -1662129912326500352 -1662129912368501248 -1662129912413502208 -1662129912452503040 -1662129912497504000 -1662129912539504896 -1662129912584505856 -1662129912626506752 -1662129912671507712 -1662129912710508544 -1662129912755509504 -1662129912797510400 -1662129912839511296 -1662129912881512192 -1662129912926513152 -1662129912974514176 -1662129913019515136 -1662129913067516160 -1662129913121517312 -1662129913169518336 -1662129913211519232 -1662129913253520128 -1662129913301521152 -1662129913349522176 -1662129913391523072 -1662129913436524032 -1662129913484525056 -1662129913529526016 -1662129913574526976 -1662129913616527872 -1662129913667528960 -1662129913709529856 -1662129913751530752 -1662129913793531648 -1662129913844532736 -1662129913889533696 -1662129913931534592 -1662129913979535616 -1662129914030536704 -1662129914078537728 -1662129914123538688 -1662129914168539648 -1662129914219540736 -1662129914267541760 -1662129914318542848 -1662129914363543808 -1662129914411544832 -1662129914453545728 -1662129914495546624 -1662129914540547584 -1662129914588548608 -1662129914633549568 -1662129914681550592 -1662129914729551616 -1662129914777552640 -1662129914825553664 -1662129914867554560 -1662129914909555456 -1662129914960556544 -1662129915002557440 -1662129915047558400 -1662129915089559296 -1662129915134560256 -1662129915176561152 -1662129915218562048 -1662129915260562944 -1662129915302563840 -1662129915353564928 -1662129915395565824 -1662129915440566784 -1662129915485567744 -1662129915533568768 -1662129915575569664 -1662129915617570560 -1662129915659571456 -1662129915704572416 -1662129915752573440 -1662129915797574400 -1662129915839575296 -1662129915881576192 -1662129915929577216 -1662129915971578112 -1662129916016579072 -1662129916067580160 -1662129916118581248 -1662129916160582144 -1662129916205583104 -1662129916244583936 -1662129916295585024 -1662129916349586176 -1662129916394587136 -1662129916442588160 -1662129916487589120 -1662129916535590144 -1662129916586591232 -1662129916631592192 -1662129916673593088 -1662129916721594112 -1662129916766595072 -1662129916811596032 -1662129916868597248 -1662129916913598208 -1662129916958599168 -1662129917000600064 -1662129917051601152 -1662129917096602112 -1662129917147603200 -1662129917192604160 -1662129917234605056 -1662129917276605952 -1662129917318606848 -1662129917360607744 -1662129917402608640 -1662129917450609664 -1662129917504610816 -1662129917549611776 -1662129917594612736 -1662129917639613696 -1662129917681614592 -1662129917732615680 -1662129917780616704 -1662129917825617664 -1662129917873618688 -1662129917921619712 -1662129917960620544 -1662129918005621504 -1662129918044622336 -1662129918089623296 -1662129918137624320 -1662129918182625280 -1662129918239626496 -1662129918278627328 -1662129918320628224 -1662129918362629120 -1662129918407630080 -1662129918455631104 -1662129918506632192 -1662129918554633216 -1662129918596634112 -1662129918641635072 -1662129918692636160 -1662129918740637184 -1662129918782638080 -1662129918824638976 -1662129918869639936 -1662129918917640960 -1662129918968642048 -1662129919013643008 -1662129919055643904 -1662129919100644864 -1662129919145645824 -1662129919187646720 -1662129919226647552 -1662129919280648704 -1662129919325649664 -1662129919367650560 -1662129919415651584 -1662129919463652608 -1662129919505653504 -1662129919556654592 -1662129919601655552 -1662129919649656576 -1662129919694657536 -1662129919736658432 -1662129919781659392 -1662129919823660288 -1662129919865661184 -1662129919910662144 -1662129919952663040 -1662129919991663872 -1662129920033664768 -1662129920081665792 -1662129920126666752 -1662129920168667648 -1662129920219668736 -1662129920261669632 -1662129920303670528 -1662129920348671488 -1662129920396672512 -1662129920444673536 -1662129920483674368 -1662129920534675456 -1662129920582676480 -1662129920627677440 -1662129920669678336 -1662129920711679232 -1662129920753680128 -1662129920798681088 -1662129920846682112 -1662129920891683072 -1662129920933683968 -1662129920975684864 -1662129921020685824 -1662129921062686720 -1662129921107687680 -1662129921149688576 -1662129921191689472 -1662129921233690368 -1662129921278691328 -1662129921329692416 -1662129921368693248 -1662129921410694144 -1662129921461695232 -1662129921506696192 -1662129921551697152 -1662129921593698048 -1662129921635698944 -1662129921677699840 -1662129921728700928 -1662129921773701888 -1662129921812702720 -1662129921854703616 -1662129921893704448 -1662129921941705472 -1662129921986706432 -1662129922028707328 -1662129922070708224 -1662129922115709184 -1662129922157710080 -1662129922202711040 -1662129922253712128 -1662129922298713088 -1662129922340713984 -1662129922391715072 -1662129922442716160 -1662129922490717184 -1662129922541718272 -1662129922583719168 -1662129922625720064 -1662129922670721024 -1662129922715721984 -1662129922757722880 -1662129922808723968 -1662129922850724864 -1662129922892725760 -1662129922937726720 -1662129922982727680 -1662129923027728640 -1662129923069729536 -1662129923111730432 -1662129923153731328 -1662129923201732352 -1662129923252733440 -1662129923297734400 -1662129923345735424 -1662129923396736512 -1662129923441737472 -1662129923483738368 -1662129923528739328 -1662129923570740224 -1662129923612741120 -1662129923657742080 -1662129923696742912 -1662129923738743808 -1662129923786744832 -1662129923834745856 -1662129923879746816 -1662129923930747904 -1662129923981748992 -1662129924020749824 -1662129924062750720 -1662129924101751552 -1662129924146752512 -1662129924200753664 -1662129924239754496 -1662129924287755520 -1662129924329756416 -1662129924368757248 -1662129924413758208 -1662129924461759232 -1662129924503760128 -1662129924545761024 -1662129924593762048 -1662129924641763072 -1662129924683763968 -1662129924725764864 -1662129924776765952 -1662129924827767040 -1662129924869767936 -1662129924914768896 -1662129924959769856 -1662129925001770752 -1662129925043771648 -1662129925085772544 -1662129925127773440 -1662129925172774400 -1662129925217775360 -1662129925259776256 -1662129925298777088 -1662129925343778048 -1662129925385778944 -1662129925430779904 -1662129925469780736 -1662129925511781632 -1662129925559782656 -1662129925607783680 -1662129925652784640 -1662129925697785600 -1662129925748786688 -1662129925790787584 -1662129925835788544 -1662129925883789568 -1662129925925790464 -1662129925970791424 -1662129926012792320 -1662129926054793216 -1662129926096794112 -1662129926138795008 -1662129926180795904 -1662129926225796864 -1662129926267797760 -1662129926312798720 -1662129926351799552 -1662129926393800448 -1662129926438801408 -1662129926489802496 -1662129926537803520 -1662129926579804416 -1662129926621805312 -1662129926675806464 -1662129926720807424 -1662129926762808320 -1662129926807809280 -1662129926852810240 -1662129926900811264 -1662129926951812352 -1662129926996813312 -1662129927044814336 -1662129927095815424 -1662129927146816512 -1662129927188817408 -1662129927233818368 -1662129927275819264 -1662129927320820224 -1662129927362821120 -1662129927407822080 -1662129927455823104 -1662129927497824000 -1662129927542824960 -1662129927587825920 -1662129927632826880 -1662129927680827904 -1662129927728828928 -1662129927779830016 -1662129927833831168 -1662129927878832128 -1662129927920833024 -1662129927962833920 -1662129928007834880 -1662129928049835776 -1662129928103836928 -1662129928145837824 -1662129928187838720 -1662129928229839616 -1662129928271840512 -1662129928316841472 -1662129928364842496 -1662129928409843456 -1662129928457844480 -1662129928493845248 -1662129928544846336 -1662129928586847232 -1662129928631848192 -1662129928676849152 -1662129928724850176 -1662129928763851008 -1662129928808851968 -1662129928847852800 -1662129928892853760 -1662129928940854784 -1662129928982855680 -1662129929024856576 -1662129929066857472 -1662129929108858368 -1662129929150859264 -1662129929195860224 -1662129929237861120 -1662129929279862016 -1662129929321862912 -1662129929363863808 -1662129929402864640 -1662129929447865600 -1662129929498866688 -1662129929540867584 -1662129929582868480 -1662129929627869440 -1662129929681870592 -1662129929729871616 -1662129929780872704 -1662129929825873664 -1662129929867874560 -1662129929918875648 -1662129929963876608 -1662129930008877568 -1662129930050878464 -1662129930092879360 -1662129930134880256 -1662129930182881280 -1662129930227882240 -1662129930269883136 -1662129930317884160 -1662129930362885120 -1662129930413886208 -1662129930458887168 -1662129930503888128 -1662129930551889152 -1662129930593890048 -1662129930635890944 -1662129930677891840 -1662129930719892736 -1662129930767893760 -1662129930818894848 -1662129930869895936 -1662129930914896896 -1662129930965897984 -1662129931010898944 -1662129931052899840 -1662129931100900864 -1662129931142901760 -1662129931184902656 -1662129931223903488 -1662129931265904384 -1662129931307905280 -1662129931346906112 -1662129931388907008 -1662129931433907968 -1662129931478908928 -1662129931526909952 -1662129931571910912 -1662129931619911936 -1662129931670913024 -1662129931721914112 -1662129931766915072 -1662129931820916224 -1662129931862917120 -1662129931910918144 -1662129931952919040 -1662129931997920000 -1662129932042920960 -1662129932084921856 -1662129932132922880 -1662129932177923840 -1662129932225924864 -1662129932267925760 -1662129932315926784 -1662129932363927808 -1662129932405928704 -1662129932447929600 -1662129932489930496 -1662129932537931520 -1662129932579932416 -1662129932621933312 -1662129932666934272 -1662129932711935232 -1662129932756936192 -1662129932807937280 -1662129932846938112 -1662129932885938944 -1662129932933939968 -1662129932984941056 -1662129933029942016 -1662129933068942848 -1662129933113943808 -1662129933155944704 -1662129933203945728 -1662129933245946624 -1662129933284947456 -1662129933326948352 -1662129933371949312 -1662129933416950272 -1662129933464951296 -1662129933506952192 -1662129933551953152 -1662129933593954048 -1662129933635954944 -1662129933686956032 -1662129933731956992 -1662129933773957888 -1662129933821958912 -1662129933863959808 -1662129933908960768 -1662129933956961792 -1662129933998962688 -1662129934040963584 -1662129934085964544 -1662129934130965504 -1662129934181966592 -1662129934226967552 -1662129934268968448 -1662129934313969408 -1662129934364970496 -1662129934409971456 -1662129934451972352 -1662129934508973568 -1662129934556974592 -1662129934604975616 -1662129934646976512 -1662129934688977408 -1662129934736978432 -1662129934778979328 -1662129934820980224 -1662129934862981120 -1662129934904982016 -1662129934946982912 -1662129934988983808 -1662129935033984768 -1662129935078985728 -1662129935120986624 -1662129935162987520 -1662129935204988416 -1662129935246989312 -1662129935294990336 -1662129935348991488 -1662129935399992576 -1662129935441993472 -1662129935483994368 -1662129935528995328 -1662129935570996224 -1662129935615997184 -1662129935657998080 -1662129935696998912 -1662129935738999808 -1662129935781000704 -1662129935826001664 -1662129935868002560 -1662129935910003456 -1662129935955004416 -1662129936000005376 -1662129936048006400 -1662129936099007488 -1662129936141008384 -1662129936192009472 -1662129936240010496 -1662129936285011456 -1662129936327012352 -1662129936369013248 -1662129936414014208 -1662129936471015424 -1662129936513016320 -1662129936564017408 -1662129936609018368 -1662129936654019328 -1662129936696020224 -1662129936738021120 -1662129936783022080 -1662129936825022976 -1662129936867023872 -1662129936912024832 -1662129936951025664 -1662129936993026560 -1662129937035027456 -1662129937086028544 -1662129937131029504 -1662129937176030464 -1662129937218031360 -1662129937260032256 -1662129937305033216 -1662129937353034240 -1662129937395035136 -1662129937437036032 -1662129937479036928 -1662129937524037888 -1662129937569038848 -1662129937608039680 -1662129937653040640 -1662129937701041664 -1662129937752042752 -1662129937797043712 -1662129937839044608 -1662129937881045504 -1662129937923046400 -1662129937974047488 -1662129938019048448 -1662129938073049600 -1662129938118050560 -1662129938169051648 -1662129938211052544 -1662129938259053568 -1662129938304054528 -1662129938349055488 -1662129938391056384 -1662129938436057344 -1662129938484058368 -1662129938532059392 -1662129938574060288 -1662129938619061248 -1662129938661062144 -1662129938703063040 -1662129938745063936 -1662129938787064832 -1662129938832065792 -1662129938871066624 -1662129938913067520 -1662129938961068544 -1662129939006069504 -1662129939048070400 -1662129939096071424 -1662129939135072256 -1662129939186073344 -1662129939231074304 -1662129939273075200 -1662129939315076096 -1662129939360077056 -1662129939408078080 -1662129939450078976 -1662129939492079872 -1662129939534080768 -1662129939579081728 -1662129939621082624 -1662129939669083648 -1662129939714084608 -1662129939759085568 -1662129939804086528 -1662129939843087360 -1662129939888088320 -1662129939933089280 -1662129939975090176 -1662129940017091072 -1662129940062092032 -1662129940107092992 -1662129940149093888 -1662129940191094784 -1662129940236095744 -1662129940275096576 -1662129940317097472 -1662129940359098368 -1662129940404099328 -1662129940452100352 -1662129940500101376 -1662129940539102208 -1662129940581103104 -1662129940629104128 -1662129940671105024 -1662129940716105984 -1662129940764107008 -1662129940812108032 -1662129940854108928 -1662129940896109824 -1662129940938110720 -1662129940980111616 -1662129941019112448 -1662129941061113344 -1662129941103114240 -1662129941148115200 -1662129941187116032 -1662129941235117056 -1662129941277117952 -1662129941322118912 -1662129941364119808 -1662129941406120704 -1662129941448121600 -1662129941496122624 -1662129941541123584 -1662129941586124544 -1662129941628125440 -1662129941685126656 -1662129941733127680 -1662129941778128640 -1662129941823129600 -1662129941865130496 -1662129941910131456 -1662129941967132672 -1662129942012133632 -1662129942051134464 -1662129942093135360 -1662129942135136256 -1662129942174137088 -1662129942216137984 -1662129942258138880 -1662129942297139712 -1662129942339140608 -1662129942390141696 -1662129942429142528 -1662129942471143424 -1662129942513144320 -1662129942558145280 -1662129942600146176 -1662129942639147008 -1662129942681147904 -1662129942723148800 -1662129942771149824 -1662129942810150656 -1662129942864151808 -1662129942906152704 -1662129942957153792 -1662129943005154816 -1662129943047155712 -1662129943086156544 -1662129943128157440 -1662129943167158272 -1662129943215159296 -1662129943257160192 -1662129943299161088 -1662129943344162048 -1662129943395163136 -1662129943440164096 -1662129943482164992 -1662129943527165952 -1662129943578167040 -1662129943623168000 -1662129943671169024 -1662129943710169856 -1662129943752170752 -1662129943797171712 -1662129943845172736 -1662129943893173760 -1662129943935174656 -1662129943977175552 -1662129944022176512 -1662129944064177408 -1662129944109178368 -1662129944151179264 -1662129944199180288 -1662129944247181312 -1662129944295182336 -1662129944337183232 -1662129944379184128 -1662129944421185024 -1662129944466185984 -1662129944511186944 -1662129944553187840 -1662129944595188736 -1662129944643189760 -1662129944685190656 -1662129944730191616 -1662129944772192512 -1662129944814193408 -1662129944859194368 -1662129944904195328 -1662129944946196224 -1662129944997197312 -1662129945039198208 -1662129945087199232 -1662129945135200256 -1662129945177201152 -1662129945222202112 -1662129945273203200 -1662129945324204288 -1662129945375205376 -1662129945426206464 -1662129945468207360 -1662129945510208256 -1662129945558209280 -1662129945609210368 -1662129945654211328 -1662129945696212224 -1662129945738213120 -1662129945783214080 -1662129945825214976 -1662129945873216000 -1662129945927217152 -1662129945966217984 -1662129946014219008 -1662129946059219968 -1662129946107220992 -1662129946155222016 -1662129946197222912 -1662129946242223872 -1662129946290224896 -1662129946332225792 -1662129946377226752 -1662129946425227776 -1662129946479228928 -1662129946521229824 -1662129946563230720 -1662129946608231680 -1662129946650232576 -1662129946692233472 -1662129946737234432 -1662129946782235392 -1662129946824236288 -1662129946866237184 -1662129946911238144 -1662129946956239104 -1662129946998240000 -1662129947040240896 -1662129947082241792 -1662129947124242688 -1662129947169243648 -1662129947211244544 -1662129947250245376 -1662129947292246272 -1662129947346247424 -1662129947391248384 -1662129947433249280 -1662129947478250240 -1662129947526251264 -1662129947574252288 -1662129947619253248 -1662129947667254272 -1662129947709255168 -1662129947754256128 -1662129947796257024 -1662129947841257984 -1662129947895259136 -1662129947940260096 -1662129947982260992 -1662129948033262080 -1662129948084263168 -1662129948129264128 -1662129948174265088 -1662129948219266048 -1662129948261266944 -1662129948312268032 -1662129948360269056 -1662129948402269952 -1662129948441270784 -1662129948486271744 -1662129948528272640 -1662129948570273536 -1662129948618274560 -1662129948660275456 -1662129948702276352 -1662129948750277376 -1662129948798278400 -1662129948840279296 -1662129948885280256 -1662129948927281152 -1662129948969282048 -1662129949011282944 -1662129949056283904 -1662129949095284736 -1662129949137285632 -1662129949185286656 -1662129949230287616 -1662129949272288512 -1662129949314289408 -1662129949356290304 -1662129949401291264 -1662129949443292160 -1662129949488293120 -1662129949533294080 -1662129949575294976 -1662129949617295872 -1662129949668296960 -1662129949710297856 -1662129949758298880 -1662129949800299776 -1662129949842300672 -1662129949884301568 -1662129949929302528 -1662129949977303552 -1662129950022304512 -1662129950067305472 -1662129950106306304 -1662129950148307200 -1662129950193308160 -1662129950235309056 -1662129950283310080 -1662129950328311040 -1662129950370311936 -1662129950415312896 -1662129950463313920 -1662129950505314816 -1662129950559315968 -1662129950601316864 -1662129950661318144 -1662129950706319104 -1662129950763320320 -1662129950808321280 -1662129950850322176 -1662129950892323072 -1662129950931323904 -1662129950982324992 -1662129951027325952 -1662129951069326848 -1662129951111327744 -1662129951156328704 -1662129951198329600 -1662129951240330496 -1662129951291331584 -1662129951333332480 -1662129951384333568 -1662129951429334528 -1662129951471335424 -1662129951516336384 -1662129951561337344 -1662129951606338304 -1662129951648339200 -1662129951693340160 -1662129951735341056 -1662129951780342016 -1662129951825342976 -1662129951867343872 -1662129951909344768 -1662129951954345728 -1662129951996346624 -1662129952044347648 -1662129952086348544 -1662129952128349440 -1662129952179350528 -1662129952221351424 -1662129952263352320 -1662129952305353216 -1662129952350354176 -1662129952386354944 -1662129952434355968 -1662129952479356928 -1662129952524357888 -1662129952572358912 -1662129952617359872 -1662129952665360896 -1662129952707361792 -1662129952752362752 -1662129952797363712 -1662129952842364672 -1662129952887365632 -1662129952929366528 -1662129952971367424 -1662129953016368384 -1662129953058369280 -1662129953106370304 -1662129953154371328 -1662129953199372288 -1662129953247373312 -1662129953298374400 -1662129953340375296 -1662129953394376448 -1662129953436377344 -1662129953475378176 -1662129953514379008 -1662129953568380160 -1662129953613381120 -1662129953655382016 -1662129953700382976 -1662129953739383808 -1662129953781384704 -1662129953826385664 -1662129953865386496 -1662129953907387392 -1662129953955388416 -1662129954000389376 -1662129954051390464 -1662129954093391360 -1662129954138392320 -1662129954183393280 -1662129954225394176 -1662129954267395072 -1662129954306395904 -1662129954354396928 -1662129954399397888 -1662129954441398784 -1662129954489399808 -1662129954531400704 -1662129954579401728 -1662129954630402816 -1662129954672403712 -1662129954714404608 -1662129954756405504 -1662129954798406400 -1662129954840407296 -1662129954888408320 -1662129954930409216 -1662129954975410176 -1662129955023411200 -1662129955071412224 -1662129955116413184 -1662129955158414080 -1662129955206415104 -1662129955254416128 -1662129955299417088 -1662129955344418048 -1662129955386418944 -1662129955428419840 -1662129955473420800 -1662129955518421760 -1662129955560422656 -1662129955608423680 -1662129955659424768 -1662129955701425664 -1662129955746426624 -1662129955800427776 -1662129955845428736 -1662129955887429632 -1662129955929430528 -1662129955968431360 -1662129956010432256 -1662129956052433152 -1662129956094434048 -1662129956139435008 -1662129956184435968 -1662129956226436864 -1662129956268437760 -1662129956313438720 -1662129956358439680 -1662129956406440704 -1662129956445441536 -1662129956490442496 -1662129956535443456 -1662129956583444480 -1662129956634445568 -1662129956676446464 -1662129956718447360 -1662129956760448256 -1662129956802449152 -1662129956850450176 -1662129956889451008 -1662129956931451904 -1662129956973452800 -1662129957015453696 -1662129957057454592 -1662129957102455552 -1662129957150456576 -1662129957198457600 -1662129957240458496 -1662129957288459520 -1662129957330460416 -1662129957378461440 -1662129957420462336 -1662129957462463232 -1662129957510464256 -1662129957555465216 -1662129957597466112 -1662129957642467072 -1662129957687468032 -1662129957729468928 -1662129957777469952 -1662129957825470976 -1662129957867471872 -1662129957912472832 -1662129957954473728 -1662129957999474688 -1662129958044475648 -1662129958089476608 -1662129958131477504 -1662129958191478784 -1662129958233479680 -1662129958278480640 -1662129958320481536 -1662129958362482432 -1662129958407483392 -1662129958452484352 -1662129958500485376 -1662129958545486336 -1662129958581487104 -1662129958626488064 -1662129958668488960 -1662129958710489856 -1662129958752490752 -1662129958797491712 -1662129958842492672 -1662129958884493568 -1662129958929494528 -1662129958971495424 -1662129959013496320 -1662129959055497216 -1662129959100498176 -1662129959142499072 -1662129959187500032 -1662129959229500928 -1662129959271501824 -1662129959313502720 -1662129959355503616 -1662129959397504512 -1662129959448505600 -1662129959499506688 -1662129959544507648 -1662129959589508608 -1662129959634509568 -1662129959679510528 -1662129959721511424 -1662129959766512384 -1662129959817513472 -1662129959859514368 -1662129959910515456 -1662129959955516416 -1662129959997517312 -1662129960039518208 -1662129960081519104 -1662129960123520000 -1662129960174521088 -1662129960219522048 -1662129960267523072 -1662129960309523968 -1662129960363525120 -1662129960405526016 -1662129960447526912 -1662129960489527808 -1662129960531528704 -1662129960576529664 -1662129960624530688 -1662129960666531584 -1662129960708532480 -1662129960750533376 -1662129960792534272 -1662129960831535104 -1662129960876536064 -1662129960921537024 -1662129960966537984 -1662129961005538816 -1662129961047539712 -1662129961092540672 -1662129961134541568 -1662129961179542528 -1662129961221543424 -1662129961263544320 -1662129961305545216 -1662129961350546176 -1662129961401547264 -1662129961443548160 -1662129961482548992 -1662129961524549888 -1662129961572550912 -1662129961614551808 -1662129961656552704 -1662129961698553600 -1662129961740554496 -1662129961779555328 -1662129961818556160 -1662129961860557056 -1662129961908558080 -1662129961953559040 -1662129961995559936 -1662129962037560832 -1662129962082561792 -1662129962124562688 -1662129962163563520 -1662129962205564416 -1662129962247565312 -1662129962289566208 -1662129962334567168 -1662129962385568256 -1662129962445569536 -1662129962496570624 -1662129962538571520 -1662129962583572480 -1662129962628573440 -1662129962676574464 -1662129962715575296 -1662129962757576192 -1662129962802577152 -1662129962847578112 -1662129962892579072 -1662129962943580160 -1662129962988581120 -1662129963039582208 -1662129963081583104 -1662129963126584064 -1662129963174585088 -1662129963216585984 -1662129963264587008 -1662129963306587904 -1662129963348588800 -1662129963390589696 -1662129963435590656 -1662129963477591552 -1662129963519592448 -1662129963561593344 -1662129963603594240 -1662129963648595200 -1662129963687596032 -1662129963729596928 -1662129963771597824 -1662129963822598912 -1662129963867599872 -1662129963909600768 -1662129963954601728 -1662129964005602816 -1662129964047603712 -1662129964101604864 -1662129964143605760 -1662129964188606720 -1662129964230607616 -1662129964275608576 -1662129964317609472 -1662129964359610368 -1662129964401611264 -1662129964446612224 -1662129964497613312 -1662129964539614208 -1662129964581615104 -1662129964626616064 -1662129964671617024 -1662129964713617920 -1662129964755618816 -1662129964800619776 -1662129964842620672 -1662129964887621632 -1662129964929622528 -1662129964977623552 -1662129965019624448 -1662129965067625472 -1662129965112626432 -1662129965157627392 -1662129965199628288 -1662129965253629440 -1662129965295630336 -1662129965334631168 -1662129965382632192 -1662129965427633152 -1662129965472634112 -1662129965514635008 -1662129965559635968 -1662129965604636928 -1662129965649637888 -1662129965694638848 -1662129965736639744 -1662129965784640768 -1662129965829641728 -1662129965880642816 -1662129965922643712 -1662129965964644608 -1662129966012645632 -1662129966054646528 -1662129966093647360 -1662129966138648320 -1662129966183649280 -1662129966228650240 -1662129966273651200 -1662129966324652288 -1662129966375653376 -1662129966420654336 -1662129966471655424 -1662129966516656384 -1662129966561657344 -1662129966606658304 -1662129966651659264 -1662129966696660224 -1662129966738661120 -1662129966780662016 -1662129966828663040 -1662129966870663936 -1662129966912664832 -1662129966954665728 -1662129966996666624 -1662129967041667584 -1662129967086668544 -1662129967128669440 -1662129967170670336 -1662129967209671168 -1662129967257672192 -1662129967296673024 -1662129967338673920 -1662129967386674944 -1662129967425675776 -1662129967467676672 -1662129967518677760 -1662129967560678656 -1662129967602679552 -1662129967647680512 -1662129967689681408 -1662129967731682304 -1662129967773683200 -1662129967818684160 -1662129967860685056 -1662129967905686016 -1662129967947686912 -1662129967992687872 -1662129968037688832 -1662129968088689920 -1662129968127690752 -1662129968172691712 -1662129968220692736 -1662129968271693824 -1662129968313694720 -1662129968355695616 -1662129968394696448 -1662129968433697280 -1662129968475698176 -1662129968517699072 -1662129968571700224 -1662129968622701312 -1662129968673702400 -1662129968715703296 -1662129968757704192 -1662129968805705216 -1662129968850706176 -1662129968895707136 -1662129968937708032 -1662129968979708928 -1662129969021709824 -1662129969063710720 -1662129969105711616 -1662129969162712832 -1662129969201713664 -1662129969252714752 -1662129969297715712 -1662129969339716608 -1662129969381717504 -1662129969423718400 -1662129969465719296 -1662129969513720320 -1662129969555721216 -1662129969600722176 -1662129969648723200 -1662129969690724096 -1662129969738725120 -1662129969783726080 -1662129969825726976 -1662129969870727936 -1662129969918728960 -1662129969966729984 -1662129970008730880 -1662129970059731968 -1662129970104732928 -1662129970149733888 -1662129970194734848 -1662129970242735872 -1662129970284736768 -1662129970335737856 -1662129970377738752 -1662129970419739648 -1662129970461740544 -1662129970503741440 -1662129970545742336 -1662129970590743296 -1662129970635744256 -1662129970677745152 -1662129970719746048 -1662129970764747008 -1662129970806747904 -1662129970851748864 -1662129970896749824 -1662129970941750784 -1662129970995751936 -1662129971043752960 -1662129971088753920 -1662129971136754944 -1662129971178755840 -1662129971220756736 -1662129971265757696 -1662129971313758720 -1662129971355759616 -1662129971403760640 -1662129971445761536 -1662129971496762624 -1662129971538763520 -1662129971583764480 -1662129971643765760 -1662129971682766592 -1662129971724767488 -1662129971769768448 -1662129971811769344 -1662129971859770368 -1662129971901771264 -1662129971943772160 -1662129971982772992 -1662129972024773888 -1662129972066774784 -1662129972108775680 -1662129972153776640 -1662129972195777536 -1662129972240778496 -1662129972285779456 -1662129972327780352 -1662129972369781248 -1662129972414782208 -1662129972456783104 -1662129972501784064 -1662129972540784896 -1662129972582785792 -1662129972627786752 -1662129972669787648 -1662129972717788672 -1662129972762789632 -1662129972804790528 -1662129972852791552 -1662129972894792448 -1662129972939793408 -1662129972981794304 -1662129973020795136 -1662129973062796032 -1662129973113797120 -1662129973155798016 -1662129973197798912 -1662129973239799808 -1662129973281800704 -1662129973323801600 -1662129973368802560 -1662129973416803584 -1662129973461804544 -1662129973506805504 -1662129973548806400 -1662129973590807296 -1662129973632808192 -1662129973674809088 -1662129973722810112 -1662129973773811200 -1662129973818812160 -1662129973866813184 -1662129973911814144 -1662129973953815040 -1662129973998816000 -1662129974040816896 -1662129974082817792 -1662129974124818688 -1662129974169819648 -1662129974211820544 -1662129974253821440 -1662129974295822336 -1662129974349823488 -1662129974391824384 -1662129974436825344 -1662129974481826304 -1662129974523827200 -1662129974580828416 -1662129974622829312 -1662129974667830272 -1662129974709831168 -1662129974754832128 -1662129974799833088 -1662129974844834048 -1662129974886834944 -1662129974940836096 -1662129974985837056 -1662129975027837952 -1662129975072838912 -1662129975114839808 -1662129975156840704 -1662129975201841664 -1662129975249842688 -1662129975291843584 -1662129975336844544 -1662129975384845568 -1662129975426846464 -1662129975471847424 -1662129975510848256 -1662129975561849344 -1662129975606850304 -1662129975657851392 -1662129975702852352 -1662129975747853312 -1662129975789854208 -1662129975834855168 -1662129975873856000 -1662129975918856960 -1662129975972858112 -1662129976017859072 -1662129976065860096 -1662129976110861056 -1662129976152861952 -1662129976197862912 -1662129976245863936 -1662129976287864832 -1662129976329865728 -1662129976377866752 -1662129976422867712 -1662129976473868800 -1662129976512869632 -1662129976557870592 -1662129976602871552 -1662129976644872448 -1662129976689873408 -1662129976731874304 -1662129976770875136 -1662129976812876032 -1662129976857876992 -1662129976896877824 -1662129976938878720 -1662129976983879680 -1662129977025880576 -1662129977070881536 -1662129977115882496 -1662129977154883328 -1662129977199884288 -1662129977250885376 -1662129977295886336 -1662129977334887168 -1662129977373888000 -1662129977415888896 -1662129977457889792 -1662129977499890688 -1662129977541891584 -1662129977583892480 -1662129977625893376 -1662129977670894336 -1662129977715895296 -1662129977757896192 -1662129977799897088 -1662129977844898048 -1662129977886898944 -1662129977937900032 -1662129977982900992 -1662129978030902016 -1662129978072902912 -1662129978111903744 -1662129978153904640 -1662129978201905664 -1662129978249906688 -1662129978297907712 -1662129978339908608 -1662129978381909504 -1662129978426910464 -1662129978477911552 -1662129978525912576 -1662129978567913472 -1662129978606914304 -1662129978648915200 -1662129978690916096 -1662129978732916992 -1662129978777917952 -1662129978822918912 -1662129978870919936 -1662129978921921024 -1662129978966921984 -1662129979014923008 -1662129979062924032 -1662129979104924928 -1662129979146925824 -1662129979188926720 -1662129979230927616 -1662129979272928512 -1662129979314929408 -1662129979353930240 -1662129979395931136 -1662129979437932032 -1662129979476932864 -1662129979521933824 -1662129979566934784 -1662129979611935744 -1662129979656936704 -1662129979704937728 -1662129979746938624 -1662129979788939520 -1662129979836940544 -1662129979875941376 -1662129979917942272 -1662129979956943104 -1662129980007944192 -1662129980052945152 -1662129980094946048 -1662129980139947008 -1662129980190948096 -1662129980232948992 -1662129980274949888 -1662129980316950784 -1662129980358951680 -1662129980400952576 -1662129980442953472 -1662129980490954496 -1662129980535955456 -1662129980577956352 -1662129980616957184 -1662129980661958144 -1662129980703959040 -1662129980745959936 -1662129980793960960 -1662129980841961984 -1662129980883962880 -1662129980928963840 -1662129980976964864 -1662129981027965952 -1662129981072966912 -1662129981117967872 -1662129981159968768 -1662129981201969664 -1662129981246970624 -1662129981285971456 -1662129981327972352 -1662129981378973440 -1662129981423974400 -1662129981462975232 -1662129981501976064 -1662129981543976960 -1662129981582977792 -1662129981624978688 -1662129981669979648 -1662129981711980544 -1662129981750981376 -1662129981792982272 -1662129981834983168 -1662129981876984064 -1662129981933985280 -1662129981975986176 -1662129982017987072 -1662129982059987968 -1662129982104988928 -1662129982146989824 -1662129982185990656 -1662129982230991616 -1662129982272992512 -1662129982314993408 -1662129982356994304 -1662129982401995264 -1662129982452996352 -1662129982494997248 -1662129982533998080 -1662129982575998976 -1662129982620999936 -1662129982669000960 -1662129982720002048 -1662129982774003200 -1662129982816004096 -1662129982858004992 -1662129982900005888 -1662129982942006784 -1662129982987007744 -1662129983029008640 -1662129983071009536 -1662129983131010816 -1662129983173011712 -1662129983221012736 -1662129983269013760 -1662129983311014656 -1662129983353015552 -1662129983398016512 -1662129983443017472 -1662129983488018432 -1662129983533019392 -1662129983575020288 -1662129983620021248 -1662129983668022272 -1662129983710023168 -1662129983752024064 -1662129983791024896 -1662129983833025792 -1662129983872026624 -1662129983917027584 -1662129983959028480 -1662129984013029632 -1662129984058030592 -1662129984100031488 -1662129984142032384 -1662129984181033216 -1662129984226034176 -1662129984274035200 -1662129984319036160 -1662129984367037184 -1662129984409038080 -1662129984457039104 -1662129984496039936 -1662129984541040896 -1662129984583041792 -1662129984628042752 -1662129984670043648 -1662129984724044800 -1662129984766045696 -1662129984811046656 -1662129984850047488 -1662129984892048384 -1662129984937049344 -1662129984979050240 -1662129985024051200 -1662129985069052160 -1662129985108052992 -1662129985150053888 -1662129985195054848 -1662129985243055872 -1662129985297057024 -1662129985342057984 -1662129985387058944 -1662129985432059904 -1662129985480060928 -1662129985525061888 -1662129985567062784 -1662129985615063808 -1662129985660064768 -1662129985711065856 -1662129985753066752 -1662129985792067584 -1662129985837068544 -1662129985879069440 -1662129985927070464 -1662129985975071488 -1662129986017072384 -1662129986065073408 -1662129986104074240 -1662129986149075200 -1662129986194076160 -1662129986233076992 -1662129986275077888 -1662129986320078848 -1662129986362079744 -1662129986404080640 -1662129986446081536 -1662129986488082432 -1662129986527083264 -1662129986569084160 -1662129986614085120 -1662129986665086208 -1662129986707087104 -1662129986755088128 -1662129986800089088 -1662129986842089984 -1662129986881090816 -1662129986923091712 -1662129986968092672 -1662129987013093632 -1662129987055094528 -1662129987097095424 -1662129987139096320 -1662129987178097152 -1662129987220098048 -1662129987268099072 -1662129987310099968 -1662129987352100864 -1662129987394101760 -1662129987439102720 -1662129987481103616 -1662129987529104640 -1662129987574105600 -1662129987622106624 -1662129987664107520 -1662129987706108416 -1662129987745109248 -1662129987790110208 -1662129987835111168 -1662129987880112128 -1662129987922113024 -1662129987961113856 -1662129988006114816 -1662129988048115712 -1662129988090116608 -1662129988132117504 -1662129988180118528 -1662129988225119488 -1662129988267120384 -1662129988309121280 -1662129988348122112 -1662129988390123008 -1662129988432123904 -1662129988474124800 -1662129988513125632 -1662129988561126656 -1662129988600127488 -1662129988648128512 -1662129988696129536 -1662129988738130432 -1662129988780131328 -1662129988831132416 -1662129988873133312 -1662129988921134336 -1662129988966135296 -1662129989011136256 -1662129989053137152 -1662129989092137984 -1662129989134138880 -1662129989179139840 -1662129989227140864 -1662129989269141760 -1662129989311142656 -1662129989356143616 -1662129989401144576 -1662129989443145472 -1662129989491146496 -1662129989533147392 -1662129989587148544 -1662129989629149440 -1662129989683150592 -1662129989725151488 -1662129989770152448 -1662129989812153344 -1662129989857154304 -1662129989899155200 -1662129989944156160 -1662129989986157056 -1662129990037158144 -1662129990079159040 -1662129990118159872 -1662129990160160768 -1662129990208161792 -1662129990253162752 -1662129990298163712 -1662129990334164480 -1662129990379165440 -1662129990421166336 -1662129990466167296 -1662129990508168192 -1662129990550169088 -1662129990601170176 -1662129990646171136 -1662129990691172096 -1662129990736173056 -1662129990781174016 -1662129990823174912 -1662129990865175808 -1662129990907176704 -1662129990949177600 -1662129990988178432 -1662129991027179264 -1662129991072180224 -1662129991111181056 -1662129991150181888 -1662129991192182784 -1662129991234183680 -1662129991276184576 -1662129991321185536 -1662129991366186496 -1662129991420187648 -1662129991462188544 -1662129991501189376 -1662129991540190208 -1662129991579191040 -1662129991621191936 -1662129991663192832 -1662129991708193792 -1662129991750194688 -1662129991792195584 -1662129991834196480 -1662129991882197504 -1662129991924198400 -1662129991966199296 -1662129992008200192 -1662129992047201024 -1662129992089201920 -1662129992131202816 -1662129992170203648 -1662129992209204480 -1662129992251205376 -1662129992290206208 -1662129992335207168 -1662129992380208128 -1662129992422209024 -1662129992464209920 -1662129992506210816 -1662129992551211776 -1662129992599212800 -1662129992641213696 -1662129992686214656 -1662129992731215616 -1662129992773216512 -1662129992821217536 -1662129992860218368 -1662129992905219328 -1662129992947220224 -1662129992989221120 -1662129993031222016 -1662129993073222912 -1662129993115223808 -1662129993163224832 -1662129993208225792 -1662129993250226688 -1662129993298227712 -1662129993355228928 -1662129993397229824 -1662129993439230720 -1662129993481231616 -1662129993523232512 -1662129993562233344 -1662129993607234304 -1662129993649235200 -1662129993691236096 -1662129993733236992 -1662129993775237888 -1662129993826238976 -1662129993877240064 -1662129993922241024 -1662129993976242176 -1662129994027243264 -1662129994072244224 -1662129994114245120 -1662129994156246016 -1662129994198246912 -1662129994243247872 -1662129994285248768 -1662129994327249664 -1662129994372250624 -1662129994414251520 -1662129994456252416 -1662129994498253312 -1662129994537254144 -1662129994579255040 -1662129994627256064 -1662129994672257024 -1662129994717257984 -1662129994759258880 -1662129994798259712 -1662129994843260672 -1662129994882261504 -1662129994924262400 -1662129994966263296 -1662129995008264192 -1662129995056265216 -1662129995104266240 -1662129995155267328 -1662129995197268224 -1662129995242269184 -1662129995287270144 -1662129995329271040 -1662129995371271936 -1662129995419272960 -1662129995458273792 -1662129995500274688 -1662129995545275648 -1662129995593276672 -1662129995635277568 -1662129995677278464 -1662129995719279360 -1662129995761280256 -1662129995803281152 -1662129995845282048 -1662129995887282944 -1662129995932283904 -1662129995983284992 -1662129996025285888 -1662129996067286784 -1662129996115287808 -1662129996157288704 -1662129996202289664 -1662129996244290560 -1662129996295291648 -1662129996340292608 -1662129996397293824 -1662129996442294784 -1662129996493295872 -1662129996538296832 -1662129996580297728 -1662129996622298624 -1662129996667299584 -1662129996712300544 -1662129996754301440 -1662129996796302336 -1662129996838303232 -1662129996880304128 -1662129996928305152 -1662129996970306048 -1662129997009306880 -1662129997054307840 -1662129997102308864 -1662129997147309824 -1662129997192310784 -1662129997234311680 -1662129997279312640 -1662129997321313536 -1662129997363314432 -1662129997405315328 -1662129997447316224 -1662129997489317120 -1662129997531318016 -1662129997573318912 -1662129997615319808 -1662129997657320704 -1662129997702321664 -1662129997741322496 -1662129997783323392 -1662129997828324352 -1662129997870325248 -1662129997912326144 -1662129997954327040 -1662129997999328000 -1662129998050329088 -1662129998098330112 -1662129998140331008 -1662129998188332032 -1662129998230332928 -1662129998275333888 -1662129998320334848 -1662129998365335808 -1662129998407336704 -1662129998446337536 -1662129998491338496 -1662129998542339584 -1662129998584340480 -1662129998626341376 -1662129998668342272 -1662129998713343232 -1662129998764344320 -1662129998806345216 -1662129998845346048 -1662129998887346944 -1662129998926347776 -1662129998968348672 -1662129999010349568 -1662129999052350464 -1662129999094351360 -1662129999139352320 -1662129999181353216 -1662129999226354176 -1662129999274355200 -1662129999316356096 -1662129999358356992 -1662129999406358016 -1662129999448358912 -1662129999496359936 -1662129999538360832 -1662129999577361664 -1662129999616362496 -1662129999658363392 -1662129999697364224 -1662129999739365120 -1662129999778365952 -1662129999817366784 -1662129999874368000 -1662129999916368896 -1662129999958369792 -1662130000012370944 -1662130000057371904 -1662130000099372800 -1662130000147373824 -1662130000189374720 -1662130000240375808 -1662130000282376704 -1662130000327377664 -1662130000375378688 -1662130000420379648 -1662130000462380544 -1662130000504381440 -1662130000546382336 -1662130000588383232 -1662130000630384128 -1662130000672385024 -1662130000714385920 -1662130000762386944 -1662130000807387904 -1662130000855388928 -1662130000903389952 -1662130000948390912 -1662130000987391744 -1662130001029392640 -1662130001071393536 -1662130001113394432 -1662130001161395456 -1662130001203396352 -1662130001245397248 -1662130001299398400 -1662130001341399296 -1662130001389400320 -1662130001428401152 -1662130001479402240 -1662130001524403200 -1662130001572404224 -1662130001620405248 -1662130001662406144 -1662130001704407040 -1662130001746407936 -1662130001788408832 -1662130001830409728 -1662130001872410624 -1662130001911411456 -1662130001953412352 -1662130001995413248 -1662130002037414144 -1662130002079415040 -1662130002124416000 -1662130002169416960 -1662130002214417920 -1662130002256418816 -1662130002301419776 -1662130002349420800 -1662130002394421760 -1662130002436422656 -1662130002481423616 -1662130002523424512 -1662130002568425472 -1662130002610426368 -1662130002652427264 -1662130002697428224 -1662130002739429120 -1662130002781430016 -1662130002826430976 -1662130002874432000 -1662130002916432896 -1662130002955433728 -1662130003000434688 -1662130003039435520 -1662130003081436416 -1662130003126437376 -1662130003171438336 -1662130003213439232 -1662130003255440128 -1662130003297441024 -1662130003339441920 -1662130003381442816 -1662130003423443712 -1662130003465444608 -1662130003507445504 -1662130003549446400 -1662130003591447296 -1662130003639448320 -1662130003681449216 -1662130003723450112 -1662130003768451072 -1662130003813452032 -1662130003855452928 -1662130003900453888 -1662130003948454912 -1662130003993455872 -1662130004035456768 -1662130004077457664 -1662130004122458624 -1662130004164459520 -1662130004209460480 -1662130004257461504 -1662130004302462464 -1662130004344463360 -1662130004398464512 -1662130004437465344 -1662130004485466368 -1662130004530467328 -1662130004578468352 -1662130004626469376 -1662130004665470208 -1662130004710471168 -1662130004749472000 -1662130004791472896 -1662130004833473792 -1662130004875474688 -1662130004917475584 -1662130004959476480 -1662130005013477632 -1662130005058478592 -1662130005103479552 -1662130005145480448 -1662130005184481280 -1662130005223482112 -1662130005265483008 -1662130005319484160 -1662130005361485056 -1662130005406486016 -1662130005448486912 -1662130005496487936 -1662130005538488832 -1662130005580489728 -1662130005628490752 -1662130005679491840 -1662130005721492736 -1662130005763493632 -1662130005817494784 -1662130005859495680 -1662130005901496576 -1662130005952497664 -1662130005991498496 -1662130006030499328 -1662130006075500288 -1662130006126501376 -1662130006171502336 -1662130006213503232 -1662130006261504256 -1662130006303505152 -1662130006342505984 -1662130006390507008 -1662130006432507904 -1662130006480508928 -1662130006522509824 -1662130006573510912 -1662130006615511808 -1662130006660512768 -1662130006702513664 -1662130006744514560 -1662130006786515456 -1662130006828516352 -1662130006867517184 -1662130006912518144 -1662130006960519168 -1662130006999520000 -1662130007041520896 -1662130007083521792 -1662130007128522752 -1662130007179523840 -1662130007227524864 -1662130007272525824 -1662130007317526784 -1662130007356527616 -1662130007398528512 -1662130007440529408 -1662130007485530368 -1662130007527531264 -1662130007572532224 -1662130007614533120 -1662130007665534208 -1662130007707535104 -1662130007749536000 -1662130007800537088 -1662130007848538112 -1662130007893539072 -1662130007938540032 -1662130007977540864 -1662130008022541824 -1662130008064542720 -1662130008115543808 -1662130008160544768 -1662130008208545792 -1662130008253546752 -1662130008295547648 -1662130008340548608 -1662130008385549568 -1662130008424550400 -1662130008466551296 -1662130008508552192 -1662130008547553024 -1662130008589553920 -1662130008634554880 -1662130008676555776 -1662130008724556800 -1662130008763557632 -1662130008805558528 -1662130008847559424 -1662130008895560448 -1662130008937561344 -1662130008982562304 -1662130009024563200 -1662130009063564032 -1662130009111565056 -1662130009153565952 -1662130009198566912 -1662130009240567808 -1662130009282568704 -1662130009327569664 -1662130009375570688 -1662130009417571584 -1662130009468572672 -1662130009519573760 -1662130009561574656 -1662130009603575552 -1662130009645576448 -1662130009687577344 -1662130009732578304 -1662130009774579200 -1662130009816580096 -1662130009864581120 -1662130009912582144 -1662130009954583040 -1662130009996583936 -1662130010038584832 -1662130010080585728 -1662130010128586752 -1662130010170587648 -1662130010209588480 -1662130010248589312 -1662130010290590208 -1662130010332591104 -1662130010386592256 -1662130010434593280 -1662130010476594176 -1662130010521595136 -1662130010560595968 -1662130010602596864 -1662130010650597888 -1662130010695598848 -1662130010737599744 -1662130010788600832 -1662130010830601728 -1662130010875602688 -1662130010920603648 -1662130010968604672 -1662130011013605632 -1662130011058606592 -1662130011100607488 -1662130011142608384 -1662130011190609408 -1662130011229610240 -1662130011286611456 -1662130011331612416 -1662130011373613312 -1662130011415614208 -1662130011463615232 -1662130011508616192 -1662130011550617088 -1662130011592617984 -1662130011637618944 -1662130011679619840 -1662130011724620800 -1662130011766621696 -1662130011811622656 -1662130011856623616 -1662130011904624640 -1662130011946625536 -1662130011988626432 -1662130012030627328 -1662130012072628224 -1662130012114629120 -1662130012156630016 -1662130012198630912 -1662130012237631744 -1662130012279632640 -1662130012321633536 -1662130012369634560 -1662130012414635520 -1662130012456636416 -1662130012513637632 -1662130012555638528 -1662130012606639616 -1662130012648640512 -1662130012690641408 -1662130012732642304 -1662130012777643264 -1662130012819644160 -1662130012867645184 -1662130012912646144 -1662130012954647040 -1662130013002648064 -1662130013053649152 -1662130013095650048 -1662130013140651008 -1662130013185651968 -1662130013230652928 -1662130013275653888 -1662130013317654784 -1662130013365655808 -1662130013407656704 -1662130013455657728 -1662130013494658560 -1662130013542659584 -1662130013584660480 -1662130013626661376 -1662130013668662272 -1662130013713663232 -1662130013767664384 -1662130013812665344 -1662130013851666176 -1662130013902667264 -1662130013941668096 -1662130013983668992 -1662130014028669952 -1662130014070670848 -1662130014112671744 -1662130014154672640 -1662130014208673792 -1662130014259674880 -1662130014301675776 -1662130014352676864 -1662130014400677888 -1662130014442678784 -1662130014484679680 -1662130014523680512 -1662130014565681408 -1662130014610682368 -1662130014652683264 -1662130014700684288 -1662130014742685184 -1662130014787686144 -1662130014832687104 -1662130014874688000 -1662130014919688960 -1662130014976690176 -1662130015024691200 -1662130015072692224 -1662130015114693120 -1662130015156694016 -1662130015201694976 -1662130015240695808 -1662130015279696640 -1662130015321697536 -1662130015369698560 -1662130015420699648 -1662130015462700544 -1662130015504701440 -1662130015552702464 -1662130015594703360 -1662130015636704256 -1662130015678705152 -1662130015720706048 -1662130015768707072 -1662130015819708160 -1662130015861709056 -1662130015903709952 -1662130015945710848 -1662130015996711936 -1662130016038712832 -1662130016080713728 -1662130016128714752 -1662130016179715840 -1662130016221716736 -1662130016263717632 -1662130016308718592 -1662130016362719744 -1662130016401720576 -1662130016443721472 -1662130016482722304 -1662130016527723264 -1662130016569724160 -1662130016611725056 -1662130016668726272 -1662130016710727168 -1662130016761728256 -1662130016812729344 -1662130016854730240 -1662130016896731136 -1662130016938732032 -1662130016977732864 -1662130017022733824 -1662130017061734656 -1662130017103735552 -1662130017154736640 -1662130017202737664 -1662130017247738624 -1662130017289739520 -1662130017334740480 -1662130017379741440 -1662130017421742336 -1662130017469743360 -1662130017517744384 -1662130017559745280 -1662130017601746176 -1662130017649747200 -1662130017691748096 -1662130017733748992 -1662130017781750016 -1662130017826750976 -1662130017877752064 -1662130017922753024 -1662130017964753920 -1662130018006754816 -1662130018045755648 -1662130018093756672 -1662130018147757824 -1662130018189758720 -1662130018228759552 -1662130018273760512 -1662130018318761472 -1662130018357762304 -1662130018402763264 -1662130018447764224 -1662130018489765120 -1662130018528765952 -1662130018573766912 -1662130018618767872 -1662130018660768768 -1662130018702769664 -1662130018744770560 -1662130018795771648 -1662130018837772544 -1662130018888773632 -1662130018936774656 -1662130018978775552 -1662130019032776704 -1662130019077777664 -1662130019116778496 -1662130019161779456 -1662130019209780480 -1662130019248781312 -1662130019287782144 -1662130019335783168 -1662130019383784192 -1662130019425785088 -1662130019473786112 -1662130019515787008 -1662130019557787904 -1662130019596788736 -1662130019644789760 -1662130019683790592 -1662130019728791552 -1662130019776792576 -1662130019821793536 -1662130019863794432 -1662130019905795328 -1662130019950796288 -1662130019992797184 -1662130020055798528 -1662130020097799424 -1662130020145800448 -1662130020190801408 -1662130020232802304 -1662130020274803200 -1662130020316804096 -1662130020364805120 -1662130020412806144 -1662130020454807040 -1662130020505808128 -1662130020550809088 -1662130020592809984 -1662130020634810880 -1662130020682811904 -1662130020724812800 -1662130020769813760 -1662130020811814656 -1662130020859815680 -1662130020904816640 -1662130020946817536 -1662130021000818688 -1662130021045819648 -1662130021093820672 -1662130021138821632 -1662130021180822528 -1662130021222823424 -1662130021267824384 -1662130021315825408 -1662130021357826304 -1662130021399827200 -1662130021441828096 -1662130021483828992 -1662130021522829824 -1662130021570830848 -1662130021615831808 -1662130021666832896 -1662130021720834048 -1662130021768835072 -1662130021822836224 -1662130021873837312 -1662130021921838336 -1662130021969839360 -1662130022014840320 -1662130022059841280 -1662130022104842240 -1662130022143843072 -1662130022188844032 -1662130022230844928 -1662130022278845952 -1662130022323846912 -1662130022374848000 -1662130022416848896 -1662130022467849984 -1662130022512850944 -1662130022554851840 -1662130022599852800 -1662130022638853632 -1662130022680854528 -1662130022722855424 -1662130022764856320 -1662130022812857344 -1662130022854858240 -1662130022896859136 -1662130022947860224 -1662130022989861120 -1662130023034862080 -1662130023076862976 -1662130023112863744 -1662130023157864704 -1662130023199865600 -1662130023244866560 -1662130023292867584 -1662130023334868480 -1662130023376869376 -1662130023418870272 -1662130023463871232 -1662130023505872128 -1662130023556873216 -1662130023607874304 -1662130023655875328 -1662130023697876224 -1662130023739877120 -1662130023787878144 -1662130023829879040 -1662130023877880064 -1662130023925881088 -1662130023970882048 -1662130024012882944 -1662130024054883840 -1662130024096884736 -1662130024150885888 -1662130024195886848 -1662130024240887808 -1662130024279888640 -1662130024324889600 -1662130024369890560 -1662130024414891520 -1662130024456892416 -1662130024501893376 -1662130024546894336 -1662130024597895424 -1662130024645896448 -1662130024690897408 -1662130024732898304 -1662130024774899200 -1662130024816900096 -1662130024858900992 -1662130024903901952 -1662130024948902912 -1662130024999904000 -1662130025041904896 -1662130025080905728 -1662130025128906752 -1662130025170907648 -1662130025224908800 -1662130025263909632 -1662130025302910464 -1662130025353911552 -1662130025398912512 -1662130025443913472 -1662130025485914368 -1662130025527915264 -1662130025569916160 -1662130025611917056 -1662130025647917824 -1662130025689918720 -1662130025734919680 -1662130025776920576 -1662130025824921600 -1662130025866922496 -1662130025908923392 -1662130025947924224 -1662130025989925120 -1662130026031926016 -1662130026076926976 -1662130026118927872 -1662130026163928832 -1662130026202929664 -1662130026244930560 -1662130026289931520 -1662130026337932544 -1662130026382933504 -1662130026424934400 -1662130026466935296 -1662130026508936192 -1662130026553937152 -1662130026595938048 -1662130026640939008 -1662130026682939904 -1662130026721940736 -1662130026763941632 -1662130026811942656 -1662130026856943616 -1662130026904944640 -1662130026955945728 -1662130026994946560 -1662130027039947520 -1662130027081948416 -1662130027117949184 -1662130027165950208 -1662130027207951104 -1662130027249952000 -1662130027297953024 -1662130027351954176 -1662130027396955136 -1662130027444956160 -1662130027489957120 -1662130027537958144 -1662130027579959040 -1662130027621959936 -1662130027660960768 -1662130027711961856 -1662130027753962752 -1662130027795963648 -1662130027837964544 -1662130027885965568 -1662130027930966528 -1662130027975967488 -1662130028026968576 -1662130028068969472 -1662130028113970432 -1662130028161971456 -1662130028209972480 -1662130028257973504 -1662130028296974336 -1662130028341975296 -1662130028383976192 -1662130028428977152 -1662130028473978112 -1662130028521979136 -1662130028563980032 -1662130028605980928 -1662130028647981824 -1662130028689982720 -1662130028731983616 -1662130028779984640 -1662130028815985408 -1662130028863986432 -1662130028908987392 -1662130028956988416 -1662130028998989312 -1662130029043990272 -1662130029085991168 -1662130029136992256 -1662130029178993152 -1662130029226994176 -1662130029271995136 -1662130029307995904 -1662130029352996864 -1662130029388997632 -1662130029433998592 -1662130029475999488 -1662130029518000384 -1662130029560001280 -1662130029605002240 -1662130029650003200 -1662130029692004096 -1662130029740005120 -1662130029782006016 -1662130029827006976 -1662130029872007936 -1662130029914008832 -1662130029959009792 -1662130030004010752 -1662130030058011904 -1662130030100012800 -1662130030145013760 -1662130030193014784 -1662130030238015744 -1662130030277016576 -1662130030319017472 -1662130030364018432 -1662130030406019328 -1662130030448020224 -1662130030496021248 -1662130030538022144 -1662130030583023104 -1662130030628024064 -1662130030676025088 -1662130030721026048 -1662130030763026944 -1662130030811027968 -1662130030856028928 -1662130030904029952 -1662130030952030976 -1662130030997031936 -1662130031045032960 -1662130031087033856 -1662130031126034688 -1662130031171035648 -1662130031213036544 -1662130031261037568 -1662130031306038528 -1662130031354039552 -1662130031396040448 -1662130031441041408 -1662130031480042240 -1662130031522043136 -1662130031567044096 -1662130031615045120 -1662130031660046080 -1662130031702046976 -1662130031744047872 -1662130031786048768 -1662130031831049728 -1662130031879050752 -1662130031921051648 -1662130031972052736 -1662130032020053760 -1662130032059054592 -1662130032110055680 -1662130032152056576 -1662130032191057408 -1662130032233058304 -1662130032278059264 -1662130032326060288 -1662130032368061184 -1662130032410062080 -1662130032452062976 -1662130032491063808 -1662130032530064640 -1662130032575065600 -1662130032617066496 -1662130032659067392 -1662130032701068288 -1662130032743069184 -1662130032782070016 -1662130032827070976 -1662130032869071872 -1662130032917072896 -1662130032959073792 -1662130033004074752 -1662130033046075648 -1662130033088076544 -1662130033133077504 -1662130033181078528 -1662130033226079488 -1662130033271080448 -1662130033319081472 -1662130033364082432 -1662130033406083328 -1662130033445084160 -1662130033493085184 -1662130033535086080 -1662130033577086976 -1662130033619087872 -1662130033661088768 -1662130033709089792 -1662130033751090688 -1662130033796091648 -1662130033838092544 -1662130033889093632 -1662130033931094528 -1662130033976095488 -1662130034018096384 -1662130034066097408 -1662130034108098304 -1662130034150099200 -1662130034195100160 -1662130034240101120 -1662130034285102080 -1662130034324102912 -1662130034366103808 -1662130034411104768 -1662130034453105664 -1662130034501106688 -1662130034543107584 -1662130034579108352 -1662130034621109248 -1662130034663110144 -1662130034708111104 -1662130034756112128 -1662130034798113024 -1662130034846114048 -1662130034888114944 -1662130034930115840 -1662130034969116672 -1662130035017117696 -1662130035059118592 -1662130035104119552 -1662130035149120512 -1662130035194121472 -1662130035236122368 -1662130035278123264 -1662130035323124224 -1662130035362125056 -1662130035404125952 -1662130035452126976 -1662130035500128000 -1662130035551129088 -1662130035593129984 -1662130035638130944 -1662130035686131968 -1662130035734132992 -1662130035776133888 -1662130035821134848 -1662130035863135744 -1662130035911136768 -1662130035953137664 -1662130036004138752 -1662130036046139648 -1662130036094140672 -1662130036139141632 -1662130036190142720 -1662130036235143680 -1662130036277144576 -1662130036328145664 -1662130036370146560 -1662130036415147520 -1662130036463148544 -1662130036502149376 -1662130036547150336 -1662130036586151168 -1662130036628152064 -1662130036676153088 -1662130036718153984 -1662130036760154880 -1662130036802155776 -1662130036844156672 -1662130036889157632 -1662130036931158528 -1662130036982159616 -1662130037021160448 -1662130037063161344 -1662130037105162240 -1662130037141163008 -1662130037183163904 -1662130037228164864 -1662130037270165760 -1662130037312166656 -1662130037354167552 -1662130037405168640 -1662130037450169600 -1662130037495170560 -1662130037537171456 -1662130037576172288 -1662130037627173376 -1662130037672174336 -1662130037711175168 -1662130037753176064 -1662130037795176960 -1662130037837177856 -1662130037885178880 -1662130037930179840 -1662130037972180736 -1662130038020181760 -1662130038059182592 -1662130038110183680 -1662130038161184768 -1662130038203185664 -1662130038251186688 -1662130038296187648 -1662130038341188608 -1662130038392189696 -1662130038434190592 -1662130038476191488 -1662130038524192512 -1662130038566193408 -1662130038614194432 -1662130038665195520 -1662130038713196544 -1662130038758197504 -1662130038800198400 -1662130038839199232 -1662130038881200128 -1662130038935201280 -1662130038980202240 -1662130039022203136 -1662130039064204032 -1662130039109204992 -1662130039154205952 -1662130039196206848 -1662130039241207808 -1662130039286208768 -1662130039325209600 -1662130039364210432 -1662130039412211456 -1662130039457212416 -1662130039499213312 -1662130039544214272 -1662130039592215296 -1662130039637216256 -1662130039679217152 -1662130039724218112 -1662130039769219072 -1662130039811219968 -1662130039853220864 -1662130039901221888 -1662130039946222848 -1662130039988223744 -1662130040027224576 -1662130040078225664 -1662130040132226816 -1662130040174227712 -1662130040213228544 -1662130040255229440 -1662130040294230272 -1662130040336231168 -1662130040375232000 -1662130040420232960 -1662130040468233984 -1662130040516235008 -1662130040558235904 -1662130040603236864 -1662130040648237824 -1662130040693238784 -1662130040738239744 -1662130040789240832 -1662130040828241664 -1662130040870242560 -1662130040912243456 -1662130040954244352 -1662130040999245312 -1662130041044246272 -1662130041089247232 -1662130041128248064 -1662130041170248960 -1662130041212249856 -1662130041254250752 -1662130041299251712 -1662130041341252608 -1662130041383253504 -1662130041428254464 -1662130041467255296 -1662130041518256384 -1662130041563257344 -1662130041608258304 -1662130041653259264 -1662130041698260224 -1662130041749261312 -1662130041785262080 -1662130041830263040 -1662130041872263936 -1662130041914264832 -1662130041971266048 -1662130042013266944 -1662130042061267968 -1662130042103268864 -1662130042145269760 -1662130042187270656 -1662130042238271744 -1662130042283272704 -1662130042334273792 -1662130042376274688 -1662130042418275584 -1662130042460276480 -1662130042517277696 -1662130042559278592 -1662130042601279488 -1662130042643280384 -1662130042691281408 -1662130042733282304 -1662130042775283200 -1662130042817284096 -1662130042859284992 -1662130042907286016 -1662130042955287040 -1662130043000288000 -1662130043054289152 -1662130043096290048 -1662130043135290880 -1662130043177291776 -1662130043228292864 -1662130043270293760 -1662130043312294656 -1662130043363295744 -1662130043405296640 -1662130043447297536 -1662130043501298688 -1662130043549299712 -1662130043594300672 -1662130043633301504 -1662130043678302464 -1662130043720303360 -1662130043759304192 -1662130043813305344 -1662130043858306304 -1662130043900307200 -1662130043945308160 -1662130043984308992 -1662130044026309888 -1662130044065310720 -1662130044110311680 -1662130044152312576 -1662130044194313472 -1662130044257314816 -1662130044293315584 -1662130044341316608 -1662130044383317504 -1662130044428318464 -1662130044470319360 -1662130044512320256 -1662130044557321216 -1662130044599322112 -1662130044647323136 -1662130044689324032 -1662130044734324992 -1662130044785326080 -1662130044827326976 -1662130044869327872 -1662130044911328768 -1662130044950329600 -1662130045001330688 -1662130045043331584 -1662130045091332608 -1662130045133333504 -1662130045175334400 -1662130045226335488 -1662130045268336384 -1662130045313337344 -1662130045355338240 -1662130045400339200 -1662130045448340224 -1662130045493341184 -1662130045544342272 -1662130045586343168 -1662130045628344064 -1662130045673345024 -1662130045715345920 -1662130045757346816 -1662130045799347712 -1662130045844348672 -1662130045886349568 -1662130045931350528 -1662130045973351424 -1662130046012352256 -1662130046054353152 -1662130046099354112 -1662130046138354944 -1662130046177355776 -1662130046219356672 -1662130046258357504 -1662130046300358400 -1662130046351359488 -1662130046396360448 -1662130046438361344 -1662130046477362176 -1662130046522363136 -1662130046561363968 -1662130046600364800 -1662130046642365696 -1662130046684366592 -1662130046726367488 -1662130046765368320 -1662130046807369216 -1662130046852370176 -1662130046900371200 -1662130046948372224 -1662130046990373120 -1662130047041374208 -1662130047086375168 -1662130047128376064 -1662130047170376960 -1662130047227378176 -1662130047269379072 -1662130047311379968 -1662130047356380928 -1662130047398381824 -1662130047443382784 -1662130047485383680 -1662130047530384640 -1662130047578385664 -1662130047626386688 -1662130047674387712 -1662130047725388800 -1662130047776389888 -1662130047815390720 -1662130047854391552 -1662130047896392448 -1662130047947393536 -1662130047995394560 -1662130048040395520 -1662130048088396544 -1662130048133397504 -1662130048181398528 -1662130048226399488 -1662130048274400512 -1662130048316401408 -1662130048364402432 -1662130048412403456 -1662130048460404480 -1662130048502405376 -1662130048553406464 -1662130048595407360 -1662130048643408384 -1662130048685409280 -1662130048736410368 -1662130048778411264 -1662130048829412352 -1662130048871413248 -1662130048916414208 -1662130048955415040 -1662130049003416064 -1662130049045416960 -1662130049090417920 -1662130049132418816 -1662130049180419840 -1662130049225420800 -1662130049270421760 -1662130049312422656 -1662130049375424000 -1662130049417424896 -1662130049462425856 -1662130049507426816 -1662130049552427776 -1662130049594428672 -1662130049633429504 -1662130049675430400 -1662130049726431488 -1662130049768432384 -1662130049810433280 -1662130049852434176 -1662130049897435136 -1662130049936435968 -1662130049984436992 -1662130050026437888 -1662130050068438784 -1662130050110439680 -1662130050155440640 -1662130050200441600 -1662130050245442560 -1662130050287443456 -1662130050329444352 -1662130050368445184 -1662130050410446080 -1662130050452446976 -1662130050500448000 -1662130050545448960 -1662130050587449856 -1662130050629450752 -1662130050674451712 -1662130050716452608 -1662130050761453568 -1662130050800454400 -1662130050845455360 -1662130050896456448 -1662130050941457408 -1662130050986458368 -1662130051031459328 -1662130051076460288 -1662130051118461184 -1662130051163462144 -1662130051211463168 -1662130051253464064 -1662130051298465024 -1662130051340465920 -1662130051385466880 -1662130051430467840 -1662130051478468864 -1662130051526469888 -1662130051571470848 -1662130051619471872 -1662130051664472832 -1662130051709473792 -1662130051751474688 -1662130051796475648 -1662130051838476544 -1662130051883477504 -1662130051925478400 -1662130051967479296 -1662130052006480128 -1662130052048481024 -1662130052090481920 -1662130052132482816 -1662130052180483840 -1662130052231484928 -1662130052273485824 -1662130052321486848 -1662130052363487744 -1662130052408488704 -1662130052453489664 -1662130052498490624 -1662130052546491648 -1662130052588492544 -1662130052639493632 -1662130052687494656 -1662130052729495552 -1662130052771496448 -1662130052816497408 -1662130052867498496 -1662130052912499456 -1662130052957500416 -1662130053008501504 -1662130053062502656 -1662130053107503616 -1662130053155504640 -1662130053197505536 -1662130053239506432 -1662130053281507328 -1662130053320508160 -1662130053362509056 -1662130053404509952 -1662130053446510848 -1662130053488511744 -1662130053536512768 -1662130053575513600 -1662130053629514752 -1662130053668515584 -1662130053713516544 -1662130053755517440 -1662130053800518400 -1662130053851519488 -1662130053896520448 -1662130053941521408 -1662130053983522304 -1662130054028523264 -1662130054073524224 -1662130054118525184 -1662130054160526080 -1662130054208527104 -1662130054250528000 -1662130054298529024 -1662130054346530048 -1662130054385530880 -1662130054427531776 -1662130054472532736 -1662130054514533632 -1662130054556534528 -1662130054604535552 -1662130054646536448 -1662130054694537472 -1662130054748538624 -1662130054796539648 -1662130054838540544 -1662130054880541440 -1662130054928542464 -1662130054976543488 -1662130055018544384 -1662130055060545280 -1662130055105546240 -1662130055153547264 -1662130055201548288 -1662130055246549248 -1662130055294550272 -1662130055342551296 -1662130055387552256 -1662130055429553152 -1662130055471554048 -1662130055510554880 -1662130055552555776 -1662130055594556672 -1662130055636557568 -1662130055693558784 -1662130055735559680 -1662130055777560576 -1662130055819561472 -1662130055861562368 -1662130055906563328 -1662130055948564224 -1662130055987565056 -1662130056032566016 -1662130056077566976 -1662130056119567872 -1662130056161568768 -1662130056203569664 -1662130056251570688 -1662130056290571520 -1662130056338572544 -1662130056386573568 -1662130056431574528 -1662130056476575488 -1662130056518576384 -1662130056563577344 -1662130056611578368 -1662130056656579328 -1662130056701580288 -1662130056743581184 -1662130056785582080 -1662130056827582976 -1662130056869583872 -1662130056914584832 -1662130056965585920 -1662130057010586880 -1662130057058587904 -1662130057106588928 -1662130057151589888 -1662130057193590784 -1662130057244591872 -1662130057286592768 -1662130057328593664 -1662130057376594688 -1662130057421595648 -1662130057466596608 -1662130057514597632 -1662130057553598464 -1662130057598599424 -1662130057646600448 -1662130057688601344 -1662130057730602240 -1662130057775603200 -1662130057823604224 -1662130057868605184 -1662130057910606080 -1662130057955607040 -1662130057994607872 -1662130058039608832 -1662130058084609792 -1662130058132610816 -1662130058180611840 -1662130058228612864 -1662130058279613952 -1662130058321614848 -1662130058363615744 -1662130058405616640 -1662130058450617600 -1662130058492618496 -1662130058537619456 -1662130058579620352 -1662130058624621312 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_dark.txt b/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_dark.txt deleted file mode 100644 index 656025a687..0000000000 --- a/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_dark.txt +++ /dev/null @@ -1,2741 +0,0 @@ -1662063934494348032 -1662063934536348928 -1662063934587350016 -1662063934629350912 -1662063934671351808 -1662063934713352704 -1662063934758353664 -1662063934803354624 -1662063934848355584 -1662063934893356544 -1662063934938357504 -1662063934977358336 -1662063935022359296 -1662063935064360192 -1662063935103361024 -1662063935145361920 -1662063935187362816 -1662063935229363712 -1662063935268364544 -1662063935310365440 -1662063935352366336 -1662063935394367232 -1662063935436368128 -1662063935478369024 -1662063935535370240 -1662063935577371136 -1662063935619372032 -1662063935670373120 -1662063935712374016 -1662063935757374976 -1662063935799375872 -1662063935844376832 -1662063935886377728 -1662063935931378688 -1662063935973379584 -1662063936015380480 -1662063936057381376 -1662063936099382272 -1662063936141383168 -1662063936180384000 -1662063936222384896 -1662063936267385856 -1662063936312386816 -1662063936360387840 -1662063936405388800 -1662063936447389696 -1662063936489390592 -1662063936531391488 -1662063936573392384 -1662063936615393280 -1662063936657394176 -1662063936699395072 -1662063936744396032 -1662063936786396928 -1662063936828397824 -1662063936870398720 -1662063936909399552 -1662063936948400384 -1662063936990401280 -1662063937038402304 -1662063937089403392 -1662063937134404352 -1662063937182405376 -1662063937224406272 -1662063937269407232 -1662063937314408192 -1662063937356409088 -1662063937401410048 -1662063937449411072 -1662063937488411904 -1662063937539412992 -1662063937584413952 -1662063937638415104 -1662063937677415936 -1662063937719416832 -1662063937761417728 -1662063937803418624 -1662063937842419456 -1662063937887420416 -1662063937935421440 -1662063937977422336 -1662063938019423232 -1662063938061424128 -1662063938106425088 -1662063938148425984 -1662063938193426944 -1662063938238427904 -1662063938283428864 -1662063938325429760 -1662063938370430720 -1662063938412431616 -1662063938457432576 -1662063938499433472 -1662063938544434432 -1662063938586435328 -1662063938631436288 -1662063938676437248 -1662063938718438144 -1662063938760439040 -1662063938802439936 -1662063938850440960 -1662063938898441984 -1662063938943442944 -1662063938988443904 -1662063939036444928 -1662063939078445824 -1662063939126446848 -1662063939165447680 -1662063939210448640 -1662063939252449536 -1662063939300450560 -1662063939342451456 -1662063939387452416 -1662063939429453312 -1662063939471454208 -1662063939510455040 -1662063939552455936 -1662063939594456832 -1662063939639457792 -1662063939681458688 -1662063939723459584 -1662063939765460480 -1662063939807461376 -1662063939852462336 -1662063939894463232 -1662063939939464192 -1662063939981465088 -1662063940026466048 -1662063940068466944 -1662063940113467904 -1662063940158468864 -1662063940209469952 -1662063940257470976 -1662063940299471872 -1662063940341472768 -1662063940383473664 -1662063940422474496 -1662063940464475392 -1662063940506476288 -1662063940548477184 -1662063940590478080 -1662063940632478976 -1662063940674479872 -1662063940716480768 -1662063940767481856 -1662063940806482688 -1662063940851483648 -1662063940899484672 -1662063940941485568 -1662063940989486592 -1662063941034487552 -1662063941079488512 -1662063941124489472 -1662063941169490432 -1662063941214491392 -1662063941262492416 -1662063941304493312 -1662063941346494208 -1662063941391495168 -1662063941436496128 -1662063941475496960 -1662063941517497856 -1662063941562498816 -1662063941604499712 -1662063941646500608 -1662063941688501504 -1662063941736502528 -1662063941784503552 -1662063941832504576 -1662063941874505472 -1662063941922506496 -1662063941964507392 -1662063942009508352 -1662063942051509248 -1662063942093510144 -1662063942138511104 -1662063942180512000 -1662063942222512896 -1662063942267513856 -1662063942309514752 -1662063942351515648 -1662063942396516608 -1662063942447517696 -1662063942498518784 -1662063942543519744 -1662063942585520640 -1662063942630521600 -1662063942672522496 -1662063942714523392 -1662063942762524416 -1662063942807525376 -1662063942852526336 -1662063942897527296 -1662063942942528256 -1662063942984529152 -1662063943029530112 -1662063943074531072 -1662063943116531968 -1662063943167533056 -1662063943206533888 -1662063943248534784 -1662063943287535616 -1662063943329536512 -1662063943374537472 -1662063943416538368 -1662063943458539264 -1662063943503540224 -1662063943545541120 -1662063943584541952 -1662063943629542912 -1662063943671543808 -1662063943710544640 -1662063943752545536 -1662063943794546432 -1662063943836547328 -1662063943884548352 -1662063943935549440 -1662063943977550336 -1662063944019551232 -1662063944061552128 -1662063944103553024 -1662063944145553920 -1662063944184554752 -1662063944229555712 -1662063944277556736 -1662063944319557632 -1662063944361558528 -1662063944418559744 -1662063944463560704 -1662063944508561664 -1662063944553562624 -1662063944595563520 -1662063944640564480 -1662063944682565376 -1662063944733566464 -1662063944778567424 -1662063944823568384 -1662063944865569280 -1662063944910570240 -1662063944955571200 -1662063944997572096 -1662063945039572992 -1662063945081573888 -1662063945126574848 -1662063945171575808 -1662063945213576704 -1662063945255577600 -1662063945297578496 -1662063945339579392 -1662063945381580288 -1662063945420581120 -1662063945465582080 -1662063945507582976 -1662063945549583872 -1662063945588584704 -1662063945642585856 -1662063945690586880 -1662063945732587776 -1662063945780588800 -1662063945822589696 -1662063945867590656 -1662063945912591616 -1662063945954592512 -1662063945999593472 -1662063946041594368 -1662063946089595392 -1662063946131596288 -1662063946173597184 -1662063946215598080 -1662063946263599104 -1662063946302599936 -1662063946344600832 -1662063946392601856 -1662063946437602816 -1662063946479603712 -1662063946524604672 -1662063946566605568 -1662063946608606464 -1662063946650607360 -1662063946692608256 -1662063946731609088 -1662063946776610048 -1662063946818610944 -1662063946863611904 -1662063946908612864 -1662063946950613760 -1662063946992614656 -1662063947037615616 -1662063947076616448 -1662063947124617472 -1662063947163618304 -1662063947205619200 -1662063947247620096 -1662063947292621056 -1662063947337622016 -1662063947382622976 -1662063947430624000 -1662063947472624896 -1662063947517625856 -1662063947565626880 -1662063947604627712 -1662063947649628672 -1662063947694629632 -1662063947736630528 -1662063947787631616 -1662063947832632576 -1662063947871633408 -1662063947913634304 -1662063947955635200 -1662063947997636096 -1662063948045637120 -1662063948087638016 -1662063948129638912 -1662063948171639808 -1662063948213640704 -1662063948270641920 -1662063948309642752 -1662063948354643712 -1662063948402644736 -1662063948444645632 -1662063948486646528 -1662063948534647552 -1662063948576648448 -1662063948621649408 -1662063948663650304 -1662063948699651072 -1662063948741651968 -1662063948783652864 -1662063948831653888 -1662063948879654912 -1662063948924655872 -1662063948966656768 -1662063949008657664 -1662063949050658560 -1662063949092659456 -1662063949134660352 -1662063949176661248 -1662063949215662080 -1662063949263663104 -1662063949305664000 -1662063949347664896 -1662063949389665792 -1662063949431666688 -1662063949473667584 -1662063949518668544 -1662063949563669504 -1662063949602670336 -1662063949641671168 -1662063949686672128 -1662063949728673024 -1662063949770673920 -1662063949812674816 -1662063949854675712 -1662063949902676736 -1662063949941677568 -1662063949986678528 -1662063950031679488 -1662063950073680384 -1662063950112681216 -1662063950154682112 -1662063950199683072 -1662063950244684032 -1662063950289684992 -1662063950334685952 -1662063950382686976 -1662063950430688000 -1662063950472688896 -1662063950520689920 -1662063950562690816 -1662063950604691712 -1662063950646692608 -1662063950688693504 -1662063950733694464 -1662063950778695424 -1662063950823696384 -1662063950865697280 -1662063950907698176 -1662063950949699072 -1662063951003700224 -1662063951042701056 -1662063951084701952 -1662063951135703040 -1662063951177703936 -1662063951222704896 -1662063951267705856 -1662063951309706752 -1662063951357707776 -1662063951402708736 -1662063951447709696 -1662063951495710720 -1662063951537711616 -1662063951585712640 -1662063951627713536 -1662063951672714496 -1662063951717715456 -1662063951759716352 -1662063951807717376 -1662063951849718272 -1662063951891719168 -1662063951933720064 -1662063951975720960 -1662063952017721856 -1662063952062722816 -1662063952104723712 -1662063952149724672 -1662063952194725632 -1662063952242726656 -1662063952287727616 -1662063952335728640 -1662063952380729600 -1662063952425730560 -1662063952470731520 -1662063952512732416 -1662063952551733248 -1662063952590734080 -1662063952635735040 -1662063952680736000 -1662063952722736896 -1662063952767737856 -1662063952809738752 -1662063952851739648 -1662063952890740480 -1662063952932741376 -1662063952980742400 -1662063953022743296 -1662063953067744256 -1662063953112745216 -1662063953154746112 -1662063953199747072 -1662063953241747968 -1662063953280748800 -1662063953325749760 -1662063953370750720 -1662063953415751680 -1662063953457752576 -1662063953502753536 -1662063953544754432 -1662063953586755328 -1662063953628756224 -1662063953676757248 -1662063953718758144 -1662063953763759104 -1662063953808760064 -1662063953850760960 -1662063953892761856 -1662063953934762752 -1662063953979763712 -1662063954024764672 -1662063954066765568 -1662063954108766464 -1662063954150767360 -1662063954192768256 -1662063954240769280 -1662063954282770176 -1662063954330771200 -1662063954375772160 -1662063954414772992 -1662063954456773888 -1662063954501774848 -1662063954543775744 -1662063954588776704 -1662063954633777664 -1662063954678778624 -1662063954720779520 -1662063954765780480 -1662063954807781376 -1662063954849782272 -1662063954891783168 -1662063954933784064 -1662063954975784960 -1662063955017785856 -1662063955065786880 -1662063955113787904 -1662063955155788800 -1662063955197789696 -1662063955242790656 -1662063955284791552 -1662063955329792512 -1662063955374793472 -1662063955425794560 -1662063955464795392 -1662063955509796352 -1662063955548797184 -1662063955590798080 -1662063955629798912 -1662063955671799808 -1662063955713800704 -1662063955755801600 -1662063955800802560 -1662063955854803712 -1662063955896804608 -1662063955938805504 -1662063955986806528 -1662063956031807488 -1662063956079808512 -1662063956121809408 -1662063956163810304 -1662063956205811200 -1662063956247812096 -1662063956289812992 -1662063956331813888 -1662063956376814848 -1662063956415815680 -1662063956457816576 -1662063956502817536 -1662063956547818496 -1662063956589819392 -1662063956637820416 -1662063956679821312 -1662063956718822144 -1662063956766823168 -1662063956814824192 -1662063956865825280 -1662063956910826240 -1662063956952827136 -1662063956997828096 -1662063957039828992 -1662063957084829952 -1662063957126830848 -1662063957171831808 -1662063957216832768 -1662063957261833728 -1662063957303834624 -1662063957348835584 -1662063957387836416 -1662063957429837312 -1662063957474838272 -1662063957522839296 -1662063957564840192 -1662063957603841024 -1662063957645841920 -1662063957690842880 -1662063957732843776 -1662063957777844736 -1662063957819845632 -1662063957864846592 -1662063957912847616 -1662063957954848512 -1662063957996849408 -1662063958041850368 -1662063958083851264 -1662063958131852288 -1662063958176853248 -1662063958224854272 -1662063958269855232 -1662063958320856320 -1662063958365857280 -1662063958407858176 -1662063958452859136 -1662063958494860032 -1662063958536860928 -1662063958584861952 -1662063958626862848 -1662063958668863744 -1662063958713864704 -1662063958752865536 -1662063958803866624 -1662063958848867584 -1662063958893868544 -1662063958941869568 -1662063958992870656 -1662063959034871552 -1662063959079872512 -1662063959121873408 -1662063959166874368 -1662063959208875264 -1662063959253876224 -1662063959301877248 -1662063959355878400 -1662063959397879296 -1662063959436880128 -1662063959478881024 -1662063959529882112 -1662063959574883072 -1662063959616883968 -1662063959658884864 -1662063959700885760 -1662063959742886656 -1662063959784887552 -1662063959829888512 -1662063959871889408 -1662063959913890304 -1662063959955891200 -1662063959997892096 -1662063960039892992 -1662063960084893952 -1662063960129894912 -1662063960174895872 -1662063960216896768 -1662063960258897664 -1662063960300898560 -1662063960342899456 -1662063960387900416 -1662063960429901312 -1662063960474902272 -1662063960525903360 -1662063960567904256 -1662063960606905088 -1662063960648905984 -1662063960687906816 -1662063960732907776 -1662063960774908672 -1662063960816909568 -1662063960861910528 -1662063960906911488 -1662063960948912384 -1662063960990913280 -1662063961032914176 -1662063961074915072 -1662063961119916032 -1662063961164916992 -1662063961209917952 -1662063961254918912 -1662063961299919872 -1662063961344920832 -1662063961389921792 -1662063961428922624 -1662063961470923520 -1662063961515924480 -1662063961563925504 -1662063961608926464 -1662063961650927360 -1662063961689928192 -1662063961728929024 -1662063961776930048 -1662063961821931008 -1662063961863931904 -1662063961908932864 -1662063961956933888 -1662063961998934784 -1662063962040935680 -1662063962088936704 -1662063962136937728 -1662063962178938624 -1662063962223939584 -1662063962271940608 -1662063962316941568 -1662063962367942656 -1662063962409943552 -1662063962451944448 -1662063962496945408 -1662063962547946496 -1662063962592947456 -1662063962640948480 -1662063962682949376 -1662063962724950272 -1662063962769951232 -1662063962814952192 -1662063962871953408 -1662063962913954304 -1662063962958955264 -1662063963006956288 -1662063963045957120 -1662063963090958080 -1662063963132958976 -1662063963183960064 -1662063963225960960 -1662063963267961856 -1662063963309962752 -1662063963354963712 -1662063963396964608 -1662063963435965440 -1662063963483966464 -1662063963531967488 -1662063963579968512 -1662063963621969408 -1662063963663970304 -1662063963711971328 -1662063963759972352 -1662063963801973248 -1662063963840974080 -1662063963885975040 -1662063963927975936 -1662063963972976896 -1662063964017977856 -1662063964059978752 -1662063964101979648 -1662063964143980544 -1662063964185981440 -1662063964227982336 -1662063964275983360 -1662063964320984320 -1662063964359985152 -1662063964401986048 -1662063964440986880 -1662063964479987712 -1662063964524988672 -1662063964566989568 -1662063964608990464 -1662063964653991424 -1662063964701992448 -1662063964749993472 -1662063964794994432 -1662063964836995328 -1662063964878996224 -1662063964923997184 -1662063964968998144 -1662063965010999040 -1662063965052999936 -1662063965098000896 -1662063965155002112 -1662063965197003008 -1662063965245004032 -1662063965287004928 -1662063965332005888 -1662063965377006848 -1662063965422007808 -1662063965461008640 -1662063965506009600 -1662063965545010432 -1662063965593011456 -1662063965635012352 -1662063965677013248 -1662063965719014144 -1662063965761015040 -1662063965809016064 -1662063965851016960 -1662063965893017856 -1662063965935018752 -1662063965980019712 -1662063966028020736 -1662063966073021696 -1662063966115022592 -1662063966160023552 -1662063966205024512 -1662063966250025472 -1662063966295026432 -1662063966337027328 -1662063966382028288 -1662063966427029248 -1662063966472030208 -1662063966514031104 -1662063966559032064 -1662063966601032960 -1662063966646033920 -1662063966688034816 -1662063966736035840 -1662063966781036800 -1662063966823037696 -1662063966868038656 -1662063966919039744 -1662063966964040704 -1662063967009041664 -1662063967054042624 -1662063967096043520 -1662063967138044416 -1662063967183045376 -1662063967225046272 -1662063967267047168 -1662063967309048064 -1662063967351048960 -1662063967393049856 -1662063967435050752 -1662063967477051648 -1662063967525052672 -1662063967570053632 -1662063967612054528 -1662063967654055424 -1662063967702056448 -1662063967741057280 -1662063967786058240 -1662063967828059136 -1662063967867059968 -1662063967909060864 -1662063967954061824 -1662063968002062848 -1662063968047063808 -1662063968089064704 -1662063968137065728 -1662063968179066624 -1662063968230067712 -1662063968275068672 -1662063968320069632 -1662063968365070592 -1662063968410071552 -1662063968455072512 -1662063968497073408 -1662063968539074304 -1662063968584075264 -1662063968623076096 -1662063968665076992 -1662063968710077952 -1662063968761079040 -1662063968803079936 -1662063968848080896 -1662063968893081856 -1662063968938082816 -1662063968983083776 -1662063969025084672 -1662063969073085696 -1662063969115086592 -1662063969157087488 -1662063969205088512 -1662063969253089536 -1662063969295090432 -1662063969346091520 -1662063969391092480 -1662063969433093376 -1662063969478094336 -1662063969523095296 -1662063969565096192 -1662063969610097152 -1662063969655098112 -1662063969700099072 -1662063969739099904 -1662063969781100800 -1662063969826101760 -1662063969868102656 -1662063969913103616 -1662063969967104768 -1662063970009105664 -1662063970051106560 -1662063970093107456 -1662063970132108288 -1662063970180109312 -1662063970228110336 -1662063970267111168 -1662063970309112064 -1662063970360113152 -1662063970405114112 -1662063970447115008 -1662063970492115968 -1662063970531116800 -1662063970576117760 -1662063970615118592 -1662063970660119552 -1662063970711120640 -1662063970750121472 -1662063970792122368 -1662063970834123264 -1662063970876124160 -1662063970918125056 -1662063970960125952 -1662063971002126848 -1662063971044127744 -1662063971089128704 -1662063971131129600 -1662063971176130560 -1662063971218131456 -1662063971260132352 -1662063971299133184 -1662063971341134080 -1662063971389135104 -1662063971431136000 -1662063971473136896 -1662063971515137792 -1662063971557138688 -1662063971605139712 -1662063971650140672 -1662063971692141568 -1662063971740142592 -1662063971782143488 -1662063971827144448 -1662063971869145344 -1662063971914146304 -1662063971956147200 -1662063971998148096 -1662063972040148992 -1662063972088150016 -1662063972142151168 -1662063972187152128 -1662063972232153088 -1662063972271153920 -1662063972316154880 -1662063972358155776 -1662063972400156672 -1662063972448157696 -1662063972490158592 -1662063972535159552 -1662063972577160448 -1662063972622161408 -1662063972661162240 -1662063972703163136 -1662063972754164224 -1662063972802165248 -1662063972853166336 -1662063972895167232 -1662063972937168128 -1662063972982169088 -1662063973024169984 -1662063973072171008 -1662063973114171904 -1662063973156172800 -1662063973201173760 -1662063973252174848 -1662063973300175872 -1662063973348176896 -1662063973402178048 -1662063973444178944 -1662063973486179840 -1662063973525180672 -1662063973564181504 -1662063973618182656 -1662063973660183552 -1662063973699184384 -1662063973744185344 -1662063973789186304 -1662063973834187264 -1662063973876188160 -1662063973921189120 -1662063973963190016 -1662063974014191104 -1662063974056192000 -1662063974095192832 -1662063974137193728 -1662063974176194560 -1662063974218195456 -1662063974260196352 -1662063974302197248 -1662063974350198272 -1662063974389199104 -1662063974440200192 -1662063974482201088 -1662063974527202048 -1662063974572203008 -1662063974614203904 -1662063974659204864 -1662063974704205824 -1662063974749206784 -1662063974797207808 -1662063974839208704 -1662063974881209600 -1662063974929210624 -1662063974971211520 -1662063975016212480 -1662063975064213504 -1662063975106214400 -1662063975154215424 -1662063975196216320 -1662063975238217216 -1662063975280218112 -1662063975325219072 -1662063975370220032 -1662063975412220928 -1662063975454221824 -1662063975493222656 -1662063975532223488 -1662063975577224448 -1662063975619225344 -1662063975661226240 -1662063975703227136 -1662063975748228096 -1662063975790228992 -1662063975832229888 -1662063975874230784 -1662063975910231552 -1662063975955232512 -1662063975994233344 -1662063976036234240 -1662063976084235264 -1662063976126236160 -1662063976168237056 -1662063976219238144 -1662063976261239040 -1662063976303239936 -1662063976345240832 -1662063976387241728 -1662063976429242624 -1662063976471243520 -1662063976519244544 -1662063976561245440 -1662063976603246336 -1662063976648247296 -1662063976693248256 -1662063976735249152 -1662063976780250112 -1662063976822251008 -1662063976867251968 -1662063976909252864 -1662063976954253824 -1662063977002254848 -1662063977044255744 -1662063977089256704 -1662063977134257664 -1662063977176258560 -1662063977218259456 -1662063977263260416 -1662063977305261312 -1662063977347262208 -1662063977389263104 -1662063977434264064 -1662063977476264960 -1662063977521265920 -1662063977563266816 -1662063977617267968 -1662063977659268864 -1662063977704269824 -1662063977761271040 -1662063977806272000 -1662063977854273024 -1662063977896273920 -1662063977938274816 -1662063977977275648 -1662063978022276608 -1662063978067277568 -1662063978112278528 -1662063978151279360 -1662063978196280320 -1662063978238281216 -1662063978286282240 -1662063978340283392 -1662063978397284608 -1662063978445285632 -1662063978484286464 -1662063978529287424 -1662063978571288320 -1662063978616289280 -1662063978658290176 -1662063978703291136 -1662063978745292032 -1662063978784292864 -1662063978826293760 -1662063978868294656 -1662063978913295616 -1662063978961296640 -1662063979003297536 -1662063979051298560 -1662063979093299456 -1662063979138300416 -1662063979186301440 -1662063979228302336 -1662063979267303168 -1662063979318304256 -1662063979363305216 -1662063979408306176 -1662063979453307136 -1662063979495308032 -1662063979534308864 -1662063979585309952 -1662063979627310848 -1662063979669311744 -1662063979711312640 -1662063979756313600 -1662063979798314496 -1662063979843315456 -1662063979888316416 -1662063979930317312 -1662063979978318336 -1662063980020319232 -1662063980065320192 -1662063980110321152 -1662063980158322176 -1662063980200323072 -1662063980239323904 -1662063980284324864 -1662063980326325760 -1662063980368326656 -1662063980410327552 -1662063980455328512 -1662063980503329536 -1662063980545330432 -1662063980587331328 -1662063980635332352 -1662063980683333376 -1662063980722334208 -1662063980764335104 -1662063980806336000 -1662063980854337024 -1662063980896337920 -1662063980947339008 -1662063980992339968 -1662063981034340864 -1662063981073341696 -1662063981118342656 -1662063981157343488 -1662063981199344384 -1662063981250345472 -1662063981292346368 -1662063981337347328 -1662063981379348224 -1662063981421349120 -1662063981472350208 -1662063981517351168 -1662063981574352384 -1662063981616353280 -1662063981667354368 -1662063981712355328 -1662063981757356288 -1662063981796357120 -1662063981841358080 -1662063981889359104 -1662063981931360000 -1662063981982361088 -1662063982024361984 -1662063982066362880 -1662063982114363904 -1662063982159364864 -1662063982201365760 -1662063982240366592 -1662063982288367616 -1662063982333368576 -1662063982384369664 -1662063982426370560 -1662063982465371392 -1662063982519372544 -1662063982561373440 -1662063982606374400 -1662063982648375296 -1662063982693376256 -1662063982738377216 -1662063982780378112 -1662063982822379008 -1662063982867379968 -1662063982909380864 -1662063982954381824 -1662063982993382656 -1662063983035383552 -1662063983080384512 -1662063983122385408 -1662063983173386496 -1662063983212387328 -1662063983257388288 -1662063983296389120 -1662063983338390016 -1662063983386391040 -1662063983434392064 -1662063983479393024 -1662063983524393984 -1662063983566394880 -1662063983608395776 -1662063983656396800 -1662063983698397696 -1662063983737398528 -1662063983779399424 -1662063983824400384 -1662063983863401216 -1662063983905402112 -1662063983959403264 -1662063984001404160 -1662063984043405056 -1662063984085405952 -1662063984124406784 -1662063984166407680 -1662063984220408832 -1662063984262409728 -1662063984310410752 -1662063984355411712 -1662063984397412608 -1662063984436413440 -1662063984478414336 -1662063984520415232 -1662063984568416256 -1662063984613417216 -1662063984658418176 -1662063984703419136 -1662063984745420032 -1662063984790420992 -1662063984835421952 -1662063984880422912 -1662063984940424192 -1662063984979425024 -1662063985021425920 -1662063985063426816 -1662063985111427840 -1662063985153428736 -1662063985195429632 -1662063985249430784 -1662063985291431680 -1662063985330432512 -1662063985375433472 -1662063985420434432 -1662063985459435264 -1662063985504436224 -1662063985546437120 -1662063985591438080 -1662063985636439040 -1662063985678439936 -1662063985726440960 -1662063985765441792 -1662063985807442688 -1662063985855443712 -1662063985900444672 -1662063985939445504 -1662063985987446528 -1662063986029447424 -1662063986074448384 -1662063986116449280 -1662063986158450176 -1662063986200451072 -1662063986248452096 -1662063986290452992 -1662063986335453952 -1662063986377454848 -1662063986419455744 -1662063986461456640 -1662063986509457664 -1662063986551458560 -1662063986593459456 -1662063986647460608 -1662063986686461440 -1662063986728462336 -1662063986770463232 -1662063986809464064 -1662063986851464960 -1662063986896465920 -1662063986938466816 -1662063986980467712 -1662063987022468608 -1662063987070469632 -1662063987112470528 -1662063987157471488 -1662063987196472320 -1662063987238473216 -1662063987289474304 -1662063987334475264 -1662063987391476480 -1662063987430477312 -1662063987475478272 -1662063987517479168 -1662063987559480064 -1662063987601480960 -1662063987637481728 -1662063987679482624 -1662063987721483520 -1662063987763484416 -1662063987805485312 -1662063987847486208 -1662063987889487104 -1662063987937488128 -1662063987979489024 -1662063988021489920 -1662063988057490688 -1662063988102491648 -1662063988144492544 -1662063988186493440 -1662063988231494400 -1662063988273495296 -1662063988318496256 -1662063988360497152 -1662063988402498048 -1662063988441498880 -1662063988483499776 -1662063988525500672 -1662063988567501568 -1662063988609502464 -1662063988651503360 -1662063988696504320 -1662063988738505216 -1662063988783506176 -1662063988825507072 -1662063988879508224 -1662063988921509120 -1662063988963510016 -1662063989008510976 -1662063989050511872 -1662063989092512768 -1662063989140513792 -1662063989185514752 -1662063989227515648 -1662063989269516544 -1662063989317517568 -1662063989362518528 -1662063989404519424 -1662063989449520384 -1662063989491521280 -1662063989533522176 -1662063989578523136 -1662063989623524096 -1662063989665524992 -1662063989707525888 -1662063989755526912 -1662063989797527808 -1662063989839528704 -1662063989881529600 -1662063989926530560 -1662063989971531520 -1662063990016532480 -1662063990055533312 -1662063990097534208 -1662063990139535104 -1662063990181536000 -1662063990223536896 -1662063990265537792 -1662063990307538688 -1662063990349539584 -1662063990391540480 -1662063990439541504 -1662063990481542400 -1662063990526543360 -1662063990571544320 -1662063990610545152 -1662063990652546048 -1662063990694546944 -1662063990739547904 -1662063990784548864 -1662063990826549760 -1662063990874550784 -1662063990916551680 -1662063990958552576 -1662063991003553536 -1662063991045554432 -1662063991087555328 -1662063991135556352 -1662063991183557376 -1662063991231558400 -1662063991270559232 -1662063991318560256 -1662063991360561152 -1662063991405562112 -1662063991450563072 -1662063991492563968 -1662063991540564992 -1662063991579565824 -1662063991618566656 -1662063991666567680 -1662063991708568576 -1662063991753569536 -1662063991801570560 -1662063991843571456 -1662063991888572416 -1662063991930573312 -1662063991975574272 -1662063992020575232 -1662063992065576192 -1662063992113577216 -1662063992158578176 -1662063992197579008 -1662063992245580032 -1662063992284580864 -1662063992332581888 -1662063992374582784 -1662063992422583808 -1662063992470584832 -1662063992521585920 -1662063992563586816 -1662063992602587648 -1662063992647588608 -1662063992692589568 -1662063992740590592 -1662063992785591552 -1662063992836592640 -1662063992875593472 -1662063992917594368 -1662063992962595328 -1662063993004596224 -1662063993049597184 -1662063993094598144 -1662063993139599104 -1662063993178599936 -1662063993223600896 -1662063993262601728 -1662063993304602624 -1662063993349603584 -1662063993388604416 -1662063993430605312 -1662063993475606272 -1662063993517607168 -1662063993559608064 -1662063993601608960 -1662063993649609984 -1662063993691610880 -1662063993733611776 -1662063993775612672 -1662063993826613760 -1662063993865614592 -1662063993907615488 -1662063993949616384 -1662063994000617472 -1662063994045618432 -1662063994084619264 -1662063994126620160 -1662063994162620928 -1662063994207621888 -1662063994255622912 -1662063994303623936 -1662063994345624832 -1662063994399625984 -1662063994444626944 -1662063994486627840 -1662063994525628672 -1662063994573629696 -1662063994621630720 -1662063994669631744 -1662063994711632640 -1662063994756633600 -1662063994798634496 -1662063994846635520 -1662063994888636416 -1662063994939637504 -1662063994990638592 -1662063995032639488 -1662063995077640448 -1662063995119641344 -1662063995164642304 -1662063995209643264 -1662063995254644224 -1662063995299645184 -1662063995347646208 -1662063995389647104 -1662063995434648064 -1662063995479649024 -1662063995527650048 -1662063995569650944 -1662063995608651776 -1662063995650652672 -1662063995695653632 -1662063995737654528 -1662063995785655552 -1662063995830656512 -1662063995872657408 -1662063995914658304 -1662063995953659136 -1662063995998660096 -1662063996040660992 -1662063996085661952 -1662063996133662976 -1662063996181664000 -1662063996229665024 -1662063996283666176 -1662063996325667072 -1662063996373668096 -1662063996412668928 -1662063996463670016 -1662063996508670976 -1662063996550671872 -1662063996592672768 -1662063996637673728 -1662063996679674624 -1662063996730675712 -1662063996775676672 -1662063996817677568 -1662063996859678464 -1662063996904679424 -1662063996952680448 -1662063996997681408 -1662063997048682496 -1662063997087683328 -1662063997126684160 -1662063997177685248 -1662063997222686208 -1662063997264687104 -1662063997306688000 -1662063997345688832 -1662063997396689920 -1662063997444690944 -1662063997486691840 -1662063997531692800 -1662063997573693696 -1662063997621694720 -1662063997666695680 -1662063997708696576 -1662063997750697472 -1662063997795698432 -1662063997840699392 -1662063997888700416 -1662063997933701376 -1662063997975702272 -1662063998020703232 -1662063998062704128 -1662063998107705088 -1662063998149705984 -1662063998200707072 -1662063998242707968 -1662063998287708928 -1662063998335709952 -1662063998377710848 -1662063998428711936 -1662063998473712896 -1662063998527714048 -1662063998575715072 -1662063998626716160 -1662063998677717248 -1662063998725718272 -1662063998770719232 -1662063998812720128 -1662063998854721024 -1662063998896721920 -1662063998944722944 -1662063998986723840 -1662063999028724736 -1662063999079725824 -1662063999121726720 -1662063999163727616 -1662063999208728576 -1662063999250729472 -1662063999292730368 -1662063999334731264 -1662063999385732352 -1662063999433733376 -1662063999475734272 -1662063999517735168 -1662063999559736064 -1662063999604737024 -1662063999646737920 -1662063999688738816 -1662063999730739712 -1662063999769740544 -1662063999811741440 -1662063999856742400 -1662063999904743424 -1662063999946744320 -1662063999988745216 -1662064000027746048 -1662064000069746944 -1662064000114747904 -1662064000156748800 -1662064000201749760 -1662064000246750720 -1662064000291751680 -1662064000333752576 -1662064000378753536 -1662064000420754432 -1662064000465755392 -1662064000510756352 -1662064000555757312 -1662064000603758336 -1662064000648759296 -1662064000687760128 -1662064000729761024 -1662064000771761920 -1662064000816762880 -1662064000864763904 -1662064000906764800 -1662064000948765696 -1662064000993766656 -1662064001044767744 -1662064001086768640 -1662064001128769536 -1662064001173770496 -1662064001215771392 -1662064001260772352 -1662064001308773376 -1662064001350774272 -1662064001398775296 -1662064001440776192 -1662064001488777216 -1662064001533778176 -1662064001578779136 -1662064001629780224 -1662064001671781120 -1662064001713782016 -1662064001755782912 -1662064001797783808 -1662064001839784704 -1662064001881785600 -1662064001929786624 -1662064001971787520 -1662064002013788416 -1662064002055789312 -1662064002097790208 -1662064002142791168 -1662064002187792128 -1662064002229793024 -1662064002274793984 -1662064002319794944 -1662064002373796096 -1662064002415796992 -1662064002457797888 -1662064002499798784 -1662064002550799872 -1662064002592800768 -1662064002634801664 -1662064002673802496 -1662064002718803456 -1662064002760804352 -1662064002805805312 -1662064002847806208 -1662064002889807104 -1662064002931808000 -1662064002979809024 -1662064003030810112 -1662064003075811072 -1662064003120812032 -1662064003168813056 -1662064003207813888 -1662064003249814784 -1662064003294815744 -1662064003342816768 -1662064003390817792 -1662064003435818752 -1662064003477819648 -1662064003522820608 -1662064003564821504 -1662064003606822400 -1662064003654823424 -1662064003699824384 -1662064003747825408 -1662064003789826304 -1662064003828827136 -1662064003873828096 -1662064003915828992 -1662064003960829952 -1662064004008830976 -1662064004053831936 -1662064004092832768 -1662064004134833664 -1662064004176834560 -1662064004218835456 -1662064004266836480 -1662064004308837376 -1662064004350838272 -1662064004392839168 -1662064004434840064 -1662064004485841152 -1662064004527842048 -1662064004575843072 -1662064004617843968 -1662064004668845056 -1662064004713846016 -1662064004758846976 -1662064004800847872 -1662064004842848768 -1662064004887849728 -1662064004929850624 -1662064004971851520 -1662064005019852544 -1662064005064853504 -1662064005115854592 -1662064005160855552 -1662064005202856448 -1662064005247857408 -1662064005289858304 -1662064005331859200 -1662064005373860096 -1662064005424861184 -1662064005466862080 -1662064005511863040 -1662064005553863936 -1662064005598864896 -1662064005640865792 -1662064005682866688 -1662064005736867840 -1662064005781868800 -1662064005826869760 -1662064005871870720 -1662064005910871552 -1662064005955872512 -1662064006000873472 -1662064006045874432 -1662064006090875392 -1662064006132876288 -1662064006177877248 -1662064006222878208 -1662064006264879104 -1662064006309880064 -1662064006360881152 -1662064006402882048 -1662064006444882944 -1662064006489883904 -1662064006531884800 -1662064006576885760 -1662064006621886720 -1662064006669887744 -1662064006717888768 -1662064006762889728 -1662064006804890624 -1662064006855891712 -1662064006897892608 -1662064006942893568 -1662064006990894592 -1662064007032895488 -1662064007077896448 -1662064007119897344 -1662064007161898240 -1662064007206899200 -1662064007248900096 -1662064007290900992 -1662064007332901888 -1662064007374902784 -1662064007425903872 -1662064007464904704 -1662064007512905728 -1662064007557906688 -1662064007602907648 -1662064007647908608 -1662064007692909568 -1662064007746910720 -1662064007791911680 -1662064007833912576 -1662064007878913536 -1662064007920914432 -1662064007962915328 -1662064008004916224 -1662064008046917120 -1662064008091918080 -1662064008133918976 -1662064008175919872 -1662064008220920832 -1662064008262921728 -1662064008307922688 -1662064008352923648 -1662064008394924544 -1662064008436925440 -1662064008478926336 -1662064008520927232 -1662064008565928192 -1662064008610929152 -1662064008664930304 -1662064008709931264 -1662064008754932224 -1662064008796933120 -1662064008844934144 -1662064008889935104 -1662064008934936064 -1662064008985937152 -1662064009027938048 -1662064009075939072 -1662064009120940032 -1662064009162940928 -1662064009207941888 -1662064009249942784 -1662064009288943616 -1662064009339944704 -1662064009381945600 -1662064009423946496 -1662064009465947392 -1662064009510948352 -1662064009558949376 -1662064009597950208 -1662064009636951040 -1662064009678951936 -1662064009717952768 -1662064009762953728 -1662064009807954688 -1662064009849955584 -1662064009897956608 -1662064009948957696 -1662064009990958592 -1662064010035959552 -1662064010077960448 -1662064010122961408 -1662064010170962432 -1662064010215963392 -1662064010260964352 -1662064010317965568 -1662064010365966592 -1662064010410967552 -1662064010458968576 -1662064010500969472 -1662064010542970368 -1662064010587971328 -1662064010629972224 -1662064010674973184 -1662064010719974144 -1662064010767975168 -1662064010809976064 -1662064010857977088 -1662064010902978048 -1662064010947979008 -1662064010989979904 -1662064011031980800 -1662064011073981696 -1662064011121982720 -1662064011172983808 -1662064011214984704 -1662064011259985664 -1662064011307986688 -1662064011346987520 -1662064011391988480 -1662064011436989440 -1662064011478990336 -1662064011523991296 -1662064011568992256 -1662064011610993152 -1662064011655994112 -1662064011700995072 -1662064011748996096 -1662064011790996992 -1662064011835997952 -1662064011877998848 -1662064011919999744 -1662064011965000704 -1662064012010001664 -1662064012049002496 -1662064012091003392 -1662064012133004288 -1662064012175005184 -1662064012217006080 -1662064012262007040 -1662064012301007872 -1662064012346008832 -1662064012391009792 -1662064012433010688 -1662064012481011712 -1662064012526012672 -1662064012568013568 -1662064012610014464 -1662064012652015360 -1662064012694016256 -1662064012748017408 -1662064012790018304 -1662064012832019200 -1662064012874020096 -1662064012916020992 -1662064012961021952 -1662064013015023104 -1662064013060024064 -1662064013105025024 -1662064013150025984 -1662064013192026880 -1662064013237027840 -1662064013279028736 -1662064013321029632 -1662064013369030656 -1662064013411031552 -1662064013456032512 -1662064013501033472 -1662064013543034368 -1662064013585035264 -1662064013630036224 -1662064013678037248 -1662064013720038144 -1662064013768039168 -1662064013810040064 -1662064013855041024 -1662064013900041984 -1662064013948043008 -1662064013993043968 -1662064014038044928 -1662064014089046016 -1662064014134046976 -1662064014179047936 -1662064014224048896 -1662064014275049984 -1662064014314050816 -1662064014356051712 -1662064014401052672 -1662064014446053632 -1662064014488054528 -1662064014533055488 -1662064014578056448 -1662064014623057408 -1662064014662058240 -1662064014710059264 -1662064014758060288 -1662064014797061120 -1662064014839062016 -1662064014887063040 -1662064014935064064 -1662064014980065024 -1662064015031066112 -1662064015082067200 -1662064015124068096 -1662064015166068992 -1662064015211069952 -1662064015259070976 -1662064015304071936 -1662064015349072896 -1662064015391073792 -1662064015436074752 -1662064015478075648 -1662064015520076544 -1662064015574077696 -1662064015634078976 -1662064015685080064 -1662064015727080960 -1662064015769081856 -1662064015811082752 -1662064015850083584 -1662064015889084416 -1662064015931085312 -1662064015973086208 -1662064016018087168 -1662064016060088064 -1662064016111089152 -1662064016153090048 -1662064016198091008 -1662064016240091904 -1662064016294093056 -1662064016342094080 -1662064016387095040 -1662064016435096064 -1662064016477096960 -1662064016522097920 -1662064016564098816 -1662064016609099776 -1662064016660100864 -1662064016705101824 -1662064016750102784 -1662064016792103680 -1662064016837104640 -1662064016879105536 -1662064016924106496 -1662064016966107392 -1662064017011108352 -1662064017053109248 -1662064017095110144 -1662064017140111104 -1662064017182112000 -1662064017227112960 -1662064017269113856 -1662064017311114752 -1662064017353115648 -1662064017395116544 -1662064017437117440 -1662064017482118400 -1662064017524119296 -1662064017566120192 -1662064017608121088 -1662064017656122112 -1662064017704123136 -1662064017749124096 -1662064017791124992 -1662064017836125952 -1662064017878126848 -1662064017920127744 -1662064017965128704 -1662064018010129664 -1662064018055130624 -1662064018103131648 -1662064018145132544 -1662064018187133440 -1662064018232134400 -1662064018289135616 -1662064018334136576 -1662064018382137600 -1662064018421138432 -1662064018463139328 -1662064018505140224 -1662064018550141184 -1662064018595142144 -1662064018640143104 -1662064018682144000 -1662064018721144832 -1662064018766145792 -1662064018808146688 -1662064018850147584 -1662064018892148480 -1662064018934149376 -1662064018976150272 -1662064019024151296 -1662064019066152192 -1662064019111153152 -1662064019153154048 -1662064019198155008 -1662064019243155968 -1662064019288156928 -1662064019327157760 -1662064019378158848 -1662064019417159680 -1662064019462160640 -1662064019507161600 -1662064019552162560 -1662064019594163456 -1662064019636164352 -1662064019672165120 -1662064019717166080 -1662064019756166912 -1662064019798167808 -1662064019843168768 -1662064019888169728 -1662064019936170752 -1662064019978171648 -1662064020020172544 -1662064020065173504 -1662064020107174400 -1662064020152175360 -1662064020194176256 -1662064020239177216 -1662064020284178176 -1662064020329179136 -1662064020377180160 -1662064020428181248 -1662064020479182336 -1662064020521183232 -1662064020572184320 -1662064020614185216 -1662064020662186240 -1662064020707187200 -1662064020752188160 -1662064020794189056 -1662064020836189952 -1662064020878190848 -1662064020923191808 -1662064020968192768 -1662064021013193728 -1662064021058194688 -1662064021100195584 -1662064021154196736 -1662064021205197824 -1662064021247198720 -1662064021289199616 -1662064021331200512 -1662064021373201408 -1662064021421202432 -1662064021463203328 -1662064021508204288 -1662064021553205248 -1662064021595206144 -1662064021637207040 -1662064021682208000 -1662064021724208896 -1662064021766209792 -1662064021811210752 -1662064021853211648 -1662064021901212672 -1662064021949213696 -1662064021994214656 -1662064022036215552 -1662064022081216512 -1662064022120217344 -1662064022162218240 -1662064022210219264 -1662064022255220224 -1662064022297221120 -1662064022342222080 -1662064022384222976 -1662064022432224000 -1662064022474224896 -1662064022525225984 -1662064022567226880 -1662064022612227840 -1662064022660228864 -1662064022702229760 -1662064022747230720 -1662064022789231616 -1662064022831232512 -1662064022888233728 -1662064022930234624 -1662064022978235648 -1662064023017236480 -1662064023065237504 -1662064023116238592 -1662064023155239424 -1662064023197240320 -1662064023239241216 -1662064023281242112 -1662064023323243008 -1662064023365243904 -1662064023407244800 -1662064023449245696 -1662064023500246784 -1662064023542247680 -1662064023584248576 -1662064023632249600 -1662064023677250560 -1662064023725251584 -1662064023767252480 -1662064023809253376 -1662064023857254400 -1662064023902255360 -1662064023944256256 -1662064023989257216 -1662064024031258112 -1662064024076259072 -1662064024127260160 -1662064024175261184 -1662064024217262080 -1662064024262263040 -1662064024304263936 -1662064024352264960 -1662064024397265920 -1662064024448267008 -1662064024496268032 -1662064024538268928 -1662064024583269888 -1662064024634270976 -1662064024679271936 -1662064024727272960 -1662064024778274048 -1662064024820274944 -1662064024871276032 -1662064024913276928 -1662064024955277824 -1662064024997278720 -1662064025039279616 -1662064025090280704 -1662064025129281536 -1662064025177282560 -1662064025228283648 -1662064025270284544 -1662064025312285440 -1662064025354286336 -1662064025396287232 -1662064025456288512 -1662064025507289600 -1662064025549290496 -1662064025594291456 -1662064025636292352 -1662064025678293248 -1662064025720294144 -1662064025768295168 -1662064025807296000 -1662064025852296960 -1662064025891297792 -1662064025933298688 -1662064025972299520 -1662064026020300544 -1662064026059301376 -1662064026101302272 -1662064026152303360 -1662064026197304320 -1662064026242305280 -1662064026284306176 -1662064026326307072 -1662064026368307968 -1662064026413308928 -1662064026455309824 -1662064026500310784 -1662064026539311616 -1662064026578312448 -1662064026620313344 -1662064026659314176 -1662064026701315072 -1662064026740315904 -1662064026785316864 -1662064026833317888 -1662064026878318848 -1662064026917319680 -1662064026962320640 -1662064027007321600 -1662064027061322752 -1662064027103323648 -1662064027142324480 -1662064027184325376 -1662064027226326272 -1662064027271327232 -1662064027313328128 -1662064027355329024 -1662064027397329920 -1662064027442330880 -1662064027484331776 -1662064027532332800 -1662064027571333632 -1662064027613334528 -1662064027655335424 -1662064027700336384 -1662064027745337344 -1662064027787338240 -1662064027832339200 -1662064027877340160 -1662064027922341120 -1662064027964342016 -1662064028006342912 -1662064028051343872 -1662064028093344768 -1662064028144345856 -1662064028192346880 -1662064028234347776 -1662064028288348928 -1662064028333349888 -1662064028378350848 -1662064028423351808 -1662064028462352640 -1662064028510353664 -1662064028549354496 -1662064028591355392 -1662064028636356352 -1662064028678357248 -1662064028723358208 -1662064028768359168 -1662064028810360064 -1662064028849360896 -1662064028891361792 -1662064028933362688 -1662064028975363584 -1662064029029364736 -1662064029071365632 -1662064029113366528 -1662064029158367488 -1662064029203368448 -1662064029245369344 -1662064029284370176 -1662064029329371136 -1662064029374372096 -1662064029416372992 -1662064029458373888 -1662064029503374848 -1662064029545375744 -1662064029593376768 -1662064029635377664 -1662064029683378688 -1662064029725379584 -1662064029767380480 -1662064029818381568 -1662064029866382592 -1662064029908383488 -1662064029950384384 -1662064029998385408 -1662064030052386560 -1662064030097387520 -1662064030145388544 -1662064030196389632 -1662064030238390528 -1662064030286391552 -1662064030331392512 -1662064030385393664 -1662064030430394624 -1662064030469395456 -1662064030514396416 -1662064030574397696 -1662064030616398592 -1662064030658399488 -1662064030700400384 -1662064030748401408 -1662064030793402368 -1662064030841403392 -1662064030886404352 -1662064030928405248 -1662064030979406336 -1662064031024407296 -1662064031066408192 -1662064031114409216 -1662064031156410112 -1662064031204411136 -1662064031246412032 -1662064031291412992 -1662064031333413888 -1662064031378414848 -1662064031417415680 -1662064031459416576 -1662064031519417856 -1662064031564418816 -1662064031612419840 -1662064031654420736 -1662064031699421696 -1662064031747422720 -1662064031798423808 -1662064031846424832 -1662064031888425728 -1662064031930426624 -1662064031972427520 -1662064032014428416 -1662064032056429312 -1662064032098430208 -1662064032143431168 -1662064032188432128 -1662064032230433024 -1662064032272433920 -1662064032314434816 -1662064032356435712 -1662064032401436672 -1662064032443437568 -1662064032488438528 -1662064032530439424 -1662064032584440576 -1662064032623441408 -1662064032665442304 -1662064032716443392 -1662064032758444288 -1662064032800445184 -1662064032845446144 -1662064032899447296 -1662064032947448320 -1662064032989449216 -1662064033031450112 -1662064033070450944 -1662064033112451840 -1662064033154452736 -1662064033205453824 -1662064033247454720 -1662064033295455744 -1662064033337456640 -1662064033385457664 -1662064033427458560 -1662064033472459520 -1662064033514460416 -1662064033559461376 -1662064033607462400 -1662064033652463360 -1662064033694464256 -1662064033736465152 -1662064033781466112 -1662064033826467072 -1662064033868467968 -1662064033910468864 -1662064033955469824 -1662064033997470720 -1662064034042471680 -1662064034084472576 -1662064034129473536 -1662064034168474368 -1662064034210475264 -1662064034252476160 -1662064034294477056 -1662064034336477952 -1662064034378478848 -1662064034417479680 -1662064034459480576 -1662064034504481536 -1662064034549482496 -1662064034597483520 -1662064034636484352 -1662064034681485312 -1662064034723486208 -1662064034765487104 -1662064034810488064 -1662064034855489024 -1662064034897489920 -1662064034936490752 -1662064034984491776 -1662064035032492800 -1662064035074493696 -1662064035122494720 -1662064035164495616 -1662064035206496512 -1662064035248497408 -1662064035290498304 -1662064035332499200 -1662064035374500096 -1662064035419501056 -1662064035458501888 -1662064035500502784 -1662064035542503680 -1662064035584504576 -1662064035626505472 -1662064035671506432 -1662064035713507328 -1662064035758508288 -1662064035806509312 -1662064035854510336 -1662064035896511232 -1662064035947512320 -1662064035995513344 -1662064036037514240 -1662064036085515264 -1662064036130516224 -1662064036172517120 -1662064036214518016 -1662064036256518912 -1662064036310520064 -1662064036352520960 -1662064036400521984 -1662064036445522944 -1662064036487523840 -1662064036529524736 -1662064036571525632 -1662064036613526528 -1662064036658527488 -1662064036697528320 -1662064036739529216 -1662064036787530240 -1662064036835531264 -1662064036877532160 -1662064036922533120 -1662064036967534080 -1662064037015535104 -1662064037057536000 -1662064037099536896 -1662064037147537920 -1662064037189538816 -1662064037234539776 -1662064037282540800 -1662064037324541696 -1662064037369542656 -1662064037408543488 -1662064037450544384 -1662064037492545280 -1662064037534546176 -1662064037576547072 -1662064037621548032 -1662064037663548928 -1662064037705549824 -1662064037750550784 -1662064037795551744 -1662064037843552768 -1662064037885553664 -1662064037930554624 -1662064037972555520 -1662064038014556416 -1662064038056557312 -1662064038104558336 -1662064038149559296 -1662064038191560192 -1662064038239561216 -1662064038281562112 -1662064038323563008 -1662064038365563904 -1662064038413564928 -1662064038455565824 -1662064038497566720 -1662064038542567680 -1662064038590568704 -1662064038638569728 -1662064038680570624 -1662064038719571456 -1662064038761572352 -1662064038806573312 -1662064038851574272 -1662064038896575232 -1662064038938576128 -1662064038983577088 -1662064039028578048 -1662064039076579072 -1662064039118579968 -1662064039160580864 -1662064039205581824 -1662064039253582848 -1662064039295583744 -1662064039340584704 -1662064039382585600 -1662064039424586496 -1662064039469587456 -1662064039508588288 -1662064039550589184 -1662064039595590144 -1662064039637591040 -1662064039685592064 -1662064039727592960 -1662064039766593792 -1662064039811594752 -1662064039853595648 -1662064039898596608 -1662064039940597504 -1662064039982598400 -1662064040024599296 -1662064040072600320 -1662064040114601216 -1662064040162602240 -1662064040207603200 -1662064040252604160 -1662064040303605248 -1662064040348606208 -1662064040390607104 -1662064040435608064 -1662064040477608960 -1662064040519609856 -1662064040561610752 -1662064040603611648 -1662064040642612480 -1662064040699613696 -1662064040738614528 -1662064040777615360 -1662064040819616256 -1662064040864617216 -1662064040906618112 -1662064040945618944 -1662064040990619904 -1662064041032620800 -1662064041074621696 -1662064041122622720 -1662064041164623616 -1662064041209624576 -1662064041254625536 -1662064041296626432 -1662064041347627520 -1662064041395628544 -1662064041443629568 -1662064041488630528 -1662064041533631488 -1662064041584632576 -1662064041629633536 -1662064041671634432 -1662064041713635328 -1662064041755636224 -1662064041806637312 -1662064041845638144 -1662064041887639040 -1662064041932640000 -1662064041977640960 -1662064042025641984 -1662064042076643072 -1662064042121644032 -1662064042163644928 -1662064042205645824 -1662064042247646720 -1662064042292647680 -1662064042334648576 -1662064042379649536 -1662064042424650496 -1662064042466651392 -1662064042508652288 -1662064042553653248 -1662064042598654208 -1662064042646655232 -1662064042691656192 -1662064042733657088 -1662064042778658048 -1662064042829659136 -1662064042871660032 -1662064042916660992 -1662064042964662016 -1662064043015663104 -1662064043057664000 -1662064043108665088 -1662064043153666048 -1662064043198667008 -1662064043240667904 -1662064043288668928 -1662064043330669824 -1662064043378670848 -1662064043423671808 -1662064043471672832 -1662064043513673728 -1662064043558674688 -1662064043603675648 -1662064043657676800 -1662064043705677824 -1662064043750678784 -1662064043792679680 -1662064043843680768 -1662064043882681600 -1662064043927682560 -1662064043966683392 -1662064044011684352 -1662064044062685440 -1662064044107686400 -1662064044146687232 -1662064044197688320 -1662064044239689216 -1662064044290690304 -1662064044332691200 -1662064044383692288 -1662064044431693312 -1662064044473694208 -1662064044515695104 -1662064044563696128 -1662064044602696960 -1662064044647697920 -1662064044698699008 -1662064044743699968 -1662064044788700928 -1662064044830701824 -1662064044872702720 -1662064044923703808 -1662064044965704704 -1662064045016705792 -1662064045058706688 -1662064045100707584 -1662064045145708544 -1662064045187709440 -1662064045238710528 -1662064045280711424 -1662064045328712448 -1662064045370713344 -1662064045415714304 -1662064045454715136 -1662064045496716032 -1662064045544717056 -1662064045589718016 -1662064045634718976 -1662064045679719936 -1662064045721720832 -1662064045763721728 -1662064045805722624 -1662064045850723584 -1662064045895724544 -1662064045940725504 -1662064045982726400 -1662064046027727360 -1662064046075728384 -1662064046123729408 -1662064046165730304 -1662064046207731200 -1662064046258732288 -1662064046303733248 -1662064046351734272 -1662064046396735232 -1662064046441736192 -1662064046492737280 -1662064046534738176 -1662064046576739072 -1662064046621740032 -1662064046666740992 -1662064046711741952 -1662064046756742912 -1662064046804743936 -1662064046846744832 -1662064046885745664 -1662064046927746560 -1662064046969747456 -1662064047014748416 -1662064047056749312 -1662064047101750272 -1662064047149751296 -1662064047194752256 -1662064047239753216 -1662064047284754176 -1662064047326755072 -1662064047371756032 -1662064047419757056 -1662064047464758016 -1662064047509758976 -1662064047554759936 -1662064047605761024 -1662064047653762048 -1662064047707763200 -1662064047752764160 -1662064047794765056 -1662064047836765952 -1662064047878766848 -1662064047923767808 -1662064047965768704 -1662064048010769664 -1662064048052770560 -1662064048094771456 -1662064048142772480 -1662064048184773376 -1662064048226774272 -1662064048277775360 -1662064048319776256 -1662064048361777152 -1662064048406778112 -1662064048448779008 -1662064048493779968 -1662064048535780864 -1662064048577781760 -1662064048619782656 -1662064048664783616 -1662064048706784512 -1662064048754785536 -1662064048793786368 -1662064048832787200 -1662064048877788160 -1662064048922789120 -1662064048967790080 -1662064049009790976 -1662064049048791808 -1662064049096792832 -1662064049141793792 -1662064049186794752 -1662064049234795776 -1662064049276796672 -1662064049318797568 -1662064049366798592 -1662064049408799488 -1662064049450800384 -1662064049495801344 -1662064049537802240 -1662064049576803072 -1662064049618803968 -1662064049660804864 -1662064049702805760 -1662064049744806656 -1662064049789807616 -1662064049834808576 -1662064049876809472 -1662064049918810368 -1662064049960811264 -1662064050002812160 -1662064050053813248 -1662064050095814144 -1662064050137815040 -1662064050179815936 -1662064050221816832 -1662064050263817728 -1662064050305818624 -1662064050347819520 -1662064050389820416 -1662064050434821376 -1662064050482822400 -1662064050524823296 -1662064050584824576 -1662064050626825472 -1662064050668826368 -1662064050713827328 -1662064050755828224 -1662064050797829120 -1662064050845830144 -1662064050887831040 -1662064050932832000 -1662064050977832960 -1662064051016833792 -1662064051070834944 -1662064051115835904 -1662064051157836800 -1662064051199837696 -1662064051241838592 -1662064051283839488 -1662064051325840384 -1662064051367841280 -1662064051409842176 -1662064051454843136 -1662064051499844096 -1662064051544845056 -1662064051592846080 -1662064051631846912 -1662064051673847808 -1662064051715848704 -1662064051763849728 -1662064051808850688 -1662064051853851648 -1662064051901852672 -1662064051943853568 -1662064051985854464 -1662064052036855552 -1662064052081856512 -1662064052129857536 -1662064052171858432 -1662064052213859328 -1662064052261860352 -1662064052303861248 -1662064052345862144 -1662064052387863040 -1662064052438864128 -1662064052483865088 -1662064052525865984 -1662064052573867008 -1662064052624868096 -1662064052669869056 -1662064052714870016 -1662064052759870976 -1662064052795871744 -1662064052840872704 -1662064052885873664 -1662064052924874496 -1662064052969875456 -1662064053011876352 -1662064053056877312 -1662064053098878208 -1662064053143879168 -1662064053188880128 -1662064053233881088 -1662064053278882048 -1662064053323883008 -1662064053365883904 -1662064053407884800 -1662064053452885760 -1662064053491886592 -1662064053533887488 -1662064053575888384 -1662064053614889216 -1662064053659890176 -1662064053698891008 -1662064053746892032 -1662064053791892992 -1662064053842894080 -1662064053884894976 -1662064053929895936 -1662064053974896896 -1662064054019897856 -1662064054061898752 -1662064054103899648 -1662064054142900480 -1662064054184901376 -1662064054223902208 -1662064054265903104 -1662064054307904000 -1662064054355905024 -1662064054409906176 -1662064054457907200 -1662064054502908160 -1662064054541908992 -1662064054589910016 -1662064054631910912 -1662064054676911872 -1662064054727912960 -1662064054772913920 -1662064054814914816 -1662064054865915904 -1662064054910916864 -1662064054946917632 -1662064054997918720 -1662064055042919680 -1662064055090920704 -1662064055138921728 -1662064055180922624 -1662064055225923584 -1662064055270924544 -1662064055315925504 -1662064055360926464 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_light.txt b/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_light.txt deleted file mode 100644 index b9447370b4..0000000000 --- a/Examples/Monocular/MIMIR_TimeStamps/SandPipe_track0_light.txt +++ /dev/null @@ -1,2605 +0,0 @@ -1662121584099220736 -1662121584144221696 -1662121584186222592 -1662121584234223616 -1662121584279224576 -1662121584321225472 -1662121584369226496 -1662121584417227520 -1662121584459228416 -1662121584498229248 -1662121584540230144 -1662121584582231040 -1662121584624231936 -1662121584669232896 -1662121584717233920 -1662121584762234880 -1662121584807235840 -1662121584855236864 -1662121584900237824 -1662121584942238720 -1662121584987239680 -1662121585032240640 -1662121585074241536 -1662121585119242496 -1662121585161243392 -1662121585203244288 -1662121585251245312 -1662121585296246272 -1662121585338247168 -1662121585389248256 -1662121585434249216 -1662121585476250112 -1662121585524251136 -1662121585575252224 -1662121585617253120 -1662121585671254272 -1662121585716255232 -1662121585758256128 -1662121585803257088 -1662121585845257984 -1662121585887258880 -1662121585932259840 -1662121585977260800 -1662121586019261696 -1662121586061262592 -1662121586106263552 -1662121586151264512 -1662121586193265408 -1662121586235266304 -1662121586277267200 -1662121586319268096 -1662121586364269056 -1662121586409270016 -1662121586460271104 -1662121586502272000 -1662121586553273088 -1662121586595273984 -1662121586634274816 -1662121586679275776 -1662121586724276736 -1662121586766277632 -1662121586823278848 -1662121586868279808 -1662121586916280832 -1662121586961281792 -1662121587003282688 -1662121587048283648 -1662121587093284608 -1662121587135285504 -1662121587177286400 -1662121587216287232 -1662121587258288128 -1662121587303289088 -1662121587345289984 -1662121587387290880 -1662121587429291776 -1662121587474292736 -1662121587522293760 -1662121587567294720 -1662121587615295744 -1662121587657296640 -1662121587702297600 -1662121587747298560 -1662121587789299456 -1662121587834300416 -1662121587876301312 -1662121587921302272 -1662121587966303232 -1662121588008304128 -1662121588053305088 -1662121588101306112 -1662121588143307008 -1662121588197308160 -1662121588245309184 -1662121588290310144 -1662121588332311040 -1662121588383312128 -1662121588428313088 -1662121588470313984 -1662121588512314880 -1662121588557315840 -1662121588602316800 -1662121588644317696 -1662121588686318592 -1662121588737319680 -1662121588779320576 -1662121588821321472 -1662121588872322560 -1662121588914323456 -1662121588962324480 -1662121589004325376 -1662121589043326208 -1662121589088327168 -1662121589130328064 -1662121589172328960 -1662121589214329856 -1662121589265330944 -1662121589307331840 -1662121589349332736 -1662121589397333760 -1662121589439334656 -1662121589478335488 -1662121589520336384 -1662121589565337344 -1662121589604338176 -1662121589646339072 -1662121589691340032 -1662121589739341056 -1662121589784342016 -1662121589826342912 -1662121589871343872 -1662121589919344896 -1662121589961345792 -1662121590003346688 -1662121590051347712 -1662121590093348608 -1662121590135349504 -1662121590183350528 -1662121590228351488 -1662121590279352576 -1662121590321353472 -1662121590360354304 -1662121590405355264 -1662121590447356160 -1662121590492357120 -1662121590540358144 -1662121590579358976 -1662121590621359872 -1662121590663360768 -1662121590705361664 -1662121590747362560 -1662121590792363520 -1662121590837364480 -1662121590885365504 -1662121590927366400 -1662121590969367296 -1662121591014368256 -1662121591062369280 -1662121591107370240 -1662121591155371264 -1662121591194372096 -1662121591236372992 -1662121591284374016 -1662121591329374976 -1662121591374375936 -1662121591428377088 -1662121591473378048 -1662121591518379008 -1662121591560379904 -1662121591611380992 -1662121591650381824 -1662121591701382912 -1662121591743383808 -1662121591785384704 -1662121591830385664 -1662121591875386624 -1662121591917387520 -1662121591962388480 -1662121592007389440 -1662121592049390336 -1662121592091391232 -1662121592133392128 -1662121592175393024 -1662121592226394112 -1662121592268395008 -1662121592313395968 -1662121592352396800 -1662121592391397632 -1662121592439398656 -1662121592496399872 -1662121592538400768 -1662121592583401728 -1662121592625402624 -1662121592670403584 -1662121592712404480 -1662121592751405312 -1662121592799406336 -1662121592844407296 -1662121592883408128 -1662121592925409024 -1662121592970409984 -1662121593024411136 -1662121593069412096 -1662121593114413056 -1662121593156413952 -1662121593201414912 -1662121593246415872 -1662121593294416896 -1662121593342417920 -1662121593390418944 -1662121593444420096 -1662121593486420992 -1662121593531421952 -1662121593576422912 -1662121593627424000 -1662121593672424960 -1662121593726426112 -1662121593777427200 -1662121593816428032 -1662121593855428864 -1662121593900429824 -1662121593948430848 -1662121594005432064 -1662121594050433024 -1662121594092433920 -1662121594143435008 -1662121594185435904 -1662121594230436864 -1662121594278437888 -1662121594323438848 -1662121594371439872 -1662121594416440832 -1662121594461441792 -1662121594503442688 -1662121594551443712 -1662121594599444736 -1662121594641445632 -1662121594683446528 -1662121594725447424 -1662121594770448384 -1662121594812449280 -1662121594857450240 -1662121594899451136 -1662121594941452032 -1662121594983452928 -1662121595034454016 -1662121595076454912 -1662121595124455936 -1662121595184457216 -1662121595226458112 -1662121595274459136 -1662121595316460032 -1662121595361460992 -1662121595406461952 -1662121595454462976 -1662121595496463872 -1662121595541464832 -1662121595583465728 -1662121595631466752 -1662121595676467712 -1662121595724468736 -1662121595772469760 -1662121595826470912 -1662121595868471808 -1662121595919472896 -1662121595964473856 -1662121596006474752 -1662121596051475712 -1662121596099476736 -1662121596144477696 -1662121596186478592 -1662121596234479616 -1662121596276480512 -1662121596318481408 -1662121596357482240 -1662121596399483136 -1662121596447484160 -1662121596489485056 -1662121596534486016 -1662121596576486912 -1662121596630488064 -1662121596675489024 -1662121596720489984 -1662121596768491008 -1662121596819492096 -1662121596861492992 -1662121596912494080 -1662121596951494912 -1662121596993495808 -1662121597038496768 -1662121597083497728 -1662121597125498624 -1662121597173499648 -1662121597215500544 -1662121597260501504 -1662121597305502464 -1662121597344503296 -1662121597389504256 -1662121597443505408 -1662121597485506304 -1662121597524507136 -1662121597572508160 -1662121597617509120 -1662121597662510080 -1662121597710511104 -1662121597761512192 -1662121597812513280 -1662121597863514368 -1662121597908515328 -1662121597950516224 -1662121598001517312 -1662121598043518208 -1662121598097519360 -1662121598148520448 -1662121598190521344 -1662121598238522368 -1662121598283523328 -1662121598334524416 -1662121598379525376 -1662121598427526400 -1662121598472527360 -1662121598520528384 -1662121598565529344 -1662121598607530240 -1662121598652531200 -1662121598694532096 -1662121598742533120 -1662121598781533952 -1662121598823534848 -1662121598868535808 -1662121598913536768 -1662121598955537664 -1662121598997538560 -1662121599042539520 -1662121599090540544 -1662121599135541504 -1662121599183542528 -1662121599231543552 -1662121599279544576 -1662121599324545536 -1662121599369546496 -1662121599411547392 -1662121599456548352 -1662121599498549248 -1662121599543550208 -1662121599585551104 -1662121599633552128 -1662121599678553088 -1662121599717553920 -1662121599762554880 -1662121599807555840 -1662121599852556800 -1662121599894557696 -1662121599936558592 -1662121599984559616 -1662121600026560512 -1662121600071561472 -1662121600122562560 -1662121600179563776 -1662121600221564672 -1662121600263565568 -1662121600302566400 -1662121600350567424 -1662121600395568384 -1662121600437569280 -1662121600482570240 -1662121600536571392 -1662121600581572352 -1662121600623573248 -1662121600665574144 -1662121600710575104 -1662121600752576000 -1662121600806577152 -1662121600848578048 -1662121600890578944 -1662121600932579840 -1662121600974580736 -1662121601025581824 -1662121601070582784 -1662121601115583744 -1662121601157584640 -1662121601205585664 -1662121601247586560 -1662121601289587456 -1662121601337588480 -1662121601382589440 -1662121601433590528 -1662121601475591424 -1662121601517592320 -1662121601559593216 -1662121601604594176 -1662121601652595200 -1662121601697596160 -1662121601742597120 -1662121601784598016 -1662121601835599104 -1662121601880600064 -1662121601928601088 -1662121601970601984 -1662121602027603200 -1662121602075604224 -1662121602117605120 -1662121602162606080 -1662121602204606976 -1662121602255608064 -1662121602297608960 -1662121602336609792 -1662121602378610688 -1662121602426611712 -1662121602468612608 -1662121602519613696 -1662121602555614464 -1662121602600615424 -1662121602645616384 -1662121602699617536 -1662121602741618432 -1662121602783619328 -1662121602825620224 -1662121602867621120 -1662121602909622016 -1662121602951622912 -1662121602999623936 -1662121603047624960 -1662121603089625856 -1662121603140626944 -1662121603185627904 -1662121603227628800 -1662121603281629952 -1662121603326630912 -1662121603368631808 -1662121603422632960 -1662121603467633920 -1662121603509634816 -1662121603563635968 -1662121603608636928 -1662121603650637824 -1662121603692638720 -1662121603734639616 -1662121603776640512 -1662121603818641408 -1662121603860642304 -1662121603905643264 -1662121603953644288 -1662121604001645312 -1662121604043646208 -1662121604088647168 -1662121604133648128 -1662121604175649024 -1662121604217649920 -1662121604262650880 -1662121604307651840 -1662121604355652864 -1662121604394653696 -1662121604442654720 -1662121604484655616 -1662121604523656448 -1662121604574657536 -1662121604619658496 -1662121604664659456 -1662121604709660416 -1662121604754661376 -1662121604805662464 -1662121604850663424 -1662121604895664384 -1662121604940665344 -1662121604988666368 -1662121605042667520 -1662121605084668416 -1662121605129669376 -1662121605174670336 -1662121605216671232 -1662121605255672064 -1662121605300673024 -1662121605342673920 -1662121605396675072 -1662121605438675968 -1662121605480676864 -1662121605528677888 -1662121605573678848 -1662121605618679808 -1662121605663680768 -1662121605705681664 -1662121605747682560 -1662121605798683648 -1662121605840684544 -1662121605882685440 -1662121605930686464 -1662121605975687424 -1662121606017688320 -1662121606059689216 -1662121606104690176 -1662121606146691072 -1662121606188691968 -1662121606230692864 -1662121606275693824 -1662121606323694848 -1662121606368695808 -1662121606413696768 -1662121606455697664 -1662121606497698560 -1662121606542699520 -1662121606587700480 -1662121606626701312 -1662121606665702144 -1662121606710703104 -1662121606758704128 -1662121606803705088 -1662121606857706240 -1662121606902707200 -1662121606944708096 -1662121606986708992 -1662121607031709952 -1662121607076710912 -1662121607124711936 -1662121607169712896 -1662121607217713920 -1662121607262714880 -1662121607304715776 -1662121607346716672 -1662121607391717632 -1662121607436718592 -1662121607487719680 -1662121607532720640 -1662121607577721600 -1662121607628722688 -1662121607670723584 -1662121607715724544 -1662121607763725568 -1662121607805726464 -1662121607847727360 -1662121607889728256 -1662121607928729088 -1662121607970729984 -1662121608018731008 -1662121608060731904 -1662121608102732800 -1662121608147733760 -1662121608198734848 -1662121608246735872 -1662121608288736768 -1662121608333737728 -1662121608375738624 -1662121608426739712 -1662121608468740608 -1662121608510741504 -1662121608552742400 -1662121608597743360 -1662121608639744256 -1662121608681745152 -1662121608729746176 -1662121608777747200 -1662121608822748160 -1662121608867749120 -1662121608909750016 -1662121608951750912 -1662121609002752000 -1662121609044752896 -1662121609086753792 -1662121609134754816 -1662121609182755840 -1662121609230756864 -1662121609272757760 -1662121609317758720 -1662121609359759616 -1662121609398760448 -1662121609443761408 -1662121609491762432 -1662121609533763328 -1662121609575764224 -1662121609617765120 -1662121609662766080 -1662121609710767104 -1662121609755768064 -1662121609797768960 -1662121609839769856 -1662121609884770816 -1662121609935771904 -1662121609977772800 -1662121610022773760 -1662121610064774656 -1662121610106775552 -1662121610151776512 -1662121610196777472 -1662121610238778368 -1662121610292779520 -1662121610331780352 -1662121610382781440 -1662121610427782400 -1662121610469783296 -1662121610511784192 -1662121610559785216 -1662121610604786176 -1662121610646787072 -1662121610691788032 -1662121610733788928 -1662121610787790080 -1662121610832791040 -1662121610874791936 -1662121610922792960 -1662121610964793856 -1662121611006794752 -1662121611048795648 -1662121611096796672 -1662121611147797760 -1662121611198798848 -1662121611252800000 -1662121611294800896 -1662121611336801792 -1662121611381802752 -1662121611432803840 -1662121611474804736 -1662121611519805696 -1662121611561806592 -1662121611603807488 -1662121611651808512 -1662121611702809600 -1662121611747810560 -1662121611789811456 -1662121611834812416 -1662121611879813376 -1662121611927814400 -1662121611972815360 -1662121612017816320 -1662121612062817280 -1662121612107818240 -1662121612152819200 -1662121612194820096 -1662121612236820992 -1662121612278821888 -1662121612323822848 -1662121612368823808 -1662121612410824704 -1662121612449825536 -1662121612491826432 -1662121612548827648 -1662121612593828608 -1662121612635829504 -1662121612683830528 -1662121612731831552 -1662121612770832384 -1662121612818833408 -1662121612860834304 -1662121612902835200 -1662121612947836160 -1662121612989837056 -1662121613037838080 -1662121613082839040 -1662121613124839936 -1662121613166840832 -1662121613211841792 -1662121613259842816 -1662121613307843840 -1662121613349844736 -1662121613397845760 -1662121613442846720 -1662121613484847616 -1662121613526848512 -1662121613577849600 -1662121613625850624 -1662121613670851584 -1662121613724852736 -1662121613769853696 -1662121613817854720 -1662121613859855616 -1662121613907856640 -1662121613958857728 -1662121614009858816 -1662121614054859776 -1662121614096860672 -1662121614138861568 -1662121614177862400 -1662121614219863296 -1662121614267864320 -1662121614318865408 -1662121614360866304 -1662121614405867264 -1662121614450868224 -1662121614492869120 -1662121614540870144 -1662121614582871040 -1662121614630872064 -1662121614672872960 -1662121614720873984 -1662121614768875008 -1662121614816876032 -1662121614855876864 -1662121614897877760 -1662121614939878656 -1662121614987879680 -1662121615032880640 -1662121615077881600 -1662121615119882496 -1662121615164883456 -1662121615209884416 -1662121615254885376 -1662121615302886400 -1662121615350887424 -1662121615395888384 -1662121615443889408 -1662121615488890368 -1662121615530891264 -1662121615584892416 -1662121615626893312 -1662121615668894208 -1662121615707895040 -1662121615752896000 -1662121615800897024 -1662121615845897984 -1662121615896899072 -1662121615947900160 -1662121615992901120 -1662121616034902016 -1662121616079902976 -1662121616127904000 -1662121616178905088 -1662121616223906048 -1662121616268907008 -1662121616316908032 -1662121616358908928 -1662121616412910080 -1662121616463911168 -1662121616505912064 -1662121616547912960 -1662121616589913856 -1662121616634914816 -1662121616679915776 -1662121616727916800 -1662121616769917696 -1662121616823918848 -1662121616865919744 -1662121616913920768 -1662121616955921664 -1662121616997922560 -1662121617045923584 -1662121617087924480 -1662121617132925440 -1662121617177926400 -1662121617222927360 -1662121617264928256 -1662121617312929280 -1662121617360930304 -1662121617402931200 -1662121617444932096 -1662121617501933312 -1662121617543934208 -1662121617591935232 -1662121617639936256 -1662121617690937344 -1662121617741938432 -1662121617789939456 -1662121617831940352 -1662121617873941248 -1662121617918942208 -1662121617966943232 -1662121618014944256 -1662121618062945280 -1662121618104946176 -1662121618149947136 -1662121618200948224 -1662121618245949184 -1662121618287950080 -1662121618326950912 -1662121618368951808 -1662121618410952704 -1662121618452953600 -1662121618500954624 -1662121618545955584 -1662121618599956736 -1662121618641957632 -1662121618686958592 -1662121618728959488 -1662121618770960384 -1662121618815961344 -1662121618863962368 -1662121618905963264 -1662121618947964160 -1662121618992965120 -1662121619034966016 -1662121619079966976 -1662121619124967936 -1662121619166968832 -1662121619211969792 -1662121619253970688 -1662121619304971776 -1662121619346972672 -1662121619400973824 -1662121619442974720 -1662121619490975744 -1662121619535976704 -1662121619577977600 -1662121619619978496 -1662121619667979520 -1662121619706980352 -1662121619751981312 -1662121619802982400 -1662121619847983360 -1662121619892984320 -1662121619937985280 -1662121619979986176 -1662121620027987200 -1662121620075988224 -1662121620117989120 -1662121620162990080 -1662121620207991040 -1662121620252992000 -1662121620306993152 -1662121620351994112 -1662121620396995072 -1662121620438995968 -1662121620480996864 -1662121620525997824 -1662121620570998784 -1662121620615999744 -1662121620658000640 -1662121620703001600 -1662121620757002752 -1662121620799003648 -1662121620847004672 -1662121620892005632 -1662121620934006528 -1662121620976007424 -1662121621018008320 -1662121621060009216 -1662121621111010304 -1662121621159011328 -1662121621204012288 -1662121621246013184 -1662121621291014144 -1662121621330014976 -1662121621372015872 -1662121621414016768 -1662121621462017792 -1662121621507018752 -1662121621555019776 -1662121621594020608 -1662121621645021696 -1662121621687022592 -1662121621729023488 -1662121621774024448 -1662121621816025344 -1662121621861026304 -1662121621912027392 -1662121621957028352 -1662121622005029376 -1662121622050030336 -1662121622095031296 -1662121622137032192 -1662121622182033152 -1662121622227034112 -1662121622272035072 -1662121622323036160 -1662121622374037248 -1662121622413038080 -1662121622458039040 -1662121622503040000 -1662121622548040960 -1662121622593041920 -1662121622638042880 -1662121622686043904 -1662121622731044864 -1662121622773045760 -1662121622818046720 -1662121622863047680 -1662121622908048640 -1662121622953049600 -1662121623001050624 -1662121623049051648 -1662121623097052672 -1662121623148053760 -1662121623193054720 -1662121623238055680 -1662121623295056896 -1662121623340057856 -1662121623385058816 -1662121623427059712 -1662121623472060672 -1662121623514061568 -1662121623559062528 -1662121623604063488 -1662121623658064640 -1662121623700065536 -1662121623742066432 -1662121623784067328 -1662121623829068288 -1662121623877069312 -1662121623919070208 -1662121623961071104 -1662121624006072064 -1662121624051073024 -1662121624093073920 -1662121624135074816 -1662121624180075776 -1662121624225076736 -1662121624279077888 -1662121624324078848 -1662121624369079808 -1662121624411080704 -1662121624456081664 -1662121624498082560 -1662121624543083520 -1662121624594084608 -1662121624642085632 -1662121624687086592 -1662121624735087616 -1662121624780088576 -1662121624828089600 -1662121624879090688 -1662121624924091648 -1662121624966092544 -1662121625020093696 -1662121625065094656 -1662121625107095552 -1662121625152096512 -1662121625197097472 -1662121625239098368 -1662121625284099328 -1662121625335100416 -1662121625380101376 -1662121625425102336 -1662121625467103232 -1662121625512104192 -1662121625560105216 -1662121625608106240 -1662121625653107200 -1662121625698108160 -1662121625752109312 -1662121625797110272 -1662121625839111168 -1662121625887112192 -1662121625929113088 -1662121625977114112 -1662121626016114944 -1662121626058115840 -1662121626100116736 -1662121626148117760 -1662121626193118720 -1662121626241119744 -1662121626283120640 -1662121626325121536 -1662121626370122496 -1662121626412123392 -1662121626457124352 -1662121626502125312 -1662121626544126208 -1662121626589127168 -1662121626631128064 -1662121626673128960 -1662121626715129856 -1662121626760130816 -1662121626808131840 -1662121626859132928 -1662121626904133888 -1662121626952134912 -1662121626997135872 -1662121627042136832 -1662121627090137856 -1662121627135138816 -1662121627177139712 -1662121627228140800 -1662121627276141824 -1662121627318142720 -1662121627360143616 -1662121627405144576 -1662121627447145472 -1662121627498146560 -1662121627549147648 -1662121627597148672 -1662121627639149568 -1662121627690150656 -1662121627732151552 -1662121627774152448 -1662121627816153344 -1662121627858154240 -1662121627900155136 -1662121627942156032 -1662121627984156928 -1662121628029157888 -1662121628071158784 -1662121628119159808 -1662121628173160960 -1662121628212161792 -1662121628254162688 -1662121628299163648 -1662121628350164736 -1662121628398165760 -1662121628440166656 -1662121628488167680 -1662121628533168640 -1662121628581169664 -1662121628623170560 -1662121628671171584 -1662121628722172672 -1662121628770173696 -1662121628818174720 -1662121628860175616 -1662121628908176640 -1662121628953177600 -1662121629001178624 -1662121629049179648 -1662121629094180608 -1662121629145181696 -1662121629196182784 -1662121629244183808 -1662121629289184768 -1662121629331185664 -1662121629376186624 -1662121629424187648 -1662121629472188672 -1662121629517189632 -1662121629571190784 -1662121629616191744 -1662121629661192704 -1662121629703193600 -1662121629739194368 -1662121629787195392 -1662121629838196480 -1662121629883197440 -1662121629931198464 -1662121629973199360 -1662121630015200256 -1662121630057201152 -1662121630102202112 -1662121630153203200 -1662121630195204096 -1662121630237204992 -1662121630282205952 -1662121630324206848 -1662121630369207808 -1662121630423208960 -1662121630474210048 -1662121630525211136 -1662121630582212352 -1662121630621213184 -1662121630660214016 -1662121630702214912 -1662121630750215936 -1662121630792216832 -1662121630843217920 -1662121630885218816 -1662121630933219840 -1662121630975220736 -1662121631026221824 -1662121631068222720 -1662121631119223808 -1662121631167224832 -1662121631212225792 -1662121631254226688 -1662121631305227776 -1662121631347228672 -1662121631389229568 -1662121631431230464 -1662121631482231552 -1662121631530232576 -1662121631575233536 -1662121631620234496 -1662121631662235392 -1662121631707236352 -1662121631752237312 -1662121631800238336 -1662121631854239488 -1662121631896240384 -1662121631938241280 -1662121631983242240 -1662121632022243072 -1662121632064243968 -1662121632109244928 -1662121632154245888 -1662121632196246784 -1662121632244247808 -1662121632289248768 -1662121632334249728 -1662121632382250752 -1662121632424251648 -1662121632466252544 -1662121632508253440 -1662121632553254400 -1662121632598255360 -1662121632649256448 -1662121632697257472 -1662121632751258624 -1662121632793259520 -1662121632838260480 -1662121632883261440 -1662121632925262336 -1662121632976263424 -1662121633018264320 -1662121633066265344 -1662121633111266304 -1662121633159267328 -1662121633204268288 -1662121633246269184 -1662121633291270144 -1662121633339271168 -1662121633390272256 -1662121633435273216 -1662121633477274112 -1662121633519275008 -1662121633564275968 -1662121633609276928 -1662121633651277824 -1662121633696278784 -1662121633738279680 -1662121633786280704 -1662121633828281600 -1662121633876282624 -1662121633921283584 -1662121633963284480 -1662121634008285440 -1662121634050286336 -1662121634098287360 -1662121634143288320 -1662121634185289216 -1662121634233290240 -1662121634281291264 -1662121634320292096 -1662121634368293120 -1662121634422294272 -1662121634467295232 -1662121634515296256 -1662121634554297088 -1662121634602298112 -1662121634644299008 -1662121634692300032 -1662121634746301184 -1662121634797302272 -1662121634842303232 -1662121634884304128 -1662121634929305088 -1662121634980306176 -1662121635022307072 -1662121635073308160 -1662121635124309248 -1662121635169310208 -1662121635211311104 -1662121635262312192 -1662121635307313152 -1662121635349314048 -1662121635391314944 -1662121635436315904 -1662121635484316928 -1662121635526317824 -1662121635574318848 -1662121635622319872 -1662121635670320896 -1662121635724322048 -1662121635769323008 -1662121635811323904 -1662121635853324800 -1662121635901325824 -1662121635946326784 -1662121635991327744 -1662121636033328640 -1662121636078329600 -1662121636123330560 -1662121636174331648 -1662121636219332608 -1662121636267333632 -1662121636309334528 -1662121636351335424 -1662121636396336384 -1662121636438337280 -1662121636480338176 -1662121636525339136 -1662121636567340032 -1662121636609340928 -1662121636657341952 -1662121636702342912 -1662121636744343808 -1662121636789344768 -1662121636840345856 -1662121636894347008 -1662121636942348032 -1662121636987348992 -1662121637029349888 -1662121637074350848 -1662121637125351936 -1662121637170352896 -1662121637212353792 -1662121637254354688 -1662121637302355712 -1662121637350356736 -1662121637398357760 -1662121637443358720 -1662121637485359616 -1662121637533360640 -1662121637587361792 -1662121637632362752 -1662121637677363712 -1662121637719364608 -1662121637761365504 -1662121637803366400 -1662121637848367360 -1662121637887368192 -1662121637929369088 -1662121637974370048 -1662121638019371008 -1662121638061371904 -1662121638103372800 -1662121638145373696 -1662121638190374656 -1662121638232375552 -1662121638277376512 -1662121638319377408 -1662121638361378304 -1662121638406379264 -1662121638448380160 -1662121638490381056 -1662121638532381952 -1662121638574382848 -1662121638616383744 -1662121638655384576 -1662121638703385600 -1662121638748386560 -1662121638799387648 -1662121638841388544 -1662121638895389696 -1662121638937390592 -1662121638979391488 -1662121639024392448 -1662121639063393280 -1662121639105394176 -1662121639159395328 -1662121639204396288 -1662121639249397248 -1662121639300398336 -1662121639342399232 -1662121639387400192 -1662121639432401152 -1662121639477402112 -1662121639519403008 -1662121639564403968 -1662121639609404928 -1662121639651405824 -1662121639699406848 -1662121639750407936 -1662121639792408832 -1662121639834409728 -1662121639876410624 -1662121639924411648 -1662121639969412608 -1662121640011413504 -1662121640062414592 -1662121640113415680 -1662121640155416576 -1662121640197417472 -1662121640239418368 -1662121640284419328 -1662121640326420224 -1662121640371421184 -1662121640419422208 -1662121640464423168 -1662121640506424064 -1662121640554425088 -1662121640590425856 -1662121640644427008 -1662121640692428032 -1662121640737428992 -1662121640785430016 -1662121640824430848 -1662121640866431744 -1662121640911432704 -1662121640959433728 -1662121641004434688 -1662121641049435648 -1662121641091436544 -1662121641142437632 -1662121641193438720 -1662121641238439680 -1662121641283440640 -1662121641337441792 -1662121641379442688 -1662121641421443584 -1662121641463444480 -1662121641505445376 -1662121641550446336 -1662121641601447424 -1662121641643448320 -1662121641694449408 -1662121641739450368 -1662121641778451200 -1662121641823452160 -1662121641868453120 -1662121641907453952 -1662121641952454912 -1662121641997455872 -1662121642042456832 -1662121642090457856 -1662121642132458752 -1662121642174459648 -1662121642219460608 -1662121642264461568 -1662121642312462592 -1662121642354463488 -1662121642399464448 -1662121642441465344 -1662121642483466240 -1662121642528467200 -1662121642570468096 -1662121642612468992 -1662121642660470016 -1662121642705470976 -1662121642747471872 -1662121642801473024 -1662121642843473920 -1662121642891474944 -1662121642939475968 -1662121642981476864 -1662121643023477760 -1662121643065478656 -1662121643107479552 -1662121643149480448 -1662121643191481344 -1662121643233482240 -1662121643275483136 -1662121643317484032 -1662121643362484992 -1662121643410486016 -1662121643455486976 -1662121643503488000 -1662121643542488832 -1662121643587489792 -1662121643629490688 -1662121643674491648 -1662121643719492608 -1662121643764493568 -1662121643806494464 -1662121643845495296 -1662121643887496192 -1662121643932497152 -1662121643983498240 -1662121644034499328 -1662121644079500288 -1662121644121501184 -1662121644160502016 -1662121644208503040 -1662121644250503936 -1662121644295504896 -1662121644337505792 -1662121644385506816 -1662121644433507840 -1662121644478508800 -1662121644526509824 -1662121644568510720 -1662121644613511680 -1662121644658512640 -1662121644706513664 -1662121644748514560 -1662121644799515648 -1662121644853516800 -1662121644898517760 -1662121644940518656 -1662121644988519680 -1662121645033520640 -1662121645078521600 -1662121645120522496 -1662121645162523392 -1662121645210524416 -1662121645252525312 -1662121645300526336 -1662121645342527232 -1662121645384528128 -1662121645426529024 -1662121645468529920 -1662121645510530816 -1662121645561531904 -1662121645603532800 -1662121645645533696 -1662121645690534656 -1662121645735535616 -1662121645780536576 -1662121645825537536 -1662121645870538496 -1662121645912539392 -1662121645957540352 -1662121646005541376 -1662121646053542400 -1662121646107543552 -1662121646149544448 -1662121646197545472 -1662121646239546368 -1662121646281547264 -1662121646329548288 -1662121646371549184 -1662121646419550208 -1662121646470551296 -1662121646521552384 -1662121646566553344 -1662121646611554304 -1662121646653555200 -1662121646698556160 -1662121646737556992 -1662121646779557888 -1662121646824558848 -1662121646869559808 -1662121646911560704 -1662121646956561664 -1662121646998562560 -1662121647040563456 -1662121647085564416 -1662121647127565312 -1662121647172566272 -1662121647214567168 -1662121647262568192 -1662121647304569088 -1662121647352570112 -1662121647400571136 -1662121647451572224 -1662121647496573184 -1662121647547574272 -1662121647589575168 -1662121647634576128 -1662121647676577024 -1662121647727578112 -1662121647784579328 -1662121647832580352 -1662121647874581248 -1662121647931582464 -1662121647973583360 -1662121648015584256 -1662121648069585408 -1662121648114586368 -1662121648156587264 -1662121648198588160 -1662121648240589056 -1662121648288590080 -1662121648336591104 -1662121648393592320 -1662121648435593216 -1662121648477594112 -1662121648519595008 -1662121648573596160 -1662121648627597312 -1662121648678598400 -1662121648723599360 -1662121648768600320 -1662121648813601280 -1662121648852602112 -1662121648894603008 -1662121648939603968 -1662121648981604864 -1662121649023605760 -1662121649080606976 -1662121649125607936 -1662121649167608832 -1662121649209609728 -1662121649251610624 -1662121649302611712 -1662121649341612544 -1662121649392613632 -1662121649437614592 -1662121649479615488 -1662121649521616384 -1662121649569617408 -1662121649614618368 -1662121649653619200 -1662121649692620032 -1662121649740621056 -1662121649785622016 -1662121649830622976 -1662121649875623936 -1662121649920624896 -1662121649971625984 -1662121650013626880 -1662121650058627840 -1662121650106628864 -1662121650148629760 -1662121650193630720 -1662121650241631744 -1662121650286632704 -1662121650331633664 -1662121650376634624 -1662121650424635648 -1662121650466636544 -1662121650517637632 -1662121650559638528 -1662121650601639424 -1662121650646640384 -1662121650688641280 -1662121650730642176 -1662121650772643072 -1662121650823644160 -1662121650868645120 -1662121650910646016 -1662121650952646912 -1662121651000647936 -1662121651042648832 -1662121651087649792 -1662121651129650688 -1662121651171651584 -1662121651213652480 -1662121651255653376 -1662121651300654336 -1662121651345655296 -1662121651384656128 -1662121651429657088 -1662121651477658112 -1662121651525659136 -1662121651573660160 -1662121651618661120 -1662121651669662208 -1662121651714663168 -1662121651765664256 -1662121651816665344 -1662121651864666368 -1662121651909667328 -1662121651951668224 -1662121652002669312 -1662121652050670336 -1662121652101671424 -1662121652143672320 -1662121652188673280 -1662121652236674304 -1662121652284675328 -1662121652335676416 -1662121652377677312 -1662121652425678336 -1662121652479679488 -1662121652521680384 -1662121652560681216 -1662121652608682240 -1662121652665683456 -1662121652707684352 -1662121652749685248 -1662121652791686144 -1662121652839687168 -1662121652881688064 -1662121652923688960 -1662121652971689984 -1662121653013690880 -1662121653055691776 -1662121653100692736 -1662121653142693632 -1662121653184694528 -1662121653229695488 -1662121653271696384 -1662121653319697408 -1662121653358698240 -1662121653403699200 -1662121653445700096 -1662121653487700992 -1662121653532701952 -1662121653577702912 -1662121653625703936 -1662121653670704896 -1662121653712705792 -1662121653754706688 -1662121653799707648 -1662121653841708544 -1662121653883709440 -1662121653934710528 -1662121653979711488 -1662121654024712448 -1662121654066713344 -1662121654108714240 -1662121654162715392 -1662121654210716416 -1662121654252717312 -1662121654300718336 -1662121654342719232 -1662121654387720192 -1662121654432721152 -1662121654471721984 -1662121654519723008 -1662121654564723968 -1662121654606724864 -1662121654657725952 -1662121654696726784 -1662121654738727680 -1662121654789728768 -1662121654831729664 -1662121654876730624 -1662121654918731520 -1662121654963732480 -1662121655002733312 -1662121655044734208 -1662121655086735104 -1662121655131736064 -1662121655176737024 -1662121655221737984 -1662121655278739200 -1662121655323740160 -1662121655365741056 -1662121655410742016 -1662121655455742976 -1662121655500743936 -1662121655539744768 -1662121655596745984 -1662121655638746880 -1662121655680747776 -1662121655722748672 -1662121655764749568 -1662121655806750464 -1662121655848751360 -1662121655893752320 -1662121655935753216 -1662121655977754112 -1662121656028755200 -1662121656073756160 -1662121656124757248 -1662121656172758272 -1662121656214759168 -1662121656262760192 -1662121656307761152 -1662121656355762176 -1662121656403763200 -1662121656445764096 -1662121656493765120 -1662121656544766208 -1662121656589767168 -1662121656631768064 -1662121656670768896 -1662121656715769856 -1662121656757770752 -1662121656805771776 -1662121656859772928 -1662121656901773824 -1662121656949774848 -1662121656991775744 -1662121657033776640 -1662121657075777536 -1662121657123778560 -1662121657168779520 -1662121657210780416 -1662121657258781440 -1662121657312782592 -1662121657360783616 -1662121657405784576 -1662121657453785600 -1662121657501786624 -1662121657546787584 -1662121657591788544 -1662121657636789504 -1662121657681790464 -1662121657723791360 -1662121657768792320 -1662121657813793280 -1662121657852794112 -1662121657897795072 -1662121657939795968 -1662121657984796928 -1662121658026797824 -1662121658068798720 -1662121658113799680 -1662121658158800640 -1662121658200801536 -1662121658254802688 -1662121658302803712 -1662121658350804736 -1662121658404805888 -1662121658446806784 -1662121658491807744 -1662121658536808704 -1662121658575809536 -1662121658626810624 -1662121658668811520 -1662121658716812544 -1662121658758813440 -1662121658809814528 -1662121658851815424 -1662121658905816576 -1662121658947817472 -1662121658989818368 -1662121659031819264 -1662121659076820224 -1662121659121821184 -1662121659166822144 -1662121659208823040 -1662121659253824000 -1662121659307825152 -1662121659361826304 -1662121659406827264 -1662121659454828288 -1662121659502829312 -1662121659547830272 -1662121659589831168 -1662121659640832256 -1662121659685833216 -1662121659739834368 -1662121659787835392 -1662121659835836416 -1662121659880837376 -1662121659925838336 -1662121659970839296 -1662121660012840192 -1662121660063841280 -1662121660108842240 -1662121660150843136 -1662121660195844096 -1662121660240845056 -1662121660288846080 -1662121660339847168 -1662121660387848192 -1662121660429849088 -1662121660474850048 -1662121660528851200 -1662121660570852096 -1662121660615853056 -1662121660657853952 -1662121660702854912 -1662121660747855872 -1662121660798856960 -1662121660840857856 -1662121660882858752 -1662121660924859648 -1662121660972860672 -1662121661020861696 -1662121661062862592 -1662121661104863488 -1662121661152864512 -1662121661197865472 -1662121661239866368 -1662121661284867328 -1662121661329868288 -1662121661374869248 -1662121661422870272 -1662121661470871296 -1662121661512872192 -1662121661557873152 -1662121661605874176 -1662121661650875136 -1662121661698876160 -1662121661740877056 -1662121661782877952 -1662121661833879040 -1662121661887880192 -1662121661929881088 -1662121661974882048 -1662121662013882880 -1662121662055883776 -1662121662103884800 -1662121662148885760 -1662121662190886656 -1662121662232887552 -1662121662283888640 -1662121662328889600 -1662121662370890496 -1662121662418891520 -1662121662463892480 -1662121662511893504 -1662121662556894464 -1662121662604895488 -1662121662649896448 -1662121662688897280 -1662121662736898304 -1662121662778899200 -1662121662823900160 -1662121662868901120 -1662121662913902080 -1662121662958903040 -1662121663006904064 -1662121663051905024 -1662121663102906112 -1662121663147907072 -1662121663195908096 -1662121663243909120 -1662121663282909952 -1662121663324910848 -1662121663366911744 -1662121663414912768 -1662121663459913728 -1662121663504914688 -1662121663549915648 -1662121663597916672 -1662121663639917568 -1662121663681918464 -1662121663723919360 -1662121663765920256 -1662121663810921216 -1662121663855922176 -1662121663903923200 -1662121663948924160 -1662121663993925120 -1662121664035926016 -1662121664089927168 -1662121664134928128 -1662121664182929152 -1662121664224930048 -1662121664272931072 -1662121664320932096 -1662121664365933056 -1662121664413934080 -1662121664461935104 -1662121664512936192 -1662121664554937088 -1662121664596937984 -1662121664647939072 -1662121664701940224 -1662121664752941312 -1662121664809942528 -1662121664854943488 -1662121664899944448 -1662121664941945344 -1662121664983946240 -1662121665037947392 -1662121665079948288 -1662121665121949184 -1662121665163950080 -1662121665214951168 -1662121665262952192 -1662121665307953152 -1662121665355954176 -1662121665400955136 -1662121665445956096 -1662121665502957312 -1662121665547958272 -1662121665592959232 -1662121665640960256 -1662121665685961216 -1662121665730962176 -1662121665772963072 -1662121665817964032 -1662121665856964864 -1662121665904965888 -1662121665946966784 -1662121665988967680 -1662121666030968576 -1662121666078969600 -1662121666120970496 -1662121666162971392 -1662121666210972416 -1662121666255973376 -1662121666297974272 -1662121666345975296 -1662121666390976256 -1662121666432977152 -1662121666474978048 -1662121666519979008 -1662121666567980032 -1662121666612980992 -1662121666666982144 -1662121666705982976 -1662121666756984064 -1662121666801985024 -1662121666858986240 -1662121666900987136 -1662121666942988032 -1662121666987988992 -1662121667041990144 -1662121667089991168 -1662121667137992192 -1662121667185993216 -1662121667230994176 -1662121667275995136 -1662121667320996096 -1662121667362996992 -1662121667410998016 -1662121667455998976 -1662121667500999936 -1662121667546000896 -1662121667594001920 -1662121667642002944 -1662121667687003904 -1662121667729004800 -1662121667771005696 -1662121667816006656 -1662121667861007616 -1662121667903008512 -1662121667957009664 -1662121667999010560 -1662121668041011456 -1662121668089012480 -1662121668134013440 -1662121668179014400 -1662121668224015360 -1662121668278016512 -1662121668323017472 -1662121668374018560 -1662121668413019392 -1662121668458020352 -1662121668500021248 -1662121668539022080 -1662121668581022976 -1662121668626023936 -1662121668668024832 -1662121668710025728 -1662121668752026624 -1662121668797027584 -1662121668842028544 -1662121668884029440 -1662121668926030336 -1662121668974031360 -1662121669019032320 -1662121669061033216 -1662121669103034112 -1662121669154035200 -1662121669199036160 -1662121669241037056 -1662121669283037952 -1662121669325038848 -1662121669367039744 -1662121669409040640 -1662121669454041600 -1662121669511042816 -1662121669556043776 -1662121669595044608 -1662121669634045440 -1662121669673046272 -1662121669715047168 -1662121669760048128 -1662121669802049024 -1662121669856050176 -1662121669901051136 -1662121669943052032 -1662121669988052992 -1662121670036054016 -1662121670081054976 -1662121670123055872 -1662121670165056768 -1662121670219057920 -1662121670267058944 -1662121670315059968 -1662121670360060928 -1662121670411062016 -1662121670456062976 -1662121670507064064 -1662121670561065216 -1662121670606066176 -1662121670654067200 -1662121670699068160 -1662121670753069312 -1662121670789070080 -1662121670831070976 -1662121670873071872 -1662121670921072896 -1662121670963073792 -1662121671005074688 -1662121671047075584 -1662121671089076480 -1662121671137077504 -1662121671179078400 -1662121671221079296 -1662121671263080192 -1662121671317081344 -1662121671359082240 -1662121671401083136 -1662121671443084032 -1662121671485084928 -1662121671536086016 -1662121671578086912 -1662121671620087808 -1662121671671088896 -1662121671713089792 -1662121671758090752 -1662121671800091648 -1662121671842092544 -1662121671893093632 -1662121671935094528 -1662121671977095424 -1662121672025096448 -1662121672073097472 -1662121672115098368 -1662121672157099264 -1662121672208100352 -1662121672259101440 -1662121672304102400 -1662121672349103360 -1662121672394104320 -1662121672436105216 -1662121672484106240 -1662121672526107136 -1662121672574108160 -1662121672616109056 -1662121672664110080 -1662121672709111040 -1662121672754112000 -1662121672799112960 -1662121672841113856 -1662121672886114816 -1662121672934115840 -1662121672985116928 -1662121673027117824 -1662121673066118656 -1662121673111119616 -1662121673159120640 -1662121673204121600 -1662121673243122432 -1662121673288123392 -1662121673339124480 -1662121673387125504 -1662121673435126528 -1662121673489127680 -1662121673537128704 -1662121673582129664 -1662121673639130880 -1662121673681131776 -1662121673726132736 -1662121673768133632 -1662121673819134720 -1662121673861135616 -1662121673906136576 -1662121673963137792 -1662121674002138624 -1662121674050139648 -1662121674092140544 -1662121674137141504 -1662121674182142464 -1662121674230143488 -1662121674275144448 -1662121674323145472 -1662121674365146368 -1662121674413147392 -1662121674458148352 -1662121674500149248 -1662121674542150144 -1662121674587151104 -1662121674629152000 -1662121674674152960 -1662121674719153920 -1662121674767154944 -1662121674818156032 -1662121674863156992 -1662121674917158144 -1662121674959159040 -1662121675007160064 -1662121675046160896 -1662121675094161920 -1662121675136162816 -1662121675178163712 -1662121675226164736 -1662121675268165632 -1662121675313166592 -1662121675355167488 -1662121675400168448 -1662121675445169408 -1662121675493170432 -1662121675535171328 -1662121675580172288 -1662121675625173248 -1662121675667174144 -1662121675709175040 -1662121675751175936 -1662121675799176960 -1662121675847177984 -1662121675892178944 -1662121675937179904 -1662121675979180800 -1662121676021181696 -1662121676066182656 -1662121676108183552 -1662121676153184512 -1662121676207185664 -1662121676249186560 -1662121676294187520 -1662121676339188480 -1662121676387189504 -1662121676432190464 -1662121676474191360 -1662121676519192320 -1662121676567193344 -1662121676621194496 -1662121676666195456 -1662121676708196352 -1662121676756197376 -1662121676798198272 -1662121676852199424 -1662121676903200512 -1662121676948201472 -1662121676993202432 -1662121677035203328 -1662121677083204352 -1662121677134205440 -1662121677188206592 -1662121677236207616 -1662121677278208512 -1662121677317209344 -1662121677365210368 -1662121677407211264 -1662121677449212160 -1662121677491213056 -1662121677533213952 -1662121677575214848 -1662121677617215744 -1662121677659216640 -1662121677701217536 -1662121677743218432 -1662121677785219328 -1662121677827220224 -1662121677869221120 -1662121677914222080 -1662121677956222976 -1662121678004224000 -1662121678055225088 -1662121678094225920 -1662121678136226816 -1662121678187227904 -1662121678229228800 -1662121678274229760 -1662121678319230720 -1662121678367231744 -1662121678412232704 -1662121678469233920 -1662121678520235008 -1662121678565235968 -1662121678607236864 -1662121678649237760 -1662121678691238656 -1662121678733239552 -1662121678775240448 -1662121678817241344 -1662121678862242304 -1662121678907243264 -1662121678952244224 -1662121679009245440 -1662121679051246336 -1662121679093247232 -1662121679138248192 -1662121679186249216 -1662121679228250112 -1662121679273251072 -1662121679321252096 -1662121679372253184 -1662121679420254208 -1662121679462255104 -1662121679504256000 -1662121679549256960 -1662121679594257920 -1662121679639258880 -1662121679684259840 -1662121679729260800 -1662121679768261632 -1662121679810262528 -1662121679861263616 -1662121679903264512 -1662121679948265472 -1662121679996266496 -1662121680035267328 -1662121680080268288 -1662121680125269248 -1662121680167270144 -1662121680218271232 -1662121680263272192 -1662121680305273088 -1662121680347273984 -1662121680392274944 -1662121680437275904 -1662121680479276800 -1662121680530277888 -1662121680578278912 -1662121680629280000 -1662121680671280896 -1662121680713281792 -1662121680761282816 -1662121680803283712 -1662121680851284736 -1662121680896285696 -1662121680935286528 -1662121680974287360 -1662121681016288256 -1662121681064289280 -1662121681109290240 -1662121681157291264 -1662121681208292352 -1662121681250293248 -1662121681295294208 -1662121681340295168 -1662121681391296256 -1662121681436297216 -1662121681484298240 -1662121681535299328 -1662121681577300224 -1662121681622301184 -1662121681673302272 -1662121681724303360 -1662121681772304384 -1662121681817305344 -1662121681862306304 -1662121681910307328 -1662121681958308352 -1662121682000309248 -1662121682048310272 -1662121682090311168 -1662121682132312064 -1662121682180313088 -1662121682225314048 -1662121682270315008 -1662121682321316096 -1662121682369317120 -1662121682417318144 -1662121682459319040 -1662121682504320000 -1662121682546320896 -1662121682597321984 -1662121682639322880 -1662121682684323840 -1662121682735324928 -1662121682789326080 -1662121682831326976 -1662121682873327872 -1662121682921328896 -1662121682966329856 -1662121683014330880 -1662121683062331904 -1662121683107332864 -1662121683161334016 -1662121683203334912 -1662121683248335872 -1662121683296336896 -1662121683341337856 -1662121683386338816 -1662121683434339840 -1662121683482340864 -1662121683527341824 -1662121683575342848 -1662121683623343872 -1662121683668344832 -1662121683713345792 -1662121683761346816 -1662121683806347776 -1662121683848348672 -1662121683899349760 -1662121683941350656 -1662121683983351552 -1662121684025352448 -1662121684067353344 -1662121684109354240 -1662121684157355264 -1662121684202356224 -1662121684250357248 -1662121684298358272 -1662121684346359296 -1662121684391360256 -1662121684433361152 -1662121684475362048 -1662121684517362944 -1662121684562363904 -1662121684616365056 -1662121684661366016 -1662121684703366912 -1662121684754368000 -1662121684799368960 -1662121684850370048 -1662121684898371072 -1662121684940371968 -1662121684997373184 -1662121685036374016 -1662121685081374976 -1662121685123375872 -1662121685171376896 -1662121685228378112 -1662121685282379264 -1662121685330380288 -1662121685375381248 -1662121685420382208 -1662121685468383232 -1662121685510384128 -1662121685561385216 -1662121685609386240 -1662121685651387136 -1662121685693388032 -1662121685738388992 -1662121685783389952 -1662121685834391040 -1662121685897392384 -1662121685948393472 -1662121685993394432 -1662121686044395520 -1662121686086396416 -1662121686131397376 -1662121686176398336 -1662121686215399168 -1662121686260400128 -1662121686305401088 -1662121686353402112 -1662121686404403200 -1662121686449404160 -1662121686491405056 -1662121686533405952 -1662121686575406848 -1662121686626407936 -1662121686668408832 -1662121686716409856 -1662121686767410944 -1662121686812411904 -1662121686854412800 -1662121686899413760 -1662121686941414656 -1662121686992415744 -1662121687040416768 -1662121687085417728 -1662121687133418752 -1662121687175419648 -1662121687217420544 -1662121687265421568 -1662121687307422464 -1662121687352423424 -1662121687397424384 -1662121687445425408 -1662121687490426368 -1662121687532427264 -1662121687574428160 -1662121687619429120 -1662121687664430080 -1662121687709431040 -1662121687751431936 -1662121687793432832 -1662121687832433664 -1662121687880434688 -1662121687928435712 -1662121687970436608 -1662121688018437632 -1662121688069438720 -1662121688126439936 -1662121688171440896 -1662121688216441856 -1662121688258442752 -1662121688303443712 -1662121688345444608 -1662121688387445504 -1662121688429446400 -1662121688474447360 -1662121688522448384 -1662121688570449408 -1662121688609450240 -1662121688651451136 -1662121688705452288 -1662121688747453184 -1662121688795454208 -1662121688840455168 -1662121688885456128 -1662121688924456960 -1662121688975458048 -1662121689017458944 -1662121689059459840 -1662121689101460736 -1662121689149461760 -1662121689194462720 -1662121689239463680 -1662121689287464704 -1662121689329465600 -1662121689380466688 -1662121689422467584 -1662121689467468544 -1662121689509469440 -1662121689554470400 -1662121689602471424 -1662121689644472320 -1662121689686473216 -1662121689734474240 -1662121689773475072 -1662121689812475904 -1662121689857476864 -1662121689908477952 -1662121689950478848 -1662121689995479808 -1662121690046480896 -1662121690094481920 -1662121690139482880 -1662121690178483712 -1662121690220484608 -1662121690268485632 -1662121690313486592 -1662121690361487616 -1662121690403488512 -1662121690454489600 -1662121690496490496 -1662121690538491392 -1662121690583492352 -1662121690625493248 -1662121690673494272 -1662121690721495296 -1662121690766496256 -1662121690805497088 -1662121690850498048 -1662121690892498944 -1662121690934499840 -1662121690976500736 -1662121691027501824 -1662121691072502784 -1662121691114503680 -1662121691156504576 -1662121691201505536 -1662121691246506496 -1662121691297507584 -1662121691342508544 -1662121691384509440 -1662121691429510400 -1662121691471511296 -1662121691522512384 -1662121691564513280 -1662121691612514304 -1662121691660515328 -1662121691705516288 -1662121691747517184 -1662121691792518144 -1662121691834519040 -1662121691885520128 -1662121691927521024 -1662121691969521920 -1662121692023523072 -1662121692068524032 -1662121692125525248 -1662121692182526464 -1662121692224527360 -1662121692266528256 -1662121692311529216 -1662121692359530240 -1662121692407531264 -1662121692449532160 -1662121692491533056 -1662121692545534208 -1662121692593535232 -1662121692644536320 -1662121692686537216 -1662121692731538176 -1662121692779539200 -1662121692818540032 -1662121692866541056 -1662121692911542016 -1662121692956542976 -1662121692998543872 -1662121693046544896 -1662121693097545984 -1662121693139546880 -1662121693184547840 -1662121693229548800 -1662121693277549824 -1662121693322550784 -1662121693364551680 -1662121693409552640 -1662121693457553664 -1662121693502554624 -1662121693547555584 -1662121693589556480 -1662121693634557440 -1662121693673558272 -1662121693718559232 -1662121693763560192 -1662121693805561088 -1662121693847561984 -1662121693895563008 -1662121693937563904 -1662121693982564864 -1662121694033565952 -1662121694081566976 -1662121694132568064 -1662121694177569024 -1662121694219569920 -1662121694267570944 -1662121694312571904 -1662121694360572928 -1662121694408573952 -1662121694462575104 -1662121694507576064 -1662121694549576960 -1662121694594577920 -1662121694636578816 -1662121694678579712 -1662121694729580800 -1662121694771581696 -1662121694822582784 -1662121694864583680 -1662121694909584640 -1662121694951585536 -1662121695002586624 -1662121695047587584 -1662121695089588480 -1662121695137589504 -1662121695185590528 -1662121695227591424 -1662121695269592320 -1662121695311593216 -1662121695353594112 -1662121695398595072 -1662121695449596160 -1662121695491597056 -1662121695548598272 -1662121695593599232 -1662121695638600192 -1662121695683601152 -1662121695725602048 -1662121695767602944 -1662121695809603840 -1662121695854604800 -1662121695896605696 -1662121695947606784 -1662121695998607872 -1662121696046608896 -1662121696091609856 -1662121696151611136 -1662121696202612224 -1662121696250613248 -1662121696298614272 -1662121696340615168 -1662121696385616128 -1662121696433617152 -1662121696478618112 -1662121696526619136 -1662121696571620096 -1662121696616621056 -1662121696661622016 -1662121696709623040 -1662121696757624064 -1662121696802625024 -1662121696847625984 -1662121696889626880 -1662121696943628032 -1662121696985628928 -1662121697036630016 -1662121697084631040 -1662121697123631872 -1662121697171632896 -1662121697219633920 -1662121697267634944 -1662121697312635904 -1662121697354636800 -1662121697399637760 -1662121697441638656 -1662121697489639680 -1662121697534640640 -1662121697582641664 -1662121697633642752 -1662121697678643712 -1662121697732644864 -1662121697780645888 -1662121697831646976 -1662121697873647872 -1662121697915648768 -1662121697960649728 -1662121698005650688 -1662121698047651584 -1662121698098652672 -1662121698143653632 -1662121698191654656 -1662121698242655744 -1662121698287656704 -1662121698329657600 -1662121698371658496 -1662121698413659392 -1662121698458660352 -1662121698506661376 -1662121698554662400 -1662121698602663424 -1662121698647664384 -1662121698689665280 -1662121698737666304 -1662121698782667264 -1662121698827668224 -1662121698866669056 -1662121698914670080 -1662121698959671040 -1662121699004672000 -1662121699049672960 -1662121699094673920 -1662121699136674816 -1662121699181675776 -1662121699226676736 -1662121699268677632 -1662121699310678528 -1662121699358679552 -1662121699400680448 -1662121699445681408 -1662121699487682304 -1662121699532683264 -1662121699577684224 -1662121699622685184 -1662121699667686144 -1662121699709687040 -1662121699763688192 -1662121699814689280 -1662121699856690176 -1662121699898691072 -1662121699946692096 -1662121700003693312 -1662121700048694272 -1662121700096695296 -1662121700138696192 -1662121700177697024 -1662121700219697920 -1662121700267698944 -1662121700312699904 -1662121700357700864 -1662121700408701952 -1662121700453702912 -1662121700495703808 -1662121700546704896 -1662121700597705984 -1662121700642706944 -1662121700684707840 -1662121700729708800 -1662121700774709760 -1662121700816710656 -1662121700864711680 -1662121700906712576 -1662121700960713728 -1662121701011714816 -1662121701053715712 -1662121701095716608 -1662121701140717568 -1662121701191718656 -1662121701233719552 -1662121701278720512 -1662121701326721536 -1662121701371722496 -1662121701413723392 -1662121701461724416 -1662121701503725312 -1662121701545726208 -1662121701584727040 -1662121701629728000 -1662121701677729024 -1662121701722729984 -1662121701770731008 -1662121701812731904 -1662121701857732864 -1662121701902733824 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor/track0/SeaFloor_track0.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor/track0/SeaFloor_track0.txt deleted file mode 100644 index d40335079d..0000000000 --- a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor/track0/SeaFloor_track0.txt +++ /dev/null @@ -1,2847 +0,0 @@ -1661868173547958016 -1661868173589958912 -1661868173628959744 -1661868173676960768 -1661868173715961600 -1661868173760962560 -1661868173802963456 -1661868173844964352 -1661868173886965248 -1661868173931966208 -1661868173973967104 -1661868174021968128 -1661868174063969024 -1661868174105969920 -1661868174147970816 -1661868174183971584 -1661868174225972480 -1661868174264973312 -1661868174306974208 -1661868174354975232 -1661868174399976192 -1661868174441977088 -1661868174483977984 -1661868174525978880 -1661868174564979712 -1661868174603980544 -1661868174645981440 -1661868174693982464 -1661868174735983360 -1661868174780984320 -1661868174828985344 -1661868174870986240 -1661868174912987136 -1661868174960988160 -1661868175002989056 -1661868175044989952 -1661868175086990848 -1661868175128991744 -1661868175170992640 -1661868175209993472 -1661868175251994368 -1661868175302995456 -1661868175341996288 -1661868175383997184 -1661868175425998080 -1661868175470999040 -1661868175509999872 -1661868175549000704 -1661868175591001600 -1661868175639002624 -1661868175681003520 -1661868175723004416 -1661868175765005312 -1661868175810006272 -1661868175849007104 -1661868175897008128 -1661868175939009024 -1661868175981009920 -1661868176029010944 -1661868176071011840 -1661868176113012736 -1661868176152013568 -1661868176197014528 -1661868176242015488 -1661868176284016384 -1661868176323017216 -1661868176368018176 -1661868176410019072 -1661868176452019968 -1661868176497020928 -1661868176536021760 -1661868176578022656 -1661868176617023488 -1661868176659024384 -1661868176701025280 -1661868176743026176 -1661868176785027072 -1661868176824027904 -1661868176869028864 -1661868176914029824 -1661868176953030656 -1661868176992031488 -1661868177034032384 -1661868177076033280 -1661868177118034176 -1661868177163035136 -1661868177208036096 -1661868177244036864 -1661868177283037696 -1661868177325038592 -1661868177367039488 -1661868177409040384 -1661868177451041280 -1661868177493042176 -1661868177535043072 -1661868177580044032 -1661868177625044992 -1661868177670045952 -1661868177712046848 -1661868177748047616 -1661868177793048576 -1661868177838049536 -1661868177877050368 -1661868177916051200 -1661868177958052096 -1661868178003053056 -1661868178048054016 -1661868178090054912 -1661868178132055808 -1661868178171056640 -1661868178207057408 -1661868178249058304 -1661868178297059328 -1661868178339060224 -1661868178384061184 -1661868178426062080 -1661868178468062976 -1661868178510063872 -1661868178546064640 -1661868178588065536 -1661868178630066432 -1661868178669067264 -1661868178711068160 -1661868178759069184 -1661868178804070144 -1661868178846071040 -1661868178888071936 -1661868178930072832 -1661868178972073728 -1661868179014074624 -1661868179059075584 -1661868179107076608 -1661868179152077568 -1661868179191078400 -1661868179233079296 -1661868179278080256 -1661868179320081152 -1661868179362082048 -1661868179407083008 -1661868179452083968 -1661868179494084864 -1661868179539085824 -1661868179581086720 -1661868179623087616 -1661868179665088512 -1661868179713089536 -1661868179758090496 -1661868179803091456 -1661868179845092352 -1661868179887093248 -1661868179926094080 -1661868179968094976 -1661868180010095872 -1661868180049096704 -1661868180088097536 -1661868180130098432 -1661868180175099392 -1661868180217100288 -1661868180256101120 -1661868180298102016 -1661868180340102912 -1661868180385103872 -1661868180427104768 -1661868180466105600 -1661868180508106496 -1661868180550107392 -1661868180589108224 -1661868180628109056 -1661868180670109952 -1661868180715110912 -1661868180760111872 -1661868180802112768 -1661868180844113664 -1661868180886114560 -1661868180922115328 -1661868180967116288 -1661868181009117184 -1661868181051118080 -1661868181090118912 -1661868181132119808 -1661868181174120704 -1661868181216121600 -1661868181258122496 -1661868181303123456 -1661868181348124416 -1661868181387125248 -1661868181432126208 -1661868181474127104 -1661868181516128000 -1661868181558128896 -1661868181597129728 -1661868181636130560 -1661868181678131456 -1661868181720132352 -1661868181762133248 -1661868181804134144 -1661868181846135040 -1661868181885135872 -1661868181927136768 -1661868181966137600 -1661868182008138496 -1661868182050139392 -1661868182095140352 -1661868182140141312 -1661868182182142208 -1661868182221143040 -1661868182263143936 -1661868182302144768 -1661868182344145664 -1661868182386146560 -1661868182428147456 -1661868182464148224 -1661868182506149120 -1661868182551150080 -1661868182590150912 -1661868182635151872 -1661868182677152768 -1661868182716153600 -1661868182758154496 -1661868182800155392 -1661868182839156224 -1661868182884157184 -1661868182926158080 -1661868182971159040 -1661868183010159872 -1661868183049160704 -1661868183091161600 -1661868183130162432 -1661868183172163328 -1661868183214164224 -1661868183256165120 -1661868183298166016 -1661868183340166912 -1661868183382167808 -1661868183427168768 -1661868183469169664 -1661868183511170560 -1661868183550171392 -1661868183595172352 -1661868183637173248 -1661868183679174144 -1661868183718174976 -1661868183769176064 -1661868183811176960 -1661868183850177792 -1661868183892178688 -1661868183931179520 -1661868183973180416 -1661868184018181376 -1661868184060182272 -1661868184102183168 -1661868184147184128 -1661868184192185088 -1661868184240186112 -1661868184282187008 -1661868184324187904 -1661868184366188800 -1661868184411189760 -1661868184447190528 -1661868184486191360 -1661868184528192256 -1661868184573193216 -1661868184618194176 -1661868184660195072 -1661868184705196032 -1661868184747196928 -1661868184786197760 -1661868184831198720 -1661868184873199616 -1661868184921200640 -1661868184960201472 -1661868185005202432 -1661868185047203328 -1661868185086204160 -1661868185125204992 -1661868185170205952 -1661868185215206912 -1661868185257207808 -1661868185299208704 -1661868185341209600 -1661868185383210496 -1661868185422211328 -1661868185464212224 -1661868185506213120 -1661868185545213952 -1661868185590214912 -1661868185632215808 -1661868185671216640 -1661868185707217408 -1661868185752218368 -1661868185794219264 -1661868185839220224 -1661868185875220992 -1661868185914221824 -1661868185962222848 -1661868186004223744 -1661868186046224640 -1661868186091225600 -1661868186130226432 -1661868186175227392 -1661868186220228352 -1661868186262229248 -1661868186307230208 -1661868186349231104 -1661868186391232000 -1661868186433232896 -1661868186478233856 -1661868186520234752 -1661868186562235648 -1661868186601236480 -1661868186643237376 -1661868186679238144 -1661868186718238976 -1661868186760239872 -1661868186805240832 -1661868186844241664 -1661868186883242496 -1661868186925243392 -1661868186964244224 -1661868187006245120 -1661868187048246016 -1661868187090246912 -1661868187129247744 -1661868187174248704 -1661868187216249600 -1661868187255250432 -1661868187297251328 -1661868187339252224 -1661868187381253120 -1661868187423254016 -1661868187465254912 -1661868187507255808 -1661868187549256704 -1661868187597257728 -1661868187639258624 -1661868187681259520 -1661868187726260480 -1661868187768261376 -1661868187807262208 -1661868187846263040 -1661868187888263936 -1661868187930264832 -1661868187978265856 -1661868188020266752 -1661868188062267648 -1661868188101268480 -1661868188143269376 -1661868188185270272 -1661868188224271104 -1661868188263271936 -1661868188302272768 -1661868188341273600 -1661868188380274432 -1661868188419275264 -1661868188464276224 -1661868188509277184 -1661868188551278080 -1661868188596279040 -1661868188641280000 -1661868188686280960 -1661868188728281856 -1661868188776282880 -1661868188824283904 -1661868188869284864 -1661868188911285760 -1661868188950286592 -1661868188992287488 -1661868189034288384 -1661868189079289344 -1661868189121290240 -1661868189163291136 -1661868189205292032 -1661868189247292928 -1661868189292293888 -1661868189328294656 -1661868189370295552 -1661868189412296448 -1661868189457297408 -1661868189502298368 -1661868189541299200 -1661868189580300032 -1661868189616300800 -1661868189661301760 -1661868189703302656 -1661868189742303488 -1661868189784304384 -1661868189832305408 -1661868189871306240 -1661868189913307136 -1661868189949307904 -1661868189988308736 -1661868190030309632 -1661868190072310528 -1661868190114311424 -1661868190156312320 -1661868190195313152 -1661868190237314048 -1661868190276314880 -1661868190321315840 -1661868190363316736 -1661868190405317632 -1661868190441318400 -1661868190486319360 -1661868190528320256 -1661868190570321152 -1661868190609321984 -1661868190654322944 -1661868190699323904 -1661868190741324800 -1661868190780325632 -1661868190822326528 -1661868190864327424 -1661868190906328320 -1661868190945329152 -1661868190990330112 -1661868191041331200 -1661868191086332160 -1661868191128333056 -1661868191170333952 -1661868191212334848 -1661868191254335744 -1661868191296336640 -1661868191338337536 -1661868191377338368 -1661868191425339392 -1661868191464340224 -1661868191509341184 -1661868191554342144 -1661868191596343040 -1661868191638343936 -1661868191683344896 -1661868191722345728 -1661868191776346880 -1661868191818347776 -1661868191857348608 -1661868191902349568 -1661868191941350400 -1661868191983351296 -1661868192028352256 -1661868192070353152 -1661868192112354048 -1661868192151354880 -1661868192193355776 -1661868192235356672 -1661868192277357568 -1661868192319358464 -1661868192361359360 -1661868192400360192 -1661868192442361088 -1661868192484361984 -1661868192526362880 -1661868192568363776 -1661868192613364736 -1661868192655365632 -1661868192700366592 -1661868192739367424 -1661868192781368320 -1661868192823369216 -1661868192862370048 -1661868192907371008 -1661868192946371840 -1661868192988372736 -1661868193027373568 -1661868193066374400 -1661868193105375232 -1661868193147376128 -1661868193192377088 -1661868193234377984 -1661868193276378880 -1661868193318379776 -1661868193354380544 -1661868193396381440 -1661868193441382400 -1661868193489383424 -1661868193531384320 -1661868193570385152 -1661868193609385984 -1661868193651386880 -1661868193693387776 -1661868193735388672 -1661868193789389824 -1661868193828390656 -1661868193870391552 -1661868193909392384 -1661868193951393280 -1661868193993394176 -1661868194038395136 -1661868194074395904 -1661868194119396864 -1661868194161397760 -1661868194203398656 -1661868194245399552 -1661868194287400448 -1661868194329401344 -1661868194371402240 -1661868194413403136 -1661868194455404032 -1661868194497404928 -1661868194539405824 -1661868194581406720 -1661868194620407552 -1661868194662408448 -1661868194707409408 -1661868194752410368 -1661868194791411200 -1661868194830412032 -1661868194869412864 -1661868194914413824 -1661868194956414720 -1661868194998415616 -1661868195040416512 -1661868195079417344 -1661868195121418240 -1661868195163419136 -1661868195205420032 -1661868195244420864 -1661868195286421760 -1661868195331422720 -1661868195376423680 -1661868195418424576 -1661868195460425472 -1661868195508426496 -1661868195550427392 -1661868195592428288 -1661868195640429312 -1661868195682430208 -1661868195724431104 -1661868195769432064 -1661868195811432960 -1661868195853433856 -1661868195895434752 -1661868195931435520 -1661868195973436416 -1661868196015437312 -1661868196060438272 -1661868196102439168 -1661868196147440128 -1661868196195441152 -1661868196237442048 -1661868196285443072 -1661868196330444032 -1661868196375444992 -1661868196414445824 -1661868196453446656 -1661868196495447552 -1661868196537448448 -1661868196579449344 -1661868196624450304 -1661868196666451200 -1661868196711452160 -1661868196747452928 -1661868196789453824 -1661868196831454720 -1661868196873455616 -1661868196921456640 -1661868196969457664 -1661868197020458752 -1661868197059459584 -1661868197098460416 -1661868197140461312 -1661868197182462208 -1661868197221463040 -1661868197263463936 -1661868197302464768 -1661868197344465664 -1661868197386466560 -1661868197428467456 -1661868197470468352 -1661868197509469184 -1661868197554470144 -1661868197593470976 -1661868197635471872 -1661868197677472768 -1661868197716473600 -1661868197758474496 -1661868197800475392 -1661868197848476416 -1661868197890477312 -1661868197932478208 -1661868197971479040 -1661868198010479872 -1661868198052480768 -1661868198100481792 -1661868198139482624 -1661868198181483520 -1661868198220484352 -1661868198262485248 -1661868198304486144 -1661868198349487104 -1661868198394488064 -1661868198439489024 -1661868198481489920 -1661868198523490816 -1661868198559491584 -1661868198604492544 -1661868198646493440 -1661868198685494272 -1661868198730495232 -1661868198775496192 -1661868198817497088 -1661868198862498048 -1661868198904498944 -1661868198946499840 -1661868198988500736 -1661868199030501632 -1661868199072502528 -1661868199114503424 -1661868199156504320 -1661868199198505216 -1661868199243506176 -1661868199285507072 -1661868199333508096 -1661868199375508992 -1661868199420509952 -1661868199462510848 -1661868199504511744 -1661868199546512640 -1661868199588513536 -1661868199630514432 -1661868199672515328 -1661868199714516224 -1661868199753517056 -1661868199795517952 -1661868199834518784 -1661868199876519680 -1661868199915520512 -1661868199954521344 -1661868199996522240 -1661868200038523136 -1661868200080524032 -1661868200119524864 -1661868200158525696 -1661868200200526592 -1661868200242527488 -1661868200284528384 -1661868200329529344 -1661868200365530112 -1661868200410531072 -1661868200452531968 -1661868200491532800 -1661868200533533696 -1661868200572534528 -1661868200614535424 -1661868200662536448 -1661868200710537472 -1661868200755538432 -1661868200797539328 -1661868200836540160 -1661868200872540928 -1661868200914541824 -1661868200956542720 -1661868200998543616 -1661868201037544448 -1661868201076545280 -1661868201118546176 -1661868201154546944 -1661868201193547776 -1661868201235548672 -1661868201280549632 -1661868201319550464 -1661868201364551424 -1661868201406552320 -1661868201451553280 -1661868201493554176 -1661868201532555008 -1661868201574555904 -1661868201616556800 -1661868201658557696 -1661868201700558592 -1661868201739559424 -1661868201778560256 -1661868201820561152 -1661868201862562048 -1661868201913563136 -1661868201955564032 -1661868202000564992 -1661868202042565888 -1661868202084566784 -1661868202129567744 -1661868202168568576 -1661868202210569472 -1661868202252570368 -1661868202288571136 -1661868202330572032 -1661868202372572928 -1661868202414573824 -1661868202462574848 -1661868202504575744 -1661868202546576640 -1661868202588577536 -1661868202630578432 -1661868202675579392 -1661868202717580288 -1661868202756581120 -1661868202801582080 -1661868202846583040 -1661868202885583872 -1661868202927584768 -1661868202972585728 -1661868203011586560 -1661868203056587520 -1661868203101588480 -1661868203140589312 -1661868203182590208 -1661868203230591232 -1661868203272592128 -1661868203314593024 -1661868203359593984 -1661868203401594880 -1661868203443595776 -1661868203485596672 -1661868203527597568 -1661868203569598464 -1661868203611599360 -1661868203653600256 -1661868203695601152 -1661868203737602048 -1661868203779602944 -1661868203824603904 -1661868203863604736 -1661868203905605632 -1661868203947606528 -1661868203989607424 -1661868204034608384 -1661868204079609344 -1661868204121610240 -1661868204163611136 -1661868204205612032 -1661868204247612928 -1661868204289613824 -1661868204328614656 -1661868204367615488 -1661868204400616192 -1661868204442617088 -1661868204490618112 -1661868204532619008 -1661868204574619904 -1661868204616620800 -1661868204658621696 -1661868204697622528 -1661868204733623296 -1661868204775624192 -1661868204820625152 -1661868204856625920 -1661868204898626816 -1661868204943627776 -1661868204988628736 -1661868205033629696 -1661868205075630592 -1661868205114631424 -1661868205156632320 -1661868205204633344 -1661868205249634304 -1661868205288635136 -1661868205330636032 -1661868205372636928 -1661868205414637824 -1661868205456638720 -1661868205498639616 -1661868205537640448 -1661868205579641344 -1661868205621642240 -1661868205654642944 -1661868205696643840 -1661868205738644736 -1661868205789645824 -1661868205828646656 -1661868205870647552 -1661868205915648512 -1661868205960649472 -1661868206002650368 -1661868206044651264 -1661868206083652096 -1661868206125652992 -1661868206170653952 -1661868206212654848 -1661868206254655744 -1661868206299656704 -1661868206341657600 -1661868206380658432 -1661868206422659328 -1661868206467660288 -1661868206509661184 -1661868206548662016 -1661868206590662912 -1661868206638663936 -1661868206677664768 -1661868206722665728 -1661868206767666688 -1661868206809667584 -1661868206851668480 -1661868206890669312 -1661868206932670208 -1661868206971671040 -1661868207013671936 -1661868207055672832 -1661868207097673728 -1661868207139674624 -1661868207187675648 -1661868207229676544 -1661868207271677440 -1661868207313678336 -1661868207355679232 -1661868207397680128 -1661868207442681088 -1661868207487682048 -1661868207526682880 -1661868207568683776 -1661868207613684736 -1661868207658685696 -1661868207700686592 -1661868207742687488 -1661868207790688512 -1661868207829689344 -1661868207868690176 -1661868207913691136 -1661868207955692032 -1661868207997692928 -1661868208039693824 -1661868208084694784 -1661868208132695808 -1661868208177696768 -1661868208216697600 -1661868208255698432 -1661868208297699328 -1661868208339700224 -1661868208375700992 -1661868208417701888 -1661868208459702784 -1661868208501703680 -1661868208549704704 -1661868208591705600 -1661868208630706432 -1661868208672707328 -1661868208714708224 -1661868208756709120 -1661868208795709952 -1661868208831710720 -1661868208876711680 -1661868208918712576 -1661868208960713472 -1661868209002714368 -1661868209047715328 -1661868209089716224 -1661868209131717120 -1661868209173718016 -1661868209218718976 -1661868209260719872 -1661868209299720704 -1661868209341721600 -1661868209386722560 -1661868209434723584 -1661868209476724480 -1661868209518725376 -1661868209563726336 -1661868209608727296 -1661868209647728128 -1661868209686728960 -1661868209731729920 -1661868209773730816 -1661868209809731584 -1661868209851732480 -1661868209899733504 -1661868209941734400 -1661868209980735232 -1661868210022736128 -1661868210067737088 -1661868210109737984 -1661868210148738816 -1661868210187739648 -1661868210226740480 -1661868210268741376 -1661868210310742272 -1661868210349743104 -1661868210391744000 -1661868210430744832 -1661868210472745728 -1661868210514746624 -1661868210556747520 -1661868210601748480 -1661868210640749312 -1661868210682750208 -1661868210724751104 -1661868210766752000 -1661868210811752960 -1661868210856753920 -1661868210898754816 -1661868210937755648 -1661868210979756544 -1661868211021757440 -1661868211063758336 -1661868211102759168 -1661868211150760192 -1661868211195761152 -1661868211237762048 -1661868211273762816 -1661868211315763712 -1661868211357764608 -1661868211396765440 -1661868211441766400 -1661868211480767232 -1661868211522768128 -1661868211567769088 -1661868211606769920 -1661868211648770816 -1661868211687771648 -1661868211729772544 -1661868211771773440 -1661868211813774336 -1661868211861775360 -1661868211906776320 -1661868211948777216 -1661868211993778176 -1661868212041779200 -1661868212083780096 -1661868212131781120 -1661868212173782016 -1661868212215782912 -1661868212257783808 -1661868212302784768 -1661868212347785728 -1661868212386786560 -1661868212431787520 -1661868212473788416 -1661868212515789312 -1661868212557790208 -1661868212599791104 -1661868212641792000 -1661868212683792896 -1661868212725793792 -1661868212767794688 -1661868212809795584 -1661868212851796480 -1661868212893797376 -1661868212935798272 -1661868212971799040 -1661868213016800000 -1661868213055800832 -1661868213094801664 -1661868213139802624 -1661868213178803456 -1661868213220804352 -1661868213259805184 -1661868213307806208 -1661868213343806976 -1661868213391808000 -1661868213430808832 -1661868213475809792 -1661868213523810816 -1661868213568811776 -1661868213610812672 -1661868213649813504 -1661868213691814400 -1661868213733815296 -1661868213772816128 -1661868213814817024 -1661868213850817792 -1661868213892818688 -1661868213937819648 -1661868213979820544 -1661868214015821312 -1661868214060822272 -1661868214099823104 -1661868214141824000 -1661868214180824832 -1661868214222825728 -1661868214264826624 -1661868214306827520 -1661868214351828480 -1661868214393829376 -1661868214432830208 -1661868214471831040 -1661868214513831936 -1661868214555832832 -1661868214594833664 -1661868214636834560 -1661868214678835456 -1661868214720836352 -1661868214762837248 -1661868214807838208 -1661868214849839104 -1661868214885839872 -1661868214927840768 -1661868214972841728 -1661868215014842624 -1661868215059843584 -1661868215101844480 -1661868215140845312 -1661868215188846336 -1661868215230847232 -1661868215278848256 -1661868215320849152 -1661868215362850048 -1661868215401850880 -1661868215443851776 -1661868215488852736 -1661868215530853632 -1661868215569854464 -1661868215611855360 -1661868215650856192 -1661868215692857088 -1661868215734857984 -1661868215776858880 -1661868215815859712 -1661868215860860672 -1661868215902861568 -1661868215944862464 -1661868215986863360 -1661868216034864384 -1661868216076865280 -1661868216121866240 -1661868216163867136 -1661868216202867968 -1661868216250868992 -1661868216295869952 -1661868216337870848 -1661868216385871872 -1661868216427872768 -1661868216475873792 -1661868216520874752 -1661868216562875648 -1661868216607876608 -1661868216649877504 -1661868216700878592 -1661868216742879488 -1661868216784880384 -1661868216823881216 -1661868216865882112 -1661868216913883136 -1661868216952883968 -1661868216991884800 -1661868217033885696 -1661868217075886592 -1661868217117887488 -1661868217162888448 -1661868217198889216 -1661868217240890112 -1661868217282891008 -1661868217321891840 -1661868217363892736 -1661868217405893632 -1661868217447894528 -1661868217489895424 -1661868217534896384 -1661868217576897280 -1661868217618898176 -1661868217666899200 -1661868217711900160 -1661868217753901056 -1661868217795901952 -1661868217837902848 -1661868217879903744 -1661868217921904640 -1661868217963905536 -1661868218005906432 -1661868218047907328 -1661868218092908288 -1661868218134909184 -1661868218182910208 -1661868218224911104 -1661868218266912000 -1661868218305912832 -1661868218350913792 -1661868218392914688 -1661868218437915648 -1661868218479916544 -1661868218521917440 -1661868218563918336 -1661868218605919232 -1661868218644920064 -1661868218686920960 -1661868218728921856 -1661868218770922752 -1661868218815923712 -1661868218857924608 -1661868218896925440 -1661868218944926464 -1661868218986927360 -1661868219028928256 -1661868219073929216 -1661868219115930112 -1661868219154930944 -1661868219202931968 -1661868219247932928 -1661868219295933952 -1661868219343934976 -1661868219385935872 -1661868219430936832 -1661868219469937664 -1661868219511938560 -1661868219553939456 -1661868219595940352 -1661868219637941248 -1661868219676942080 -1661868219715942912 -1661868219757943808 -1661868219796944640 -1661868219841945600 -1661868219883946496 -1661868219925947392 -1661868219967948288 -1661868220006949120 -1661868220045949952 -1661868220087950848 -1661868220129951744 -1661868220174952704 -1661868220213953536 -1661868220252954368 -1661868220291955200 -1661868220333956096 -1661868220375956992 -1661868220420957952 -1661868220462958848 -1661868220504959744 -1661868220549960704 -1661868220594961664 -1661868220636962560 -1661868220678963456 -1661868220717964288 -1661868220762965248 -1661868220804966144 -1661868220855967232 -1661868220897968128 -1661868220942969088 -1661868220984969984 -1661868221026970880 -1661868221068971776 -1661868221107972608 -1661868221146973440 -1661868221185974272 -1661868221224975104 -1661868221269976064 -1661868221311976960 -1661868221350977792 -1661868221395978752 -1661868221440979712 -1661868221479980544 -1661868221518981376 -1661868221560982272 -1661868221602983168 -1661868221647984128 -1661868221686984960 -1661868221731985920 -1661868221779986944 -1661868221821987840 -1661868221866988800 -1661868221908989696 -1661868221947990528 -1661868221995991552 -1661868222034992384 -1661868222076993280 -1661868222121994240 -1661868222166995200 -1661868222211996160 -1661868222253997056 -1661868222292997888 -1661868222331998720 -1661868222373999616 -1661868222416000512 -1661868222458001408 -1661868222500002304 -1661868222548003328 -1661868222584004096 -1661868222626004992 -1661868222671005952 -1661868222713006848 -1661868222764007936 -1661868222806008832 -1661868222848009728 -1661868222890010624 -1661868222932011520 -1661868222974012416 -1661868223022013440 -1661868223070014464 -1661868223109015296 -1661868223151016192 -1661868223190017024 -1661868223241018112 -1661868223283019008 -1661868223328019968 -1661868223367020800 -1661868223409021696 -1661868223457022720 -1661868223499023616 -1661868223541024512 -1661868223583025408 -1661868223625026304 -1661868223670027264 -1661868223709028096 -1661868223751028992 -1661868223793029888 -1661868223841030912 -1661868223883031808 -1661868223925032704 -1661868223967033600 -1661868224006034432 -1661868224045035264 -1661868224087036160 -1661868224129037056 -1661868224168037888 -1661868224207038720 -1661868224261039872 -1661868224300040704 -1661868224342041600 -1661868224384042496 -1661868224432043520 -1661868224474044416 -1661868224519045376 -1661868224561046272 -1661868224603047168 -1661868224645048064 -1661868224687048960 -1661868224732049920 -1661868224774050816 -1661868224816051712 -1661868224855052544 -1661868224897053440 -1661868224939054336 -1661868224981055232 -1661868225023056128 -1661868225074057216 -1661868225116058112 -1661868225161059072 -1661868225203059968 -1661868225248060928 -1661868225290061824 -1661868225338062848 -1661868225380063744 -1661868225422064640 -1661868225467065600 -1661868225509066496 -1661868225545067264 -1661868225590068224 -1661868225638069248 -1661868225686070272 -1661868225728071168 -1661868225770072064 -1661868225818073088 -1661868225860073984 -1661868225902074880 -1661868225944075776 -1661868225992076800 -1661868226034077696 -1661868226076078592 -1661868226118079488 -1661868226160080384 -1661868226199081216 -1661868226241082112 -1661868226289083136 -1661868226334084096 -1661868226376084992 -1661868226418085888 -1661868226454086656 -1661868226496087552 -1661868226535088384 -1661868226586089472 -1661868226628090368 -1661868226670091264 -1661868226709092096 -1661868226751092992 -1661868226799094016 -1661868226838094848 -1661868226883095808 -1661868226925096704 -1661868226967097600 -1661868227012098560 -1661868227054099456 -1661868227093100288 -1661868227141101312 -1661868227186102272 -1661868227225103104 -1661868227270104064 -1661868227312104960 -1661868227354105856 -1661868227396106752 -1661868227441107712 -1661868227483108608 -1661868227525109504 -1661868227567110400 -1661868227609111296 -1661868227651112192 -1661868227690113024 -1661868227732113920 -1661868227774114816 -1661868227819115776 -1661868227867116800 -1661868227912117760 -1661868227954118656 -1661868227996119552 -1661868228038120448 -1661868228086121472 -1661868228134122496 -1661868228179123456 -1661868228221124352 -1661868228263125248 -1661868228305126144 -1661868228353127168 -1661868228395128064 -1661868228434128896 -1661868228479129856 -1661868228524130816 -1661868228569131776 -1661868228611132672 -1661868228656133632 -1661868228698134528 -1661868228737135360 -1661868228776136192 -1661868228824137216 -1661868228866138112 -1661868228908139008 -1661868228950139904 -1661868228992140800 -1661868229031141632 -1661868229073142528 -1661868229124143616 -1661868229166144512 -1661868229208145408 -1661868229253146368 -1661868229295147264 -1661868229337148160 -1661868229379149056 -1661868229421149952 -1661868229463150848 -1661868229508151808 -1661868229547152640 -1661868229592153600 -1661868229634154496 -1661868229673155328 -1661868229715156224 -1661868229757157120 -1661868229796157952 -1661868229838158848 -1661868229880159744 -1661868229931160832 -1661868229973161728 -1661868230015162624 -1661868230057163520 -1661868230099164416 -1661868230141165312 -1661868230186166272 -1661868230228167168 -1661868230270168064 -1661868230309168896 -1661868230354169856 -1661868230396170752 -1661868230435171584 -1661868230480172544 -1661868230525173504 -1661868230561174272 -1661868230603175168 -1661868230642176000 -1661868230684176896 -1661868230723177728 -1661868230765178624 -1661868230807179520 -1661868230849180416 -1661868230891181312 -1661868230936182272 -1661868230978183168 -1661868231020184064 -1661868231059184896 -1661868231104185856 -1661868231146186752 -1661868231191187712 -1661868231233188608 -1661868231275189504 -1661868231317190400 -1661868231356191232 -1661868231401192192 -1661868231443193088 -1661868231482193920 -1661868231524194816 -1661868231569195776 -1661868231611196672 -1661868231653197568 -1661868231692198400 -1661868231731199232 -1661868231770200064 -1661868231812200960 -1661868231857201920 -1661868231902202880 -1661868231944203776 -1661868231986204672 -1661868232031205632 -1661868232070206464 -1661868232112207360 -1661868232157208320 -1661868232199209216 -1661868232241210112 -1661868232283211008 -1661868232328211968 -1661868232370212864 -1661868232412213760 -1661868232454214656 -1661868232496215552 -1661868232532216320 -1661868232574217216 -1661868232616218112 -1661868232652218880 -1661868232691219712 -1661868232733220608 -1661868232775221504 -1661868232817222400 -1661868232859223296 -1661868232901224192 -1661868232946225152 -1661868232991226112 -1661868233030226944 -1661868233075227904 -1661868233117228800 -1661868233159229696 -1661868233204230656 -1661868233240231424 -1661868233282232320 -1661868233324233216 -1661868233363234048 -1661868233405234944 -1661868233441235712 -1661868233483236608 -1661868233528237568 -1661868233576238592 -1661868233624239616 -1661868233669240576 -1661868233711241472 -1661868233756242432 -1661868233798243328 -1661868233840244224 -1661868233882245120 -1661868233924246016 -1661868233963246848 -1661868234005247744 -1661868234053248768 -1661868234095249664 -1661868234134250496 -1661868234179251456 -1661868234221252352 -1661868234263253248 -1661868234305254144 -1661868234347255040 -1661868234389255936 -1661868234431256832 -1661868234473257728 -1661868234518258688 -1661868234560259584 -1661868234602260480 -1661868234644261376 -1661868234686262272 -1661868234728263168 -1661868234770264064 -1661868234812264960 -1661868234848265728 -1661868234890266624 -1661868234929267456 -1661868234974268416 -1661868235013269248 -1661868235055270144 -1661868235103271168 -1661868235148272128 -1661868235187272960 -1661868235232273920 -1661868235274274816 -1661868235319275776 -1661868235361276672 -1661868235403277568 -1661868235448278528 -1661868235499279616 -1661868235544280576 -1661868235589281536 -1661868235631282432 -1661868235670283264 -1661868235715284224 -1661868235760285184 -1661868235802286080 -1661868235850287104 -1661868235892288000 -1661868235937288960 -1661868235979289856 -1661868236021290752 -1661868236069291776 -1661868236111292672 -1661868236153293568 -1661868236195294464 -1661868236240295424 -1661868236282296320 -1661868236333297408 -1661868236375298304 -1661868236417299200 -1661868236462300160 -1661868236507301120 -1661868236543301888 -1661868236585302784 -1661868236627303680 -1661868236666304512 -1661868236708305408 -1661868236756306432 -1661868236795307264 -1661868236834308096 -1661868236870308864 -1661868236915309824 -1661868236957310720 -1661868237005311744 -1661868237047312640 -1661868237089313536 -1661868237134314496 -1661868237176315392 -1661868237218316288 -1661868237263317248 -1661868237302318080 -1661868237344318976 -1661868237383319808 -1661868237425320704 -1661868237467321600 -1661868237506322432 -1661868237557323520 -1661868237599324416 -1661868237641325312 -1661868237683326208 -1661868237725327104 -1661868237770328064 -1661868237809328896 -1661868237851329792 -1661868237899330816 -1661868237941331712 -1661868237989332736 -1661868238028333568 -1661868238073334528 -1661868238118335488 -1661868238160336384 -1661868238202337280 -1661868238241338112 -1661868238292339200 -1661868238337340160 -1661868238379341056 -1661868238421341952 -1661868238463342848 -1661868238505343744 -1661868238547344640 -1661868238583345408 -1661868238628346368 -1661868238667347200 -1661868238709348096 -1661868238757349120 -1661868238799350016 -1661868238844350976 -1661868238889351936 -1661868238928352768 -1661868238967353600 -1661868239003354368 -1661868239045355264 -1661868239090356224 -1661868239138357248 -1661868239183358208 -1661868239234359296 -1661868239279360256 -1661868239321361152 -1661868239369362176 -1661868239411363072 -1661868239456364032 -1661868239504365056 -1661868239546365952 -1661868239591366912 -1661868239633367808 -1661868239678368768 -1661868239717369600 -1661868239759370496 -1661868239810371584 -1661868239852372480 -1661868239894373376 -1661868239936374272 -1661868239975375104 -1661868240023376128 -1661868240065377024 -1661868240107377920 -1661868240149378816 -1661868240191379712 -1661868240236380672 -1661868240281381632 -1661868240320382464 -1661868240359383296 -1661868240398384128 -1661868240437384960 -1661868240479385856 -1661868240521386752 -1661868240560387584 -1661868240599388416 -1661868240641389312 -1661868240683390208 -1661868240728391168 -1661868240770392064 -1661868240815393024 -1661868240857393920 -1661868240902394880 -1661868240947395840 -1661868240986396672 -1661868241028397568 -1661868241070398464 -1661868241121399552 -1661868241166400512 -1661868241208401408 -1661868241247402240 -1661868241289403136 -1661868241331404032 -1661868241373404928 -1661868241418405888 -1661868241460406784 -1661868241505407744 -1661868241544408576 -1661868241583409408 -1661868241625410304 -1661868241667411200 -1661868241709412096 -1661868241754413056 -1661868241796413952 -1661868241838414848 -1661868241880415744 -1661868241925416704 -1661868241979417856 -1661868242021418752 -1661868242060419584 -1661868242099420416 -1661868242141421312 -1661868242183422208 -1661868242225423104 -1661868242267424000 -1661868242312424960 -1661868242354425856 -1661868242390426624 -1661868242432427520 -1661868242471428352 -1661868242507429120 -1661868242549430016 -1661868242591430912 -1661868242633431808 -1661868242675432704 -1661868242717433600 -1661868242759434496 -1661868242801435392 -1661868242843436288 -1661868242885437184 -1661868242927438080 -1661868242969438976 -1661868243011439872 -1661868243053440768 -1661868243095441664 -1661868243140442624 -1661868243182443520 -1661868243221444352 -1661868243272445440 -1661868243317446400 -1661868243359447296 -1661868243401448192 -1661868243440449024 -1661868243488450048 -1661868243533451008 -1661868243575451904 -1661868243617452800 -1661868243656453632 -1661868243698454528 -1661868243740455424 -1661868243782456320 -1661868243824457216 -1661868243866458112 -1661868243914459136 -1661868243956460032 -1661868243998460928 -1661868244043461888 -1661868244085462784 -1661868244127463680 -1661868244172464640 -1661868244220465664 -1661868244265466624 -1661868244304467456 -1661868244349468416 -1661868244394469376 -1661868244439470336 -1661868244481471232 -1661868244520472064 -1661868244559472896 -1661868244601473792 -1661868244649474816 -1661868244691475712 -1661868244736476672 -1661868244778477568 -1661868244823478528 -1661868244865479424 -1661868244913480448 -1661868244961481472 -1661868245012482560 -1661868245054483456 -1661868245096484352 -1661868245138485248 -1661868245180486144 -1661868245222487040 -1661868245267488000 -1661868245309488896 -1661868245351489792 -1661868245396490752 -1661868245438491648 -1661868245483492608 -1661868245525493504 -1661868245570494464 -1661868245615495424 -1661868245657496320 -1661868245702497280 -1661868245741498112 -1661868245783499008 -1661868245822499840 -1661868245867500800 -1661868245909501696 -1661868245951502592 -1661868245993503488 -1661868246038504448 -1661868246080505344 -1661868246125506304 -1661868246182507520 -1661868246224508416 -1661868246263509248 -1661868246302510080 -1661868246344510976 -1661868246389511936 -1661868246434512896 -1661868246476513792 -1661868246521514752 -1661868246563515648 -1661868246602516480 -1661868246638517248 -1661868246686518272 -1661868246725519104 -1661868246767520000 -1661868246809520896 -1661868246851521792 -1661868246893522688 -1661868246944523776 -1661868246986524672 -1661868247028525568 -1661868247076526592 -1661868247118527488 -1661868247151528192 -1661868247190529024 -1661868247238530048 -1661868247280530944 -1661868247325531904 -1661868247370532864 -1661868247415533824 -1661868247457534720 -1661868247499535616 -1661868247541536512 -1661868247580537344 -1661868247622538240 -1661868247664539136 -1661868247709540096 -1661868247751540992 -1661868247790541824 -1661868247832542720 -1661868247874543616 -1661868247925544704 -1661868247967545600 -1661868248015546624 -1661868248057547520 -1661868248099548416 -1661868248141549312 -1661868248183550208 -1661868248222551040 -1661868248264551936 -1661868248312552960 -1661868248354553856 -1661868248399554816 -1661868248444555776 -1661868248486556672 -1661868248528557568 -1661868248567558400 -1661868248606559232 -1661868248645560064 -1661868248693561088 -1661868248735561984 -1661868248777562880 -1661868248819563776 -1661868248861564672 -1661868248906565632 -1661868248945566464 -1661868248987567360 -1661868249029568256 -1661868249077569280 -1661868249119570176 -1661868249164571136 -1661868249206572032 -1661868249248572928 -1661868249299574016 -1661868249341574912 -1661868249386575872 -1661868249425576704 -1661868249470577664 -1661868249509578496 -1661868249554579456 -1661868249599580416 -1661868249641581312 -1661868249686582272 -1661868249728583168 -1661868249767584000 -1661868249806584832 -1661868249851585792 -1661868249896586752 -1661868249932587520 -1661868249974588416 -1661868250016589312 -1661868250055590144 -1661868250097591040 -1661868250139591936 -1661868250181592832 -1661868250223593728 -1661868250265594624 -1661868250304595456 -1661868250343596288 -1661868250385597184 -1661868250430598144 -1661868250472599040 -1661868250523600128 -1661868250574601216 -1661868250619602176 -1661868250658603008 -1661868250703603968 -1661868250754605056 -1661868250796605952 -1661868250838606848 -1661868250880607744 -1661868250922608640 -1661868250964609536 -1661868251006610432 -1661868251048611328 -1661868251090612224 -1661868251129613056 -1661868251177614080 -1661868251219614976 -1661868251261615872 -1661868251303616768 -1661868251342617600 -1661868251384618496 -1661868251426619392 -1661868251471620352 -1661868251513621248 -1661868251555622144 -1661868251597623040 -1661868251642624000 -1661868251693625088 -1661868251732625920 -1661868251771626752 -1661868251810627584 -1661868251855628544 -1661868251897629440 -1661868251939630336 -1661868251984631296 -1661868252035632384 -1661868252074633216 -1661868252122634240 -1661868252164635136 -1661868252206636032 -1661868252245636864 -1661868252287637760 -1661868252338638848 -1661868252380639744 -1661868252422640640 -1661868252464641536 -1661868252506642432 -1661868252545643264 -1661868252590644224 -1661868252632645120 -1661868252677646080 -1661868252722647040 -1661868252764647936 -1661868252806648832 -1661868252842649600 -1661868252884650496 -1661868252938651648 -1661868252980652544 -1661868253022653440 -1661868253064654336 -1661868253100655104 -1661868253145656064 -1661868253184656896 -1661868253226657792 -1661868253268658688 -1661868253307659520 -1661868253349660416 -1661868253391661312 -1661868253433662208 -1661868253478663168 -1661868253520664064 -1661868253562664960 -1661868253610665984 -1661868253652666880 -1661868253694667776 -1661868253736668672 -1661868253778669568 -1661868253817670400 -1661868253859671296 -1661868253901672192 -1661868253943673088 -1661868253985673984 -1661868254027674880 -1661868254069675776 -1661868254111676672 -1661868254153677568 -1661868254195678464 -1661868254234679296 -1661868254279680256 -1661868254318681088 -1661868254360681984 -1661868254402682880 -1661868254444683776 -1661868254489684736 -1661868254534685696 -1661868254582686720 -1661868254624687616 -1661868254666688512 -1661868254708689408 -1661868254750690304 -1661868254798691328 -1661868254843692288 -1661868254885693184 -1661868254924694016 -1661868254969694976 -1661868255011695872 -1661868255053696768 -1661868255095697664 -1661868255137698560 -1661868255179699456 -1661868255224700416 -1661868255266701312 -1661868255317702400 -1661868255359703296 -1661868255398704128 -1661868255437704960 -1661868255479705856 -1661868255518706688 -1661868255557707520 -1661868255599708416 -1661868255641709312 -1661868255680710144 -1661868255722711040 -1661868255761711872 -1661868255803712768 -1661868255845713664 -1661868255887714560 -1661868255932715520 -1661868255977716480 -1661868256019717376 -1661868256061718272 -1661868256103719168 -1661868256145720064 -1661868256196721152 -1661868256238722048 -1661868256280722944 -1661868256319723776 -1661868256361724672 -1661868256403725568 -1661868256442726400 -1661868256490727424 -1661868256529728256 -1661868256568729088 -1661868256607729920 -1661868256649730816 -1661868256691731712 -1661868256727732480 -1661868256766733312 -1661868256808734208 -1661868256847735040 -1661868256892736000 -1661868256934736896 -1661868256979737856 -1661868257021738752 -1661868257063739648 -1661868257105740544 -1661868257150741504 -1661868257192742400 -1661868257234743296 -1661868257276744192 -1661868257318745088 -1661868257360745984 -1661868257408747008 -1661868257450747904 -1661868257492748800 -1661868257534749696 -1661868257582750720 -1661868257621751552 -1661868257663752448 -1661868257702753280 -1661868257741754112 -1661868257783755008 -1661868257828755968 -1661868257873756928 -1661868257915757824 -1661868257960758784 -1661868257999759616 -1661868258044760576 -1661868258092761600 -1661868258134762496 -1661868258170763264 -1661868258209764096 -1661868258251764992 -1661868258293765888 -1661868258332766720 -1661868258374767616 -1661868258416768512 -1661868258458769408 -1661868258503770368 -1661868258545771264 -1661868258587772160 -1661868258629773056 -1661868258674774016 -1661868258713774848 -1661868258749775616 -1661868258788776448 -1661868258830777344 -1661868258872778240 -1661868258914779136 -1661868258950779904 -1661868258992780800 -1661868259034781696 -1661868259073782528 -1661868259118783488 -1661868259160784384 -1661868259202785280 -1661868259244786176 -1661868259286787072 -1661868259328787968 -1661868259373788928 -1661868259415789824 -1661868259460790784 -1661868259502791680 -1661868259544792576 -1661868259592793600 -1661868259631794432 -1661868259673795328 -1661868259715796224 -1661868259757797120 -1661868259799798016 -1661868259838798848 -1661868259883799808 -1661868259928800768 -1661868259973801728 -1661868260015802624 -1661868260054803456 -1661868260096804352 -1661868260138805248 -1661868260180806144 -1661868260219806976 -1661868260261807872 -1661868260303808768 -1661868260348809728 -1661868260390810624 -1661868260432811520 -1661868260477812480 -1661868260519813376 -1661868260564814336 -1661868260606815232 -1661868260648816128 -1661868260690817024 -1661868260732817920 -1661868260774818816 -1661868260816819712 -1661868260861820672 -1661868260903821568 -1661868260939822336 -1661868260981823232 -1661868261020824064 -1661868261059824896 -1661868261104825856 -1661868261149826816 -1661868261188827648 -1661868261224828416 -1661868261272829440 -1661868261314830336 -1661868261359831296 -1661868261398832128 -1661868261443833088 -1661868261488834048 -1661868261530834944 -1661868261572835840 -1661868261620836864 -1661868261662837760 -1661868261707838720 -1661868261752839680 -1661868261791840512 -1661868261833841408 -1661868261875842304 -1661868261923843328 -1661868261965844224 -1661868262010845184 -1661868262052846080 -1661868262100847104 -1661868262139847936 -1661868262178848768 -1661868262217849600 -1661868262259850496 -1661868262301851392 -1661868262343852288 -1661868262388853248 -1661868262430854144 -1661868262472855040 -1661868262511855872 -1661868262559856896 -1661868262601857792 -1661868262646858752 -1661868262691859712 -1661868262733860608 -1661868262775861504 -1661868262820862464 -1661868262868863488 -1661868262907864320 -1661868262949865216 -1661868262991866112 -1661868263033867008 -1661868263075867904 -1661868263117868800 -1661868263159869696 -1661868263198870528 -1661868263240871424 -1661868263279872256 -1661868263321873152 -1661868263363874048 -1661868263408875008 -1661868263444875776 -1661868263486876672 -1661868263528877568 -1661868263567878400 -1661868263609879296 -1661868263651880192 -1661868263696881152 -1661868263738882048 -1661868263780882944 -1661868263822883840 -1661868263867884800 -1661868263906885632 -1661868263954886656 -1661868263996887552 -1661868264035888384 -1661868264074889216 -1661868264119890176 -1661868264161891072 -1661868264203891968 -1661868264242892800 -1661868264287893760 -1661868264329894656 -1661868264371895552 -1661868264413896448 -1661868264461897472 -1661868264500898304 -1661868264539899136 -1661868264584900096 -1661868264626900992 -1661868264665901824 -1661868264707902720 -1661868264752903680 -1661868264800904704 -1661868264851905792 -1661868264893906688 -1661868264935907584 -1661868264977908480 -1661868265016909312 -1661868265058910208 -1661868265100911104 -1661868265142912000 -1661868265187912960 -1661868265229913856 -1661868265274914816 -1661868265322915840 -1661868265361916672 -1661868265403917568 -1661868265445918464 -1661868265484919296 -1661868265526920192 -1661868265565921024 -1661868265619922176 -1661868265664923136 -1661868265706924032 -1661868265748924928 -1661868265790925824 -1661868265829926656 -1661868265874927616 -1661868265916928512 -1661868265955929344 -1661868265997930240 -1661868266036931072 -1661868266081932032 -1661868266123932928 -1661868266162933760 -1661868266204934656 -1661868266246935552 -1661868266288936448 -1661868266330937344 -1661868266369938176 -1661868266408939008 -1661868266450939904 -1661868266492940800 -1661868266540941824 -1661868266588942848 -1661868266633943808 -1661868266675944704 -1661868266729945856 -1661868266768946688 -1661868266813947648 -1661868266852948480 -1661868266894949376 -1661868266939950336 -1661868266978951168 -1661868267020952064 -1661868267065953024 -1661868267110953984 -1661868267149954816 -1661868267194955776 -1661868267236956672 -1661868267278957568 -1661868267317958400 -1661868267359959296 -1661868267398960128 -1661868267440961024 -1661868267485961984 -1661868267527962880 -1661868267569963776 -1661868267611964672 -1661868267650965504 -1661868267686966272 -1661868267728967168 -1661868267770968064 -1661868267818969088 -1661868267860969984 -1661868267902970880 -1661868267950971904 -1661868268001972992 -1661868268043973888 -1661868268091974912 -1661868268133975808 -1661868268175976704 -1661868268217977600 -1661868268259978496 -1661868268301979392 -1661868268340980224 -1661868268382981120 -1661868268427982080 -1661868268472983040 -1661868268511983872 -1661868268553984768 -1661868268598985728 -1661868268640986624 -1661868268685987584 -1661868268727988480 -1661868268766989312 -1661868268811990272 -1661868268853991168 -1661868268892992000 -1661868268937992960 -1661868268979993856 -1661868269021994752 -1661868269063995648 -1661868269105996544 -1661868269147997440 -1661868269192998400 -1661868269234999296 -1661868269277000192 -1661868269316001024 -1661868269361001984 -1661868269400002816 -1661868269442003712 -1661868269484004608 -1661868269529005568 -1661868269568006400 -1661868269607007232 -1661868269649008128 -1661868269694009088 -1661868269736009984 -1661868269784011008 -1661868269829011968 -1661868269877012992 -1661868269919013888 -1661868269961014784 -1661868270009015808 -1661868270051016704 -1661868270096017664 -1661868270147018752 -1661868270186019584 -1661868270225020416 -1661868270264021248 -1661868270300022016 -1661868270339022848 -1661868270384023808 -1661868270423024640 -1661868270474025728 -1661868270516026624 -1661868270558027520 -1661868270600028416 -1661868270639029248 -1661868270681030144 -1661868270723031040 -1661868270762031872 -1661868270807032832 -1661868270849033728 -1661868270897034752 -1661868270939035648 -1661868270978036480 -1661868271026037504 -1661868271071038464 -1661868271113039360 -1661868271152040192 -1661868271194041088 -1661868271248042240 -1661868271290043136 -1661868271335044096 -1661868271380045056 -1661868271422045952 -1661868271467046912 -1661868271506047744 -1661868271545048576 -1661868271587049472 -1661868271629050368 -1661868271668051200 -1661868271713052160 -1661868271758053120 -1661868271803054080 -1661868271845054976 -1661868271887055872 -1661868271929056768 -1661868271971057664 -1661868272010058496 -1661868272052059392 -1661868272094060288 -1661868272136061184 -1661868272181062144 -1661868272223063040 -1661868272265063936 -1661868272307064832 -1661868272352065792 -1661868272391066624 -1661868272427067392 -1661868272469068288 -1661868272508069120 -1661868272550070016 -1661868272592070912 -1661868272631071744 -1661868272673072640 -1661868272715073536 -1661868272757074432 -1661868272796075264 -1661868272838076160 -1661868272880077056 -1661868272922077952 -1661868272964078848 -1661868273006079744 -1661868273045080576 -1661868273087081472 -1661868273129082368 -1661868273171083264 -1661868273213084160 -1661868273255085056 -1661868273297085952 -1661868273342086912 -1661868273387087872 -1661868273429088768 -1661868273471089664 -1661868273516090624 -1661868273558091520 -1661868273606092544 -1661868273651093504 -1661868273693094400 -1661868273735095296 -1661868273777096192 -1661868273822097152 -1661868273864098048 -1661868273909099008 -1661868273957100032 -1661868273999100928 -1661868274041101824 -1661868274092102912 -1661868274131103744 -1661868274173104640 -1661868274215105536 -1661868274260106496 -1661868274299107328 -1661868274341108224 -1661868274386109184 -1661868274428110080 -1661868274476111104 -1661868274521112064 -1661868274566113024 -1661868274605113856 -1661868274656114944 -1661868274701115904 -1661868274743116800 -1661868274785117696 -1661868274827118592 -1661868274869119488 -1661868274911120384 -1661868274953121280 -1661868274989122048 -1661868275031122944 -1661868275070123776 -1661868275109124608 -1661868275151125504 -1661868275193126400 -1661868275238127360 -1661868275280128256 -1661868275322129152 -1661868275364130048 -1661868275403130880 -1661868275451131904 -1661868275493132800 -1661868275538133760 -1661868275580134656 -1661868275622135552 -1661868275670136576 -1661868275706137344 -1661868275745138176 -1661868275784139008 -1661868275829139968 -1661868275874140928 -1661868275916141824 -1661868275958142720 -1661868275997143552 -1661868276039144448 -1661868276081145344 -1661868276123146240 -1661868276168147200 -1661868276210148096 -1661868276249148928 -1661868276291149824 -1661868276333150720 -1661868276378151680 -1661868276417152512 -1661868276459153408 -1661868276501154304 -1661868276546155264 -1661868276588156160 -1661868276630157056 -1661868276675158016 -1661868276717158912 -1661868276759159808 -1661868276804160768 -1661868276846161664 -1661868276885162496 -1661868276924163328 -1661868276963164160 -1661868277002164992 -1661868277044165888 -1661868277086166784 -1661868277128167680 -1661868277170168576 -1661868277215169536 -1661868277260170496 -1661868277308171520 -1661868277347172352 -1661868277389173248 -1661868277431174144 -1661868277470174976 -1661868277512175872 -1661868277554176768 -1661868277596177664 -1661868277641178624 -1661868277686179584 -1661868277728180480 -1661868277770181376 -1661868277812182272 -1661868277851183104 -1661868277893184000 -1661868277932184832 -1661868277971185664 -1661868278013186560 -1661868278055187456 -1661868278100188416 -1661868278145189376 -1661868278187190272 -1661868278229191168 -1661868278271192064 -1661868278310192896 -1661868278349193728 -1661868278391194624 -1661868278427195392 -1661868278469196288 -1661868278511197184 -1661868278550198016 -1661868278598199040 -1661868278637199872 -1661868278676200704 -1661868278721201664 -1661868278763202560 -1661868278805203456 -1661868278847204352 -1661868278886205184 -1661868278925206016 -1661868278967206912 -1661868279009207808 -1661868279048208640 -1661868279090209536 -1661868279132210432 -1661868279177211392 -1661868279216212224 -1661868279264213248 -1661868279309214208 -1661868279351215104 -1661868279393216000 -1661868279435216896 -1661868279477217792 -1661868279522218752 -1661868279570219776 -1661868279612220672 -1661868279651221504 -1661868279687222272 -1661868279732223232 -1661868279774224128 -1661868279816225024 -1661868279858225920 -1661868279900226816 -1661868279945227776 -1661868279990228736 -1661868280035229696 -1661868280077230592 -1661868280125231616 -1661868280167232512 -1661868280209233408 -1661868280251234304 -1661868280293235200 -1661868280338236160 -1661868280380237056 -1661868280422237952 -1661868280464238848 -1661868280503239680 -1661868280548240640 -1661868280590241536 -1661868280635242496 -1661868280680243456 -1661868280722244352 -1661868280764245248 -1661868280800246016 -1661868280851247104 -1661868280905248256 -1661868280956249344 -1661868280998250240 -1661868281040251136 -1661868281082252032 -1661868281124252928 -1661868281166253824 -1661868281208254720 -1661868281253255680 -1661868281292256512 -1661868281337257472 -1661868281379258368 -1661868281424259328 -1661868281466260224 -1661868281511261184 -1661868281550262016 -1661868281592262912 -1661868281631263744 -1661868281676264704 -1661868281718265600 -1661868281763266560 -1661868281808267520 -1661868281850268416 -1661868281892269312 -1661868281937270272 -1661868281985271296 -1661868282024272128 -1661868282066273024 -1661868282111273984 -1661868282159275008 -1661868282204275968 -1661868282249276928 -1661868282288277760 -1661868282330278656 -1661868282378279680 -1661868282417280512 -1661868282459281408 -1661868282513282560 -1661868282555283456 -1661868282597284352 -1661868282639285248 -1661868282681286144 -1661868282726287104 -1661868282768288000 -1661868282813288960 -1661868282852289792 -1661868282894290688 -1661868282939291648 -1661868282984292608 -1661868283023293440 -1661868283068294400 -1661868283116295424 -1661868283158296320 -1661868283203297280 -1661868283245298176 -1661868283284299008 -1661868283329299968 -1661868283371300864 -1661868283419301888 -1661868283461302784 -1661868283500303616 -1661868283548304640 -1661868283590305536 -1661868283638306560 -1661868283677307392 -1661868283725308416 -1661868283770309376 -1661868283812310272 -1661868283857311232 -1661868283899312128 -1661868283941313024 -1661868283989314048 -1661868284028314880 -1661868284067315712 -1661868284109316608 -1661868284157317632 -1661868284199318528 -1661868284247319552 -1661868284286320384 -1661868284328321280 -1661868284379322368 -1661868284421323264 -1661868284457324032 -1661868284496324864 -1661868284538325760 -1661868284580326656 -1661868284622327552 -1661868284667328512 -1661868284709329408 -1661868284763330560 -1661868284805331456 -1661868284850332416 -1661868284895333376 -1661868284937334272 -1661868284976335104 -1661868285021336064 -1661868285066337024 -1661868285105337856 -1661868285156338944 -1661868285201339904 -1661868285243340800 -1661868285294341888 -1661868285336342784 -1661868285378343680 -1661868285420344576 -1661868285459345408 -1661868285501346304 -1661868285543347200 -1661868285585348096 -1661868285624348928 -1661868285666349824 -1661868285711350784 -1661868285753351680 -1661868285795352576 -1661868285834353408 -1661868285885354496 -1661868285927355392 -1661868285969356288 -1661868286011357184 -1661868286050358016 -1661868286089358848 -1661868286131359744 -1661868286176360704 -1661868286221361664 -1661868286263362560 -1661868286314363648 -1661868286353364480 -1661868286398365440 -1661868286440366336 -1661868286482367232 -1661868286524368128 -1661868286560368896 -1661868286602369792 -1661868286644370688 -1661868286686371584 -1661868286728372480 -1661868286770373376 -1661868286821374464 -1661868286863375360 -1661868286908376320 -1661868286950377216 -1661868286992378112 -1661868287037379072 -1661868287079379968 -1661868287127380992 -1661868287169381888 -1661868287208382720 -1661868287253383680 -1661868287298384640 -1661868287340385536 -1661868287382386432 -1661868287424387328 -1661868287466388224 -1661868287508389120 -1661868287550390016 -1661868287592390912 -1661868287634391808 -1661868287676392704 -1661868287718393600 -1661868287760394496 -1661868287805395456 -1661868287847396352 -1661868287895397376 -1661868287937398272 -1661868287976399104 -1661868288015399936 -1661868288063400960 -1661868288105401856 -1661868288147402752 -1661868288189403648 -1661868288231404544 -1661868288273405440 -1661868288315406336 -1661868288354407168 -1661868288396408064 -1661868288438408960 -1661868288483409920 -1661868288525410816 -1661868288570411776 -1661868288606412544 -1661868288648413440 -1661868288690414336 -1661868288732415232 -1661868288774416128 -1661868288816417024 -1661868288858417920 -1661868288900418816 -1661868288951419904 -1661868288993420800 -1661868289041421824 -1661868289083422720 -1661868289128423680 -1661868289170424576 -1661868289212425472 -1661868289257426432 -1661868289296427264 -1661868289338428160 -1661868289380429056 -1661868289428430080 -1661868289476431104 -1661868289518432000 -1661868289560432896 -1661868289602433792 -1661868289641434624 -1661868289683435520 -1661868289725436416 -1661868289767437312 -1661868289809438208 -1661868289851439104 -1661868289890439936 -1661868289935440896 -1661868289983441920 -1661868290025442816 -1661868290067443712 -1661868290115444736 -1661868290154445568 -1661868290199446528 -1661868290244447488 -1661868290289448448 -1661868290328449280 -1661868290364450048 -1661868290412451072 -1661868290454451968 -1661868290496452864 -1661868290535453696 -1661868290580454656 -1661868290622455552 -1661868290664456448 -1661868290706457344 -1661868290754458368 -1661868290802459392 -1661868290841460224 -1661868290883461120 -1661868290925462016 -1661868290967462912 -1661868291015463936 -1661868291060464896 -1661868291102465792 -1661868291144466688 -1661868291186467584 -1661868291231468544 -1661868291270469376 -1661868291312470272 -1661868291354471168 -1661868291396472064 -1661868291438472960 -1661868291483473920 -1661868291525474816 -1661868291567475712 -1661868291609476608 -1661868291648477440 -1661868291690478336 -1661868291732479232 -1661868291771480064 -1661868291813480960 -1661868291855481856 -1661868291900482816 -1661868291942483712 -1661868291984484608 -1661868292026485504 -1661868292071486464 -1661868292113487360 -1661868292152488192 -1661868292194489088 -1661868292233489920 -1661868292281490944 -1661868292320491776 -1661868292359492608 -1661868292401493504 -1661868292443494400 -1661868292485495296 -1661868292530496256 -1661868292572497152 -1661868292614498048 -1661868292656498944 -1661868292698499840 -1661868292743500800 -1661868292785501696 -1661868292821502464 -1661868292869503488 -1661868292911504384 -1661868292959505408 -1661868293001506304 -1661868293043507200 -1661868293085508096 -1661868293130509056 -1661868293175510016 -1661868293217510912 -1661868293265511936 -1661868293313512960 -1661868293352513792 -1661868293391514624 -1661868293430515456 -1661868293472516352 -1661868293520517376 -1661868293562518272 -1661868293601519104 -1661868293643520000 -1661868293685520896 -1661868293730521856 -1661868293772522752 -1661868293811523584 -1661868293853524480 -1661868293898525440 -1661868293940526336 -1661868293985527296 -1661868294027528192 -1661868294069529088 -1661868294111529984 -1661868294162531072 -1661868294204531968 -1661868294246532864 -1661868294285533696 -1661868294324534528 -1661868294366535424 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt deleted file mode 100644 index 23ef73aa69..0000000000 --- a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track0.txt +++ /dev/null @@ -1,2934 +0,0 @@ -1662064490014331136 -1662064490059332096 -1662064490101332992 -1662064490140333824 -1662064490188334848 -1662064490233335808 -1662064490275336704 -1662064490323337728 -1662064490371338752 -1662064490419339776 -1662064490461340672 -1662064490506341632 -1662064490548342528 -1662064490590343424 -1662064490632344320 -1662064490671345152 -1662064490710345984 -1662064490749346816 -1662064490794347776 -1662064490836348672 -1662064490878349568 -1662064490920350464 -1662064490962351360 -1662064491007352320 -1662064491049353216 -1662064491088354048 -1662064491130354944 -1662064491175355904 -1662064491223356928 -1662064491265357824 -1662064491307358720 -1662064491352359680 -1662064491397360640 -1662064491439361536 -1662064491481362432 -1662064491523363328 -1662064491562364160 -1662064491601364992 -1662064491643365888 -1662064491685366784 -1662064491727367680 -1662064491778368768 -1662064491820369664 -1662064491862370560 -1662064491904371456 -1662064491946372352 -1662064491985373184 -1662064492030374144 -1662064492072375040 -1662064492117376000 -1662064492159376896 -1662064492201377792 -1662064492246378752 -1662064492288379648 -1662064492330380544 -1662064492372381440 -1662064492411382272 -1662064492456383232 -1662064492501384192 -1662064492543385088 -1662064492588386048 -1662064492630386944 -1662064492669387776 -1662064492714388736 -1662064492756389632 -1662064492801390592 -1662064492846391552 -1662064492885392384 -1662064492927393280 -1662064492975394304 -1662064493017395200 -1662064493065396224 -1662064493107397120 -1662064493149398016 -1662064493188398848 -1662064493236399872 -1662064493284400896 -1662064493329401856 -1662064493374402816 -1662064493419403776 -1662064493464404736 -1662064493506405632 -1662064493554406656 -1662064493596407552 -1662064493638408448 -1662064493680409344 -1662064493722410240 -1662064493767411200 -1662064493815412224 -1662064493857413120 -1662064493899414016 -1662064493938414848 -1662064493983415808 -1662064494028416768 -1662064494073417728 -1662064494115418624 -1662064494160419584 -1662064494205420544 -1662064494244421376 -1662064494289422336 -1662064494331423232 -1662064494379424256 -1662064494418425088 -1662064494463426048 -1662064494505426944 -1662064494547427840 -1662064494589428736 -1662064494631429632 -1662064494670430464 -1662064494721431552 -1662064494766432512 -1662064494811433472 -1662064494853434368 -1662064494895435264 -1662064494937436160 -1662064494976436992 -1662064495018437888 -1662064495063438848 -1662064495108439808 -1662064495147440640 -1662064495189441536 -1662064495231442432 -1662064495273443328 -1662064495321444352 -1662064495366445312 -1662064495408446208 -1662064495450447104 -1662064495486447872 -1662064495528448768 -1662064495570449664 -1662064495615450624 -1662064495654451456 -1662064495699452416 -1662064495738453248 -1662064495783454208 -1662064495819454976 -1662064495861455872 -1662064495903456768 -1662064495945457664 -1662064495987458560 -1662064496026459392 -1662064496071460352 -1662064496116461312 -1662064496161462272 -1662064496200463104 -1662064496242464000 -1662064496284464896 -1662064496326465792 -1662064496365466624 -1662064496407467520 -1662064496452468480 -1662064496494469376 -1662064496536470272 -1662064496578471168 -1662064496623472128 -1662064496668473088 -1662064496707473920 -1662064496752474880 -1662064496794475776 -1662064496833476608 -1662064496875477504 -1662064496917478400 -1662064496959479296 -1662064497004480256 -1662064497046481152 -1662064497091482112 -1662064497133483008 -1662064497175483904 -1662064497217484800 -1662064497256485632 -1662064497295486464 -1662064497334487296 -1662064497379488256 -1662064497424489216 -1662064497463490048 -1662064497505490944 -1662064497550491904 -1662064497589492736 -1662064497631493632 -1662064497676494592 -1662064497727495680 -1662064497769496576 -1662064497811497472 -1662064497853498368 -1662064497892499200 -1662064497934500096 -1662064497973500928 -1662064498012501760 -1662064498057502720 -1662064498102503680 -1662064498147504640 -1662064498189505536 -1662064498234506496 -1662064498276507392 -1662064498318508288 -1662064498363509248 -1662064498408510208 -1662064498450511104 -1662064498492512000 -1662064498534512896 -1662064498579513856 -1662064498615514624 -1662064498654515456 -1662064498696516352 -1662064498741517312 -1662064498777518080 -1662064498813518848 -1662064498855519744 -1662064498903520768 -1662064498948521728 -1662064498993522688 -1662064499035523584 -1662064499080524544 -1662064499122525440 -1662064499161526272 -1662064499206527232 -1662064499242528000 -1662064499284528896 -1662064499323529728 -1662064499365530624 -1662064499404531456 -1662064499446532352 -1662064499494533376 -1662064499542534400 -1662064499590535424 -1662064499629536256 -1662064499671537152 -1662064499716538112 -1662064499761539072 -1662064499800539904 -1662064499839540736 -1662064499884541696 -1662064499923542528 -1662064499968543488 -1662064500016544512 -1662064500064545536 -1662064500109546496 -1662064500148547328 -1662064500190548224 -1662064500235549184 -1662064500277550080 -1662064500322551040 -1662064500367552000 -1662064500409552896 -1662064500451553792 -1662064500496554752 -1662064500541555712 -1662064500583556608 -1662064500625557504 -1662064500670558464 -1662064500712559360 -1662064500757560320 -1662064500799561216 -1662064500841562112 -1662064500883563008 -1662064500925563904 -1662064500970564864 -1662064501015565824 -1662064501060566784 -1662064501102567680 -1662064501144568576 -1662064501192569600 -1662064501234570496 -1662064501276571392 -1662064501315572224 -1662064501354573056 -1662064501405574144 -1662064501447575040 -1662064501489575936 -1662064501534576896 -1662064501579577856 -1662064501621578752 -1662064501666579712 -1662064501714580736 -1662064501756581632 -1662064501798582528 -1662064501843583488 -1662064501885584384 -1662064501924585216 -1662064501969586176 -1662064502011587072 -1662064502053587968 -1662064502098588928 -1662064502143589888 -1662064502191590912 -1662064502236591872 -1662064502281592832 -1662064502320593664 -1662064502362594560 -1662064502398595328 -1662064502440596224 -1662064502485597184 -1662064502524598016 -1662064502566598912 -1662064502608599808 -1662064502653600768 -1662064502695601664 -1662064502737602560 -1662064502782603520 -1662064502827604480 -1662064502872605440 -1662064502917606400 -1662064502962607360 -1662064503007608320 -1662064503052609280 -1662064503100610304 -1662064503139611136 -1662064503178611968 -1662064503223612928 -1662064503268613888 -1662064503313614848 -1662064503355615744 -1662064503397616640 -1662064503442617600 -1662064503484618496 -1662064503526619392 -1662064503568620288 -1662064503610621184 -1662064503658622208 -1662064503703623168 -1662064503745624064 -1662064503790625024 -1662064503832625920 -1662064503874626816 -1662064503916627712 -1662064503958628608 -1662064504000629504 -1662064504042630400 -1662064504084631296 -1662064504126632192 -1662064504162632960 -1662064504204633856 -1662064504249634816 -1662064504294635776 -1662064504339636736 -1662064504381637632 -1662064504429638656 -1662064504468639488 -1662064504510640384 -1662064504558641408 -1662064504597642240 -1662064504645643264 -1662064504687644160 -1662064504729645056 -1662064504771645952 -1662064504813646848 -1662064504852647680 -1662064504897648640 -1662064504936649472 -1662064504975650304 -1662064505017651200 -1662064505059652096 -1662064505101652992 -1662064505143653888 -1662064505191654912 -1662064505236655872 -1662064505278656768 -1662064505320657664 -1662064505362658560 -1662064505407659520 -1662064505449660416 -1662064505497661440 -1662064505539662336 -1662064505578663168 -1662064505623664128 -1662064505668665088 -1662064505716666112 -1662064505758667008 -1662064505809668096 -1662064505848668928 -1662064505890669824 -1662064505938670848 -1662064505980671744 -1662064506022672640 -1662064506064673536 -1662064506106674432 -1662064506151675392 -1662064506196676352 -1662064506244677376 -1662064506289678336 -1662064506334679296 -1662064506376680192 -1662064506418681088 -1662064506454681856 -1662064506499682816 -1662064506544683776 -1662064506586684672 -1662064506631685632 -1662064506673686528 -1662064506715687424 -1662064506757688320 -1662064506796689152 -1662064506838690048 -1662064506880690944 -1662064506922691840 -1662064506970692864 -1662064507012693760 -1662064507057694720 -1662064507099695616 -1662064507141696512 -1662064507180697344 -1662064507219698176 -1662064507270699264 -1662064507315700224 -1662064507357701120 -1662064507405702144 -1662064507447703040 -1662064507486703872 -1662064507528704768 -1662064507570705664 -1662064507612706560 -1662064507654707456 -1662064507702708480 -1662064507747709440 -1662064507789710336 -1662064507834711296 -1662064507879712256 -1662064507930713344 -1662064507975714304 -1662064508014715136 -1662064508062716160 -1662064508107717120 -1662064508152718080 -1662064508194718976 -1662064508236719872 -1662064508281720832 -1662064508329721856 -1662064508362722560 -1662064508407723520 -1662064508455724544 -1662064508497725440 -1662064508539726336 -1662064508584727296 -1662064508623728128 -1662064508665729024 -1662064508710729984 -1662064508761731072 -1662064508806732032 -1662064508854733056 -1662064508899734016 -1662064508941734912 -1662064508983735808 -1662064509025736704 -1662064509070737664 -1662064509115738624 -1662064509151739392 -1662064509193740288 -1662064509235741184 -1662064509280742144 -1662064509325743104 -1662064509364743936 -1662064509406744832 -1662064509448745728 -1662064509490746624 -1662064509532747520 -1662064509574748416 -1662064509616749312 -1662064509661750272 -1662064509706751232 -1662064509751752192 -1662064509793753088 -1662064509835753984 -1662064509877754880 -1662064509922755840 -1662064509967756800 -1662064510009757696 -1662064510051758592 -1662064510099759616 -1662064510141760512 -1662064510183761408 -1662064510228762368 -1662064510273763328 -1662064510321764352 -1662064510363765248 -1662064510405766144 -1662064510453767168 -1662064510495768064 -1662064510540769024 -1662064510582769920 -1662064510621770752 -1662064510660771584 -1662064510702772480 -1662064510747773440 -1662064510789774336 -1662064510831775232 -1662064510870776064 -1662064510915777024 -1662064510957777920 -1662064510999778816 -1662064511041779712 -1662064511083780608 -1662064511122781440 -1662064511164782336 -1662064511206783232 -1662064511254784256 -1662064511296785152 -1662064511338786048 -1662064511383787008 -1662064511425787904 -1662064511473788928 -1662064511515789824 -1662064511557790720 -1662064511602791680 -1662064511644792576 -1662064511686793472 -1662064511725794304 -1662064511770795264 -1662064511809796096 -1662064511851796992 -1662064511896797952 -1662064511938798848 -1662064511980799744 -1662064512028800768 -1662064512070801664 -1662064512109802496 -1662064512151803392 -1662064512193804288 -1662064512235805184 -1662064512271805952 -1662064512322807040 -1662064512364807936 -1662064512406808832 -1662064512445809664 -1662064512484810496 -1662064512523811328 -1662064512568812288 -1662064512607813120 -1662064512646813952 -1662064512691814912 -1662064512733815808 -1662064512778816768 -1662064512820817664 -1662064512859818496 -1662064512904819456 -1662064512952820480 -1662064512997821440 -1662064513039822336 -1662064513081823232 -1662064513123824128 -1662064513165825024 -1662064513207825920 -1662064513252826880 -1662064513294827776 -1662064513339828736 -1662064513381829632 -1662064513423830528 -1662064513465831424 -1662064513507832320 -1662064513546833152 -1662064513588834048 -1662064513627834880 -1662064513672835840 -1662064513714836736 -1662064513756837632 -1662064513795838464 -1662064513834839296 -1662064513873840128 -1662064513915841024 -1662064513960841984 -1662064514008843008 -1662064514050843904 -1662064514095844864 -1662064514137845760 -1662064514179846656 -1662064514221847552 -1662064514266848512 -1662064514311849472 -1662064514350850304 -1662064514383851008 -1662064514425851904 -1662064514467852800 -1662064514512853760 -1662064514554854656 -1662064514596855552 -1662064514641856512 -1662064514683857408 -1662064514725858304 -1662064514767859200 -1662064514812860160 -1662064514854861056 -1662064514899862016 -1662064514944862976 -1662064514986863872 -1662064515028864768 -1662064515070865664 -1662064515112866560 -1662064515154867456 -1662064515205868544 -1662064515250869504 -1662064515295870464 -1662064515343871488 -1662064515388872448 -1662064515427873280 -1662064515472874240 -1662064515517875200 -1662064515556876032 -1662064515598876928 -1662064515637877760 -1662064515685878784 -1662064515727879680 -1662064515769880576 -1662064515817881600 -1662064515859882496 -1662064515898883328 -1662064515937884160 -1662064515985885184 -1662064516024886016 -1662064516063886848 -1662064516105887744 -1662064516144888576 -1662064516189889536 -1662064516228890368 -1662064516270891264 -1662064516315892224 -1662064516360893184 -1662064516402894080 -1662064516441894912 -1662064516483895808 -1662064516522896640 -1662064516558897408 -1662064516600898304 -1662064516639899136 -1662064516687900160 -1662064516729901056 -1662064516774902016 -1662064516819902976 -1662064516858903808 -1662064516900904704 -1662064516942905600 -1662064516984906496 -1662064517029907456 -1662064517071908352 -1662064517116909312 -1662064517158910208 -1662064517200911104 -1662064517254912256 -1662064517296913152 -1662064517338914048 -1662064517380914944 -1662064517419915776 -1662064517467916800 -1662064517512917760 -1662064517554918656 -1662064517605919744 -1662064517650920704 -1662064517692921600 -1662064517737922560 -1662064517779923456 -1662064517824924416 -1662064517863925248 -1662064517902926080 -1662064517947927040 -1662064517989927936 -1662064518028928768 -1662064518073929728 -1662064518118930688 -1662064518160931584 -1662064518199932416 -1662064518241933312 -1662064518280934144 -1662064518322935040 -1662064518361935872 -1662064518406936832 -1662064518448937728 -1662064518490938624 -1662064518532939520 -1662064518577940480 -1662064518622941440 -1662064518667942400 -1662064518709943296 -1662064518751944192 -1662064518793945088 -1662064518832945920 -1662064518874946816 -1662064518916947712 -1662064518964948736 -1662064519009949696 -1662064519048950528 -1662064519084951296 -1662064519126952192 -1662064519168953088 -1662064519210953984 -1662064519252954880 -1662064519288955648 -1662064519333956608 -1662064519378957568 -1662064519420958464 -1662064519462959360 -1662064519507960320 -1662064519546961152 -1662064519591962112 -1662064519639963136 -1662064519678963968 -1662064519717964800 -1662064519759965696 -1662064519804966656 -1662064519849967616 -1662064519888968448 -1662064519930969344 -1662064519975970304 -1662064520017971200 -1662064520062972160 -1662064520104973056 -1662064520149974016 -1662064520194974976 -1662064520239975936 -1662064520281976832 -1662064520323977728 -1662064520368978688 -1662064520416979712 -1662064520464980736 -1662064520506981632 -1662064520548982528 -1662064520593983488 -1662064520641984512 -1662064520683985408 -1662064520725986304 -1662064520767987200 -1662064520812988160 -1662064520854989056 -1662064520896989952 -1662064520938990848 -1662064520977991680 -1662064521022992640 -1662064521064993536 -1662064521106994432 -1662064521148995328 -1662064521187996160 -1662064521226996992 -1662064521268997888 -1662064521316998912 -1662064521361999872 -1662064521407000832 -1662064521449001728 -1662064521491002624 -1662064521536003584 -1662064521578004480 -1662064521620005376 -1662064521662006272 -1662064521707007232 -1662064521746008064 -1662064521788008960 -1662064521827009792 -1662064521869010688 -1662064521911011584 -1662064521950012416 -1662064521992013312 -1662064522034014208 -1662064522076015104 -1662064522118016000 -1662064522163016960 -1662064522205017856 -1662064522247018752 -1662064522286019584 -1662064522328020480 -1662064522370021376 -1662064522412022272 -1662064522457023232 -1662064522499024128 -1662064522538024960 -1662064522580025856 -1662064522625026816 -1662064522667027712 -1662064522709028608 -1662064522754029568 -1662064522793030400 -1662064522835031296 -1662064522877032192 -1662064522919033088 -1662064522961033984 -1662064523003034880 -1662064523045035776 -1662064523093036800 -1662064523138037760 -1662064523180038656 -1662064523225039616 -1662064523267040512 -1662064523312041472 -1662064523354042368 -1662064523396043264 -1662064523438044160 -1662064523480045056 -1662064523522045952 -1662064523561046784 -1662064523600047616 -1662064523645048576 -1662064523687049472 -1662064523735050496 -1662064523777051392 -1662064523819052288 -1662064523861053184 -1662064523903054080 -1662064523954055168 -1662064523996056064 -1662064524035056896 -1662064524083057920 -1662064524128058880 -1662064524170059776 -1662064524212060672 -1662064524254061568 -1662064524302062592 -1662064524344063488 -1662064524389064448 -1662064524431065344 -1662064524470066176 -1662064524512067072 -1662064524557068032 -1662064524596068864 -1662064524638069760 -1662064524677070592 -1662064524722071552 -1662064524761072384 -1662064524806073344 -1662064524851074304 -1662064524896075264 -1662064524932076032 -1662064524971076864 -1662064525013077760 -1662064525058078720 -1662064525106079744 -1662064525151080704 -1662064525196081664 -1662064525238082560 -1662064525280083456 -1662064525328084480 -1662064525367085312 -1662064525412086272 -1662064525454087168 -1662064525499088128 -1662064525544089088 -1662064525586089984 -1662064525628090880 -1662064525664091648 -1662064525712092672 -1662064525754093568 -1662064525802094592 -1662064525847095552 -1662064525889096448 -1662064525931097344 -1662064525982098432 -1662064526024099328 -1662064526066100224 -1662064526105101056 -1662064526147101952 -1662064526189102848 -1662064526231103744 -1662064526276104704 -1662064526324105728 -1662064526366106624 -1662064526405107456 -1662064526450108416 -1662064526492109312 -1662064526534110208 -1662064526579111168 -1662064526624112128 -1662064526666113024 -1662064526708113920 -1662064526753114880 -1662064526798115840 -1662064526840116736 -1662064526885117696 -1662064526927118592 -1662064526969119488 -1662064527020120576 -1662064527062121472 -1662064527104122368 -1662064527149123328 -1662064527185124096 -1662064527227124992 -1662064527269125888 -1662064527311126784 -1662064527353127680 -1662064527389128448 -1662064527431129344 -1662064527470130176 -1662064527512131072 -1662064527557132032 -1662064527602132992 -1662064527644133888 -1662064527692134912 -1662064527731135744 -1662064527776136704 -1662064527815137536 -1662064527863138560 -1662064527905139456 -1662064527950140416 -1662064527992141312 -1662064528037142272 -1662064528079143168 -1662064528124144128 -1662064528172145152 -1662064528214146048 -1662064528262147072 -1662064528304147968 -1662064528349148928 -1662064528391149824 -1662064528430150656 -1662064528472151552 -1662064528514152448 -1662064528556153344 -1662064528592154112 -1662064528628154880 -1662064528667155712 -1662064528712156672 -1662064528754157568 -1662064528796158464 -1662064528838159360 -1662064528883160320 -1662064528922161152 -1662064528964162048 -1662064529009163008 -1662064529048163840 -1662064529093164800 -1662064529138165760 -1662064529183166720 -1662064529225167616 -1662064529267168512 -1662064529309169408 -1662064529354170368 -1662064529396171264 -1662064529438172160 -1662064529480173056 -1662064529525174016 -1662064529564174848 -1662064529609175808 -1662064529654176768 -1662064529693177600 -1662064529738178560 -1662064529780179456 -1662064529822180352 -1662064529867181312 -1662064529915182336 -1662064529957183232 -1662064530002184192 -1662064530047185152 -1662064530092186112 -1662064530134187008 -1662064530182188032 -1662064530227188992 -1662064530269189888 -1662064530308190720 -1662064530350191616 -1662064530395192576 -1662064530437193472 -1662064530482194432 -1662064530521195264 -1662064530566196224 -1662064530611197184 -1662064530653198080 -1662064530695198976 -1662064530740199936 -1662064530788200960 -1662064530833201920 -1662064530872202752 -1662064530920203776 -1662064530962204672 -1662064531007205632 -1662064531049206528 -1662064531097207552 -1662064531142208512 -1662064531184209408 -1662064531223210240 -1662064531265211136 -1662064531310212096 -1662064531352212992 -1662064531394213888 -1662064531436214784 -1662064531478215680 -1662064531517216512 -1662064531556217344 -1662064531601218304 -1662064531646219264 -1662064531685220096 -1662064531727220992 -1662064531769221888 -1662064531808222720 -1662064531847223552 -1662064531892224512 -1662064531934225408 -1662064531982226432 -1662064532027227392 -1662064532069228288 -1662064532111229184 -1662064532159230208 -1662064532201231104 -1662064532246232064 -1662064532291233024 -1662064532330233856 -1662064532372234752 -1662064532417235712 -1662064532462236672 -1662064532504237568 -1662064532543238400 -1662064532585239296 -1662064532627240192 -1662064532672241152 -1662064532714242048 -1662064532756242944 -1662064532795243776 -1662064532837244672 -1662064532882245632 -1662064532927246592 -1662064532966247424 -1662064533008248320 -1662064533047249152 -1662064533089250048 -1662064533131250944 -1662064533173251840 -1662064533215252736 -1662064533257253632 -1662064533302254592 -1662064533344255488 -1662064533386256384 -1662064533428257280 -1662064533470258176 -1662064533512259072 -1662064533551259904 -1662064533593260800 -1662064533638261760 -1662064533680262656 -1662064533722263552 -1662064533767264512 -1662064533809265408 -1662064533851266304 -1662064533893267200 -1662064533935268096 -1662064533977268992 -1662064534022269952 -1662064534067270912 -1662064534109271808 -1662064534154272768 -1662064534193273600 -1662064534238274560 -1662064534280275456 -1662064534322276352 -1662064534367277312 -1662064534409278208 -1662064534451279104 -1662064534499280128 -1662064534544281088 -1662064534589282048 -1662064534634283008 -1662064534673283840 -1662064534712284672 -1662064534754285568 -1662064534799286528 -1662064534844287488 -1662064534892288512 -1662064534937289472 -1662064534979290368 -1662064535021291264 -1662064535060292096 -1662064535105293056 -1662064535156294144 -1662064535201295104 -1662064535249296128 -1662064535291297024 -1662064535336297984 -1662064535375298816 -1662064535417299712 -1662064535459300608 -1662064535501301504 -1662064535543302400 -1662064535585303296 -1662064535627304192 -1662064535669305088 -1662064535714306048 -1662064535753306880 -1662064535795307776 -1662064535837308672 -1662064535879309568 -1662064535921310464 -1662064535969311488 -1662064536014312448 -1662064536056313344 -1662064536104314368 -1662064536143315200 -1662064536185316096 -1662064536230317056 -1662064536275318016 -1662064536323319040 -1662064536365319936 -1662064536410320896 -1662064536452321792 -1662064536497322752 -1662064536545323776 -1662064536593324800 -1662064536635325696 -1662064536677326592 -1662064536719327488 -1662064536761328384 -1662064536806329344 -1662064536854330368 -1662064536905331456 -1662064536950332416 -1662064536992333312 -1662064537034334208 -1662064537079335168 -1662064537124336128 -1662064537163336960 -1662064537202337792 -1662064537244338688 -1662064537289339648 -1662064537331340544 -1662064537376341504 -1662064537421342464 -1662064537463343360 -1662064537505344256 -1662064537553345280 -1662064537595346176 -1662064537640347136 -1662064537688348160 -1662064537733349120 -1662064537775350016 -1662064537817350912 -1662064537856351744 -1662064537898352640 -1662064537940353536 -1662064537988354560 -1662064538033355520 -1662064538078356480 -1662064538123357440 -1662064538171358464 -1662064538213359360 -1662064538258360320 -1662064538297361152 -1662064538339362048 -1662064538384363008 -1662064538429363968 -1662064538471364864 -1662064538513365760 -1662064538555366656 -1662064538597367552 -1662064538639368448 -1662064538684369408 -1662064538726370304 -1662064538771371264 -1662064538810372096 -1662064538852372992 -1662064538891373824 -1662064538939374848 -1662064538984375808 -1662064539026376704 -1662064539071377664 -1662064539113378560 -1662064539158379520 -1662064539200380416 -1662064539242381312 -1662064539281382144 -1662064539326383104 -1662064539368384000 -1662064539410384896 -1662064539455385856 -1662064539497386752 -1662064539539387648 -1662064539581388544 -1662064539629389568 -1662064539671390464 -1662064539719391488 -1662064539764392448 -1662064539803393280 -1662064539845394176 -1662064539896395264 -1662064539938396160 -1662064539977396992 -1662064540022397952 -1662064540061398784 -1662064540103399680 -1662064540151400704 -1662064540187401472 -1662064540226402304 -1662064540271403264 -1662064540319404288 -1662064540361405184 -1662064540403406080 -1662064540445406976 -1662064540481407744 -1662064540523408640 -1662064540562409472 -1662064540607410432 -1662064540649411328 -1662064540694412288 -1662064540736413184 -1662064540781414144 -1662064540826415104 -1662064540868416000 -1662064540910416896 -1662064540949417728 -1662064540994418688 -1662064541039419648 -1662064541078420480 -1662064541117421312 -1662064541159422208 -1662064541198423040 -1662064541240423936 -1662064541282424832 -1662064541324425728 -1662064541366426624 -1662064541405427456 -1662064541444428288 -1662064541489429248 -1662064541534430208 -1662064541576431104 -1662064541621432064 -1662064541666433024 -1662064541705433856 -1662064541744434688 -1662064541789435648 -1662064541828436480 -1662064541870437376 -1662064541915438336 -1662064541957439232 -1662064541999440128 -1662064542044441088 -1662064542086441984 -1662064542131442944 -1662064542173443840 -1662064542215444736 -1662064542263445760 -1662064542308446720 -1662064542350447616 -1662064542395448576 -1662064542440449536 -1662064542482450432 -1662064542524451328 -1662064542569452288 -1662064542614453248 -1662064542659454208 -1662064542701455104 -1662064542743456000 -1662064542782456832 -1662064542827457792 -1662064542875458816 -1662064542920459776 -1662064542959460608 -1662064543004461568 -1662064543049462528 -1662064543091463424 -1662064543139464448 -1662064543184465408 -1662064543235466496 -1662064543280467456 -1662064543325468416 -1662064543367469312 -1662064543412470272 -1662064543454471168 -1662064543496472064 -1662064543541473024 -1662064543580473856 -1662064543625474816 -1662064543667475712 -1662064543706476544 -1662064543742477312 -1662064543784478208 -1662064543823479040 -1662064543877480192 -1662064543928481280 -1662064543973482240 -1662064544018483200 -1662064544057484032 -1662064544099484928 -1662064544144485888 -1662064544186486784 -1662064544228487680 -1662064544267488512 -1662064544309489408 -1662064544354490368 -1662064544396491264 -1662064544438492160 -1662064544477492992 -1662064544519493888 -1662064544564494848 -1662064544609495808 -1662064544651496704 -1662064544693497600 -1662064544735498496 -1662064544777499392 -1662064544819500288 -1662064544864501248 -1662064544909502208 -1662064544954503168 -1662064544993504000 -1662064545035504896 -1662064545080505856 -1662064545122506752 -1662064545164507648 -1662064545209508608 -1662064545257509632 -1662064545299510528 -1662064545344511488 -1662064545389512448 -1662064545431513344 -1662064545476514304 -1662064545518515200 -1662064545563516160 -1662064545617517312 -1662064545659518208 -1662064545707519232 -1662064545749520128 -1662064545794521088 -1662064545836521984 -1662064545881522944 -1662064545926523904 -1662064545971524864 -1662064546016525824 -1662064546061526784 -1662064546106527744 -1662064546148528640 -1662064546193529600 -1662064546232530432 -1662064546274531328 -1662064546316532224 -1662064546361533184 -1662064546406534144 -1662064546445534976 -1662064546484535808 -1662064546529536768 -1662064546574537728 -1662064546619538688 -1662064546658539520 -1662064546700540416 -1662064546739541248 -1662064546784542208 -1662064546826543104 -1662064546871544064 -1662064546913544960 -1662064546955545856 -1662064546997546752 -1662064547042547712 -1662064547087548672 -1662064547132549632 -1662064547177550592 -1662064547219551488 -1662064547264552448 -1662064547306553344 -1662064547348554240 -1662064547390555136 -1662064547432556032 -1662064547474556928 -1662064547522557952 -1662064547564558848 -1662064547606559744 -1662064547651560704 -1662064547699561728 -1662064547738562560 -1662064547780563456 -1662064547816564224 -1662064547855565056 -1662064547900566016 -1662064547942566912 -1662064547987567872 -1662064548029568768 -1662064548074569728 -1662064548116570624 -1662064548158571520 -1662064548197572352 -1662064548242573312 -1662064548284574208 -1662064548329575168 -1662064548368576000 -1662064548407576832 -1662064548452577792 -1662064548500578816 -1662064548545579776 -1662064548590580736 -1662064548629581568 -1662064548671582464 -1662064548713583360 -1662064548758584320 -1662064548803585280 -1662064548845586176 -1662064548884587008 -1662064548929587968 -1662064548974588928 -1662064549016589824 -1662064549061590784 -1662064549100591616 -1662064549148592640 -1662064549199593728 -1662064549241594624 -1662064549286595584 -1662064549328596480 -1662064549373597440 -1662064549418598400 -1662064549463599360 -1662064549505600256 -1662064549550601216 -1662064549592602112 -1662064549634603008 -1662064549676603904 -1662064549724604928 -1662064549766605824 -1662064549805606656 -1662064549847607552 -1662064549886608384 -1662064549931609344 -1662064549976610304 -1662064550021611264 -1662064550063612160 -1662064550108613120 -1662064550147613952 -1662064550189614848 -1662064550231615744 -1662064550276616704 -1662064550318617600 -1662064550357618432 -1662064550399619328 -1662064550444620288 -1662064550486621184 -1662064550528622080 -1662064550567622912 -1662064550609623808 -1662064550657624832 -1662064550702625792 -1662064550744626688 -1662064550786627584 -1662064550822628352 -1662064550861629184 -1662064550906630144 -1662064550951631104 -1662064550987631872 -1662064551029632768 -1662064551071633664 -1662064551116634624 -1662064551158635520 -1662064551200636416 -1662064551239637248 -1662064551281638144 -1662064551323639040 -1662064551365639936 -1662064551404640768 -1662064551449641728 -1662064551494642688 -1662064551539643648 -1662064551581644544 -1662064551623645440 -1662064551662646272 -1662064551707647232 -1662064551749648128 -1662064551794649088 -1662064551839650048 -1662064551881650944 -1662064551926651904 -1662064551971652864 -1662064552010653696 -1662064552049654528 -1662064552088655360 -1662064552133656320 -1662064552178657280 -1662064552220658176 -1662064552262659072 -1662064552310660096 -1662064552352660992 -1662064552394661888 -1662064552436662784 -1662064552478663680 -1662064552532664832 -1662064552577665792 -1662064552619666688 -1662064552661667584 -1662064552709668608 -1662064552757669632 -1662064552802670592 -1662064552844671488 -1662064552886672384 -1662064552928673280 -1662064552970674176 -1662064553018675200 -1662064553060676096 -1662064553093676800 -1662064553141677824 -1662064553180678656 -1662064553228679680 -1662064553273680640 -1662064553315681536 -1662064553354682368 -1662064553396683264 -1662064553438684160 -1662064553480685056 -1662064553525686016 -1662064553567686912 -1662064553612687872 -1662064553654688768 -1662064553699689728 -1662064553741690624 -1662064553780691456 -1662064553822692352 -1662064553864693248 -1662064553906694144 -1662064553948695040 -1662064553990695936 -1662064554035696896 -1662064554074697728 -1662064554116698624 -1662064554155699456 -1662064554200700416 -1662064554245701376 -1662064554287702272 -1662064554332703232 -1662064554371704064 -1662064554413704960 -1662064554452705792 -1662064554494706688 -1662064554536707584 -1662064554578708480 -1662064554620709376 -1662064554665710336 -1662064554707711232 -1662064554752712192 -1662064554797713152 -1662064554836713984 -1662064554878714880 -1662064554920715776 -1662064554962716672 -1662064555007717632 -1662064555049718528 -1662064555088719360 -1662064555130720256 -1662064555172721152 -1662064555214722048 -1662064555256722944 -1662064555301723904 -1662064555346724864 -1662064555391725824 -1662064555433726720 -1662064555475727616 -1662064555514728448 -1662064555571729664 -1662064555613730560 -1662064555655731456 -1662064555703732480 -1662064555748733440 -1662064555790734336 -1662064555832735232 -1662064555874736128 -1662064555919737088 -1662064555961737984 -1662064556006738944 -1662064556048739840 -1662064556093740800 -1662064556132741632 -1662064556174742528 -1662064556219743488 -1662064556264744448 -1662064556309745408 -1662064556357746432 -1662064556405747456 -1662064556450748416 -1662064556489749248 -1662064556534750208 -1662064556582751232 -1662064556627752192 -1662064556669753088 -1662064556711753984 -1662064556756754944 -1662064556798755840 -1662064556843756800 -1662064556885757696 -1662064556933758720 -1662064556969759488 -1662064557008760320 -1662064557047761152 -1662064557089762048 -1662064557131762944 -1662064557173763840 -1662064557212764672 -1662064557260765696 -1662064557305766656 -1662064557347767552 -1662064557383768320 -1662064557422769152 -1662064557467770112 -1662064557515771136 -1662064557557772032 -1662064557599772928 -1662064557638773760 -1662064557683774720 -1662064557728775680 -1662064557773776640 -1662064557818777600 -1662064557860778496 -1662064557902779392 -1662064557941780224 -1662064557983781120 -1662064558028782080 -1662064558067782912 -1662064558109783808 -1662064558148784640 -1662064558190785536 -1662064558232786432 -1662064558277787392 -1662064558322788352 -1662064558364789248 -1662064558409790208 -1662064558457791232 -1662064558499792128 -1662064558538792960 -1662064558583793920 -1662064558631794944 -1662064558673795840 -1662064558715796736 -1662064558757797632 -1662064558799798528 -1662064558847799552 -1662064558886800384 -1662064558928801280 -1662064558973802240 -1662064559018803200 -1662064559063804160 -1662064559108805120 -1662064559147805952 -1662064559189806848 -1662064559234807808 -1662064559276808704 -1662064559312809472 -1662064559354810368 -1662064559399811328 -1662064559441812224 -1662064559489813248 -1662064559534814208 -1662064559576815104 -1662064559618816000 -1662064559663816960 -1662064559705817856 -1662064559744818688 -1662064559786819584 -1662064559828820480 -1662064559867821312 -1662064559915822336 -1662064559957823232 -1662064559999824128 -1662064560044825088 -1662064560089826048 -1662064560134827008 -1662064560176827904 -1662064560218828800 -1662064560260829696 -1662064560299830528 -1662064560338831360 -1662064560377832192 -1662064560416833024 -1662064560458833920 -1662064560503834880 -1662064560545835776 -1662064560587836672 -1662064560632837632 -1662064560671838464 -1662064560716839424 -1662064560761840384 -1662064560803841280 -1662064560848842240 -1662064560893843200 -1662064560932844032 -1662064560968844800 -1662064561010845696 -1662064561055846656 -1662064561094847488 -1662064561136848384 -1662064561184849408 -1662064561220850176 -1662064561265851136 -1662064561310852096 -1662064561352852992 -1662064561397853952 -1662064561436854784 -1662064561478855680 -1662064561523856640 -1662064561568857600 -1662064561607858432 -1662064561652859392 -1662064561691860224 -1662064561733861120 -1662064561775862016 -1662064561817862912 -1662064561859863808 -1662064561901864704 -1662064561943865600 -1662064561988866560 -1662064562033867520 -1662064562075868416 -1662064562120869376 -1662064562162870272 -1662064562201871104 -1662064562243872000 -1662064562285872896 -1662064562327873792 -1662064562372874752 -1662064562417875712 -1662064562462876672 -1662064562510877696 -1662064562552878592 -1662064562594879488 -1662064562636880384 -1662064562681881344 -1662064562726882304 -1662064562768883200 -1662064562816884224 -1662064562861885184 -1662064562903886080 -1662064562948887040 -1662064562996888064 -1662064563038888960 -1662064563080889856 -1662064563122890752 -1662064563164891648 -1662064563209892608 -1662064563248893440 -1662064563290894336 -1662064563332895232 -1662064563374896128 -1662064563416897024 -1662064563461897984 -1662064563503898880 -1662064563545899776 -1662064563590900736 -1662064563632901632 -1662064563674902528 -1662064563719903488 -1662064563767904512 -1662064563806905344 -1662064563848906240 -1662064563887907072 -1662064563929907968 -1662064563971908864 -1662064564010909696 -1662064564052910592 -1662064564097911552 -1662064564139912448 -1662064564184913408 -1662064564226914304 -1662064564271915264 -1662064564313916160 -1662064564352916992 -1662064564397917952 -1662064564439918848 -1662064564484919808 -1662064564529920768 -1662064564571921664 -1662064564616922624 -1662064564658923520 -1662064564703924480 -1662064564745925376 -1662064564790926336 -1662064564832927232 -1662064564871928064 -1662064564913928960 -1662064564958929920 -1662064565000930816 -1662064565039931648 -1662064565081932544 -1662064565126933504 -1662064565171934464 -1662064565210935296 -1662064565255936256 -1662064565297937152 -1662064565339938048 -1662064565381938944 -1662064565426939904 -1662064565468940800 -1662064565510941696 -1662064565552942592 -1662064565594943488 -1662064565639944448 -1662064565681945344 -1662064565723946240 -1662064565768947200 -1662064565807948032 -1662064565849948928 -1662064565891949824 -1662064565933950720 -1662064565978951680 -1662064566020952576 -1662064566062953472 -1662064566104954368 -1662064566143955200 -1662064566188956160 -1662064566230957056 -1662064566263957760 -1662064566308958720 -1662064566353959680 -1662064566398960640 -1662064566440961536 -1662064566482962432 -1662064566527963392 -1662064566569964288 -1662064566617965312 -1662064566659966208 -1662064566701967104 -1662064566743968000 -1662064566785968896 -1662064566827969792 -1662064566872970752 -1662064566914971648 -1662064566959972608 -1662064567004973568 -1662064567046974464 -1662064567088975360 -1662064567133976320 -1662064567172977152 -1662064567214978048 -1662064567259979008 -1662064567298979840 -1662064567343980800 -1662064567388981760 -1662064567430982656 -1662064567472983552 -1662064567511984384 -1662064567556985344 -1662064567592986112 -1662064567634987008 -1662064567682988032 -1662064567721988864 -1662064567757989632 -1662064567799990528 -1662064567838991360 -1662064567880992256 -1662064567925993216 -1662064567964994048 -1662064568006994944 -1662064568051995904 -1662064568090996736 -1662064568132997632 -1662064568177998592 -1662064568222999552 -1662064568256000256 -1662064568301001216 -1662064568343002112 -1662064568385003008 -1662064568424003840 -1662064568466004736 -1662064568511005696 -1662064568553006592 -1662064568598007552 -1662064568640008448 -1662064568685009408 -1662064568724010240 -1662064568766011136 -1662064568811012096 -1662064568853012992 -1662064568898013952 -1662064568943014912 -1662064568988015872 -1662064569027016704 -1662064569069017600 -1662064569108018432 -1662064569150019328 -1662064569195020288 -1662064569234021120 -1662064569279022080 -1662064569324023040 -1662064569366023936 -1662064569411024896 -1662064569453025792 -1662064569498026752 -1662064569543027712 -1662064569582028544 -1662064569630029568 -1662064569672030464 -1662064569717031424 -1662064569759032320 -1662064569801033216 -1662064569837033984 -1662064569879034880 -1662064569927035904 -1662064569969036800 -1662064570011037696 -1662064570056038656 -1662064570101039616 -1662064570146040576 -1662064570188041472 -1662064570230042368 -1662064570275043328 -1662064570317044224 -1662064570359045120 -1662064570398045952 -1662064570443046912 -1662064570485047808 -1662064570527048704 -1662064570569049600 -1662064570614050560 -1662064570659051520 -1662064570701052416 -1662064570740053248 -1662064570782054144 -1662064570827055104 -1662064570869056000 -1662064570914056960 -1662064570959057920 -1662064571001058816 -1662064571043059712 -1662064571079060480 -1662064571124061440 -1662064571169062400 -1662064571211063296 -1662064571253064192 -1662064571298065152 -1662064571343066112 -1662064571394067200 -1662064571433068032 -1662064571478068992 -1662064571520069888 -1662064571565070848 -1662064571610071808 -1662064571652072704 -1662064571694073600 -1662064571736074496 -1662064571784075520 -1662064571829076480 -1662064571877077504 -1662064571919078400 -1662064571970079488 -1662064572012080384 -1662064572060081408 -1662064572102082304 -1662064572144083200 -1662064572186084096 -1662064572225084928 -1662064572267085824 -1662064572309086720 -1662064572357087744 -1662064572399088640 -1662064572444089600 -1662064572492090624 -1662064572540091648 -1662064572588092672 -1662064572630093568 -1662064572669094400 -1662064572714095360 -1662064572759096320 -1662064572801097216 -1662064572840098048 -1662064572882098944 -1662064572921099776 -1662064572966100736 -1662064573008101632 -1662064573050102528 -1662064573092103424 -1662064573134104320 -1662064573176105216 -1662064573215106048 -1662064573257106944 -1662064573299107840 -1662064573341108736 -1662064573383109632 -1662064573422110464 -1662064573464111360 -1662064573509112320 -1662064573545113088 -1662064573587113984 -1662064573629114880 -1662064573671115776 -1662064573710116608 -1662064573752117504 -1662064573794118400 -1662064573836119296 -1662064573878120192 -1662064573917121024 -1662064573959121920 -1662064574004122880 -1662064574049123840 -1662064574088124672 -1662064574133125632 -1662064574175126528 -1662064574220127488 -1662064574265128448 -1662064574304129280 -1662064574343130112 -1662064574388131072 -1662064574430131968 -1662064574475132928 -1662064574520133888 -1662064574556134656 -1662064574595135488 -1662064574637136384 -1662064574679137280 -1662064574721138176 -1662064574769139200 -1662064574811140096 -1662064574856141056 -1662064574898141952 -1662064574934142720 -1662064574970143488 -1662064575015144448 -1662064575057145344 -1662064575099146240 -1662064575144147200 -1662064575189148160 -1662064575231149056 -1662064575273149952 -1662064575318150912 -1662064575363151872 -1662064575408152832 -1662064575450153728 -1662064575489154560 -1662064575531155456 -1662064575579156480 -1662064575624157440 -1662064575663158272 -1662064575711159296 -1662064575756160256 -1662064575801161216 -1662064575840162048 -1662064575882162944 -1662064575924163840 -1662064575963164672 -1662064576008165632 -1662064576050166528 -1662064576095167488 -1662064576137168384 -1662064576182169344 -1662064576224170240 -1662064576263171072 -1662064576302171904 -1662064576347172864 -1662064576392173824 -1662064576434174720 -1662064576476175616 -1662064576518176512 -1662064576560177408 -1662064576608178432 -1662064576650179328 -1662064576701180416 -1662064576743181312 -1662064576782182144 -1662064576824183040 -1662064576866183936 -1662064576908184832 -1662064576950185728 -1662064576995186688 -1662064577034187520 -1662064577079188480 -1662064577118189312 -1662064577163190272 -1662064577205191168 -1662064577247192064 -1662064577289192960 -1662064577331193856 -1662064577373194752 -1662064577415195648 -1662064577460196608 -1662064577505197568 -1662064577547198464 -1662064577592199424 -1662064577634200320 -1662064577676201216 -1662064577718202112 -1662064577757202944 -1662064577799203840 -1662064577841204736 -1662064577886205696 -1662064577928206592 -1662064577973207552 -1662064578012208384 -1662064578051209216 -1662064578090210048 -1662064578132210944 -1662064578174211840 -1662064578219212800 -1662064578258213632 -1662064578306214656 -1662064578348215552 -1662064578393216512 -1662064578441217536 -1662064578489218560 -1662064578534219520 -1662064578576220416 -1662064578615221248 -1662064578657222144 -1662064578699223040 -1662064578741223936 -1662064578786224896 -1662064578828225792 -1662064578867226624 -1662064578912227584 -1662064578954228480 -1662064578996229376 -1662064579041230336 -1662064579080231168 -1662064579122232064 -1662064579161232896 -1662064579203233792 -1662064579248234752 -1662064579287235584 -1662064579329236480 -1662064579374237440 -1662064579422238464 -1662064579470239488 -1662064579515240448 -1662064579557241344 -1662064579599242240 -1662064579638243072 -1662064579680243968 -1662064579728244992 -1662064579773245952 -1662064579815246848 -1662064579860247808 -1662064579902248704 -1662064579944249600 -1662064579986250496 -1662064580028251392 -1662064580067252224 -1662064580112253184 -1662064580151254016 -1662064580190254848 -1662064580229255680 -1662064580271256576 -1662064580310257408 -1662064580352258304 -1662064580394259200 -1662064580442260224 -1662064580484261120 -1662064580526262016 -1662064580568262912 -1662064580610263808 -1662064580655264768 -1662064580697265664 -1662064580739266560 -1662064580781267456 -1662064580823268352 -1662064580868269312 -1662064580916270336 -1662064580955271168 -1662064581000272128 -1662064581045273088 -1662064581087273984 -1662064581135275008 -1662064581177275904 -1662064581222276864 -1662064581267277824 -1662064581312278784 -1662064581357279744 -1662064581399280640 -1662064581441281536 -1662064581489282560 -1662064581531283456 -1662064581564284160 -1662064581606285056 -1662064581651286016 -1662064581690286848 -1662064581732287744 -1662064581777288704 -1662064581816289536 -1662064581861290496 -1662064581903291392 -1662064581945292288 -1662064581987293184 -1662064582032294144 -1662064582068294912 -1662064582113295872 -1662064582152296704 -1662064582194297600 -1662064582239298560 -1662064582278299392 -1662064582320300288 -1662064582365301248 -1662064582404302080 -1662064582446302976 -1662064582485303808 -1662064582536304896 -1662064582578305792 -1662064582620306688 -1662064582665307648 -1662064582707308544 -1662064582752309504 -1662064582794310400 -1662064582839311360 -1662064582881312256 -1662064582923313152 -1662064582965314048 -1662064583007314944 -1662064583058316032 -1662064583100316928 -1662064583145317888 -1662064583187318784 -1662064583229319680 -1662064583274320640 -1662064583319321600 -1662064583364322560 -1662064583409323520 -1662064583454324480 -1662064583499325440 -1662064583544326400 -1662064583589327360 -1662064583631328256 -1662064583676329216 -1662064583715330048 -1662064583760331008 -1662064583802331904 -1662064583847332864 -1662064583886333696 -1662064583928334592 -1662064583973335552 -1662064584018336512 -1662064584063337472 -1662064584102338304 -1662064584141339136 -1662064584183340032 -1662064584222340864 -1662064584264341760 -1662064584309342720 -1662064584351343616 -1662064584393344512 -1662064584435345408 -1662064584477346304 -1662064584519347200 -1662064584561348096 -1662064584600348928 -1662064584645349888 -1662064584690350848 -1662064584729351680 -1662064584774352640 -1662064584816353536 -1662064584861354496 -1662064584903355392 -1662064584945356288 -1662064584990357248 -1662064585032358144 -1662064585074359040 -1662064585116359936 -1662064585164360960 -1662064585206361856 -1662064585248362752 -1662064585293363712 -1662064585332364544 -1662064585377365504 -1662064585419366400 -1662064585464367360 -1662064585509368320 -1662064585557369344 -1662064585599370240 -1662064585641371136 -1662064585686372096 -1662064585731373056 -1662064585779374080 -1662064585824375040 -1662064585866375936 -1662064585914376960 -1662064585953377792 -1662064586001378816 -1662064586043379712 -1662064586088380672 -1662064586133381632 -1662064586175382528 -1662064586217383424 -1662064586262384384 -1662064586307385344 -1662064586352386304 -1662064586394387200 -1662064586442388224 -1662064586484389120 -1662064586526390016 -1662064586574391040 -1662064586619392000 -1662064586664392960 -1662064586706393856 -1662064586748394752 -1662064586790395648 -1662064586835396608 -1662064586874397440 -1662064586919398400 -1662064586964399360 -1662064587006400256 -1662064587048401152 -1662064587093402112 -1662064587135403008 -1662064587180403968 -1662064587225404928 -1662064587267405824 -1662064587312406784 -1662064587357407744 -1662064587396408576 -1662064587441409536 -1662064587483410432 -1662064587531411456 -1662064587576412416 -1662064587621413376 -1662064587666414336 -1662064587708415232 -1662064587750416128 -1662064587798417152 -1662064587840418048 -1662064587882418944 -1662064587921419776 -1662064587963420672 -1662064588005421568 -1662064588041422336 -1662064588083423232 -1662064588122424064 -1662064588173425152 -1662064588212425984 -1662064588257426944 -1662064588299427840 -1662064588341428736 -1662064588386429696 -1662064588431430656 -1662064588476431616 -1662064588521432576 -1662064588563433472 -1662064588608434432 -1662064588647435264 -1662064588689436160 -1662064588734437120 -1662064588776438016 -1662064588815438848 -1662064588860439808 -1662064588902440704 -1662064588938441472 -1662064588983442432 -1662064589025443328 -1662064589067444224 -1662064589112445184 -1662064589154446080 -1662064589196446976 -1662064589244448000 -1662064589280448768 -1662064589322449664 -1662064589364450560 -1662064589406451456 -1662064589445452288 -1662064589487453184 -1662064589532454144 -1662064589571454976 -1662064589613455872 -1662064589658456832 -1662064589697457664 -1662064589742458624 -1662064589781459456 -1662064589823460352 -1662064589865461248 -1662064589907462144 -1662064589949463040 -1662064589994464000 -1662064590036464896 -1662064590081465856 -1662064590123466752 -1662064590168467712 -1662064590210468608 -1662064590255469568 -1662064590300470528 -1662064590348471552 -1662064590390472448 -1662064590435473408 -1662064590477474304 -1662064590516475136 -1662064590552475904 -1662064590594476800 -1662064590639477760 -1662064590687478784 -1662064590723479552 -1662064590762480384 -1662064590810481408 -1662064590849482240 -1662064590894483200 -1662064590939484160 -1662064590981485056 -1662064591023485952 -1662064591065486848 -1662064591107487744 -1662064591158488832 -1662064591206489856 -1662064591254490880 -1662064591296491776 -1662064591344492800 -1662064591389493760 -1662064591431494656 -1662064591479495680 -1662064591524496640 -1662064591569497600 -1662064591611498496 -1662064591650499328 -1662064591689500160 -1662064591734501120 -1662064591776502016 -1662064591821502976 -1662064591863503872 -1662064591905504768 -1662064591950505728 -1662064591992506624 -1662064592037507584 -1662064592079508480 -1662064592124509440 -1662064592163510272 -1662064592202511104 -1662064592247512064 -1662064592289512960 -1662064592328513792 -1662064592370514688 -1662064592412515584 -1662064592451516416 -1662064592490517248 -1662064592532518144 -1662064592577519104 -1662064592622520064 -1662064592661520896 -1662064592706521856 -1662064592748522752 -1662064592790523648 -1662064592829524480 -1662064592871525376 -1662064592913526272 -1662064592955527168 -1662064593000528128 -1662064593045529088 -1662064593087529984 -1662064593129530880 -1662064593168531712 -1662064593210532608 -1662064593252533504 -1662064593297534464 -1662064593342535424 -1662064593384536320 -1662064593429537280 -1662064593468538112 -1662064593510539008 -1662064593555539968 -1662064593600540928 -1662064593648541952 -1662064593687542784 -1662064593732543744 -1662064593771544576 -1662064593816545536 -1662064593861546496 -1662064593903547392 -1662064593942548224 -1662064593984549120 -1662064594026550016 -1662064594071550976 -1662064594113551872 -1662064594161552896 -1662064594206553856 -1662064594248554752 -1662064594287555584 -1662064594326556416 -1662064594371557376 -1662064594416558336 -1662064594452559104 -1662064594494560000 -1662064594533560832 -1662064594578561792 -1662064594623562752 -1662064594665563648 -1662064594704564480 -1662064594746565376 -1662064594788566272 -1662064594830567168 -1662064594869568000 -1662064594908568832 -1662064594950569728 -1662064594995570688 -1662064595037571584 -1662064595076572416 -1662064595115573248 -1662064595157574144 -1662064595199575040 -1662064595244576000 -1662064595286576896 -1662064595331577856 -1662064595373578752 -1662064595415579648 -1662064595460580608 -1662064595502581504 -1662064595550582528 -1662064595592583424 -1662064595637584384 -1662064595676585216 -1662064595718586112 -1662064595757586944 -1662064595802587904 -1662064595847588864 -1662064595886589696 -1662064595925590528 -1662064595967591424 -1662064596012592384 -1662064596057593344 -1662064596099594240 -1662064596141595136 -1662064596183596032 -1662064596228596992 -1662064596273597952 -1662064596312598784 -1662064596357599744 -1662064596402600704 -1662064596441601536 -1662064596483602432 -1662064596525603328 -1662064596567604224 -1662064596606605056 -1662064596648605952 -1662064596687606784 -1662064596729607680 -1662064596771608576 -1662064596816609536 -1662064596858610432 -1662064596900611328 -1662064596939612160 -1662064596975612928 -1662064597020613888 -1662064597068614912 -1662064597110615808 -1662064597155616768 -1662064597197617664 -1662064597239618560 -1662064597284619520 -1662064597326620416 -1662064597368621312 -1662064597410622208 -1662064597452623104 -1662064597497624064 -1662064597542625024 -1662064597584625920 -1662064597626626816 -1662064597668627712 -1662064597707628544 -1662064597749629440 -1662064597788630272 -1662064597836631296 -1662064597878632192 -1662064597920633088 -1662064597962633984 -1662064598010635008 -1662064598052635904 -1662064598097636864 -1662064598139637760 -1662064598175638528 -1662064598220639488 -1662064598259640320 -1662064598301641216 -1662064598346642176 -1662064598391643136 -1662064598433644032 -1662064598481645056 -1662064598520645888 -1662064598559646720 -1662064598601647616 -1662064598643648512 -1662064598685649408 -1662064598727650304 -1662064598772651264 -1662064598814652160 -1662064598859653120 -1662064598901654016 -1662064598943654912 -1662064598985655808 -1662064599027656704 -1662064599069657600 -1662064599114658560 -1662064599156659456 -1662064599201660416 -1662064599243661312 -1662064599288662272 -1662064599330663168 -1662064599372664064 -1662064599420665088 -1662064599465666048 -1662064599510667008 -1662064599552667904 -1662064599591668736 -1662064599639669760 -1662064599681670656 -1662064599723671552 -1662064599771672576 -1662064599810673408 -1662064599852674304 -1662064599900675328 -1662064599939676160 -1662064599981677056 -1662064600026678016 -1662064600071678976 -1662064600113679872 -1662064600158680832 -1662064600200681728 -1662064600245682688 -1662064600287683584 -1662064600329684480 -1662064600371685376 -1662064600416686336 -1662064600458687232 -1662064600497688064 -1662064600539688960 -1662064600581689856 -1662064600623690752 -1662064600668691712 -1662064600713692672 -1662064600761693696 -1662064600806694656 -1662064600851695616 -1662064600899696640 -1662064600947697664 -1662064600989698560 -1662064601031699456 -1662064601079700480 -1662064601124701440 -1662064601172702464 -1662064601217703424 -1662064601262704384 -1662064601307705344 -1662064601349706240 -1662064601388707072 -1662064601424707840 -1662064601466708736 -1662064601511709696 -1662064601550710528 -1662064601595711488 -1662064601640712448 -1662064601685713408 -1662064601727714304 -1662064601769715200 -1662064601811716096 -1662064601853716992 -1662064601901718016 -1662064601943718912 -1662064601988719872 -1662064602036720896 -1662064602078721792 -1662064602120722688 -1662064602168723712 -1662064602210724608 -1662064602249725440 -1662064602294726400 -1662064602333727232 -1662064602375728128 -1662064602414728960 -1662064602456729856 -1662064602495730688 -1662064602546731776 -1662064602591732736 -1662064602633733632 -1662064602675734528 -1662064602714735360 -1662064602762736384 -1662064602807737344 -1662064602846738176 -1662064602888739072 -1662064602930739968 -1662064602972740864 -1662064603017741824 -1662064603056742656 -1662064603095743488 -1662064603140744448 -1662064603182745344 -1662064603218746112 -1662064603269747200 -1662064603308748032 -1662064603347748864 -1662064603389749760 -1662064603434750720 -1662064603479751680 -1662064603521752576 -1662064603563753472 -1662064603605754368 -1662064603650755328 -1662064603689756160 -1662064603740757248 -1662064603782758144 -1662064603827759104 -1662064603869760000 -1662064603914760960 -1662064603950761728 -1662064603992762624 -1662064604034763520 -1662064604076764416 -1662064604118765312 -1662064604160766208 -1662064604208767232 -1662064604247768064 -1662064604289768960 -1662064604337769984 -1662064604379770880 -1662064604421771776 -1662064604463772672 -1662064604508773632 -1662064604550774528 -1662064604595775488 -1662064604640776448 -1662064604682777344 -1662064604724778240 -1662064604769779200 -1662064604814780160 -1662064604853780992 -1662064604901782016 -1662064604943782912 -1662064604985783808 -1662064605027784704 -1662064605072785664 -1662064605114786560 -1662064605156787456 -1662064605198788352 -1662064605240789248 -1662064605282790144 -1662064605324791040 -1662064605366791936 -1662064605411792896 -1662064605462793984 -1662064605510795008 -1662064605552795904 -1662064605591796736 -1662064605630797568 -1662064605672798464 -1662064605714799360 -1662064605765800448 -1662064605810801408 -1662064605852802304 -1662064605897803264 -1662064605936804096 -1662064605978804992 -1662064606020805888 -1662064606065806848 -1662064606110807808 -1662064606155808768 -1662064606197809664 -1662064606242810624 -1662064606287811584 -1662064606329812480 -1662064606368813312 -1662064606413814272 -1662064606452815104 -1662064606491815936 -1662064606533816832 -1662064606578817792 -1662064606620818688 -1662064606668819712 -1662064606710820608 -1662064606752821504 -1662064606794822400 -1662064606836823296 -1662064606881824256 -1662064606923825152 -1662064606968826112 -1662064607010827008 -1662064607055827968 -1662064607100828928 -1662064607142829824 -1662064607187830784 -1662064607229831680 -1662064607271832576 -1662064607316833536 -1662064607358834432 -1662064607406835456 -1662064607448836352 -1662064607493837312 -1662064607535838208 -1662064607577839104 -1662064607619840000 -1662064607664840960 -1662064607709841920 -1662064607751842816 -1662064607790843648 -1662064607829844480 -1662064607871845376 -1662064607910846208 -1662064607958847232 -1662064608003848192 -1662064608048849152 -1662064608090850048 -1662064608135851008 -1662064608177851904 -1662064608219852800 -1662064608267853824 -1662064608312854784 -1662064608354855680 -1662064608396856576 -1662064608441857536 -1662064608486858496 -1662064608528859392 -1662064608570860288 -1662064608615861248 -1662064608657862144 -1662064608699863040 -1662064608744864000 -1662064608786864896 -1662064608828865792 -1662064608870866688 -1662064608915867648 -1662064608957868544 -1662064608999869440 -1662064609038870272 -1662064609083871232 -1662064609128872192 -1662064609170873088 -1662064609212873984 -1662064609254874880 -1662064609299875840 -1662064609341876736 -1662064609386877696 -1662064609428878592 -1662064609470879488 -1662064609515880448 -1662064609560881408 -1662064609605882368 -1662064609653883392 -1662064609698884352 -1662064609740885248 -1662064609785886208 -1662064609827887104 -1662064609869888000 -1662064609917889024 -1662064609956889856 -1662064610001890816 -1662064610043891712 -1662064610082892544 -1662064610124893440 -1662064610166894336 -1662064610208895232 -1662064610250896128 -1662064610292897024 -1662064610334897920 -1662064610376898816 -1662064610418899712 -1662064610463900672 -1662064610505901568 -1662064610547902464 -1662064610589903360 -1662064610634904320 -1662064610676905216 -1662064610715906048 -1662064610760907008 -1662064610805907968 -1662064610850908928 -1662064610889909760 -1662064610931910656 -1662064610976911616 -1662064611021912576 -1662064611066913536 -1662064611111914496 -1662064611153915392 -1662064611198916352 -1662064611240917248 -1662064611282918144 -1662064611321918976 -1662064611363919872 -1662064611402920704 -1662064611447921664 -1662064611495922688 -1662064611537923584 -1662064611579924480 -1662064611627925504 -1662064611666926336 -1662064611708927232 -1662064611753928192 -1662064611795929088 -1662064611843930112 -1662064611885931008 -1662064611924931840 -1662064611969932800 -1662064612017933824 -1662064612059934720 -1662064612104935680 -1662064612149936640 -1662064612194937600 -1662064612233938432 -1662064612278939392 -1662064612326940416 -1662064612371941376 -1662064612410942208 -1662064612452943104 -1662064612491943936 -1662064612530944768 -1662064612569945600 -1662064612614946560 -1662064612659947520 -1662064612704948480 -1662064612749949440 -1662064612788950272 -1662064612833951232 -1662064612875952128 -1662064612917953024 -1662064612956953856 -1662064613001954816 -1662064613040955648 -1662064613085956608 -1662064613130957568 -1662064613178958592 -1662064613220959488 -1662064613262960384 -1662064613304961280 -1662064613346962176 -1662064613385963008 -1662064613430963968 -1662064613469964800 -1662064613511965696 -1662064613553966592 -1662064613595967488 -1662064613634968320 -1662064613673969152 -1662064613715970048 -1662064613757970944 -1662064613805971968 -1662064613847972864 -1662064613886973696 -1662064613925974528 -1662064613976975616 -1662064614015976448 -1662064614057977344 -1662064614102978304 -1662064614144979200 -1662064614186980096 -1662064614228980992 -1662064614267981824 -1662064614318982912 -1662064614360983808 -1662064614405984768 -1662064614447985664 -1662064614489986560 -1662064614531987456 -1662064614570988288 -1662064614609989120 -1662064614654990080 -1662064614696990976 -1662064614741991936 -1662064614783992832 -1662064614828993792 -1662064614870994688 -1662064614915995648 -1662064614960996608 -1662064615002997504 -1662064615044998400 -1662064615086999296 -1662064615132000256 -1662064615177001216 -1662064615219002112 -1662064615261003008 -1662064615303003904 -1662064615345004800 -1662064615384005632 -1662064615423006464 -1662064615462007296 -1662064615498008064 -1662064615546009088 -1662064615588009984 -1662064615630010880 -1662064615675011840 -1662064615714012672 -1662064615756013568 -1662064615798014464 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt deleted file mode 100644 index 51983432b0..0000000000 --- a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track1.txt +++ /dev/null @@ -1,2076 +0,0 @@ -1662125073430662912 -1662125073472663808 -1662125073511664640 -1662125073553665536 -1662125073598666496 -1662125073643667456 -1662125073688668416 -1662125073733669376 -1662125073781670400 -1662125073823671296 -1662125073865672192 -1662125073907673088 -1662125073952674048 -1662125073997675008 -1662125074042675968 -1662125074087676928 -1662125074132677888 -1662125074174678784 -1662125074216679680 -1662125074258680576 -1662125074303681536 -1662125074345682432 -1662125074387683328 -1662125074429684224 -1662125074474685184 -1662125074519686144 -1662125074564687104 -1662125074606688000 -1662125074651688960 -1662125074696689920 -1662125074741690880 -1662125074789691904 -1662125074831692800 -1662125074879693824 -1662125074918694656 -1662125074960695552 -1662125074999696384 -1662125075044697344 -1662125075086698240 -1662125075131699200 -1662125075176700160 -1662125075224701184 -1662125075269702144 -1662125075308702976 -1662125075347703808 -1662125075389704704 -1662125075440705792 -1662125075482706688 -1662125075524707584 -1662125075569708544 -1662125075617709568 -1662125075659710464 -1662125075701711360 -1662125075746712320 -1662125075788713216 -1662125075830714112 -1662125075872715008 -1662125075917715968 -1662125075956716800 -1662125076001717760 -1662125076046718720 -1662125076091719680 -1662125076139720704 -1662125076181721600 -1662125076223722496 -1662125076265723392 -1662125076307724288 -1662125076358725376 -1662125076400726272 -1662125076445727232 -1662125076490728192 -1662125076538729216 -1662125076580730112 -1662125076625731072 -1662125076670732032 -1662125076712732928 -1662125076754733824 -1662125076796734720 -1662125076847735808 -1662125076889736704 -1662125076934737664 -1662125076976738560 -1662125077024739584 -1662125077072740608 -1662125077114741504 -1662125077156742400 -1662125077195743232 -1662125077237744128 -1662125077279745024 -1662125077327746048 -1662125077366746880 -1662125077411747840 -1662125077453748736 -1662125077498749696 -1662125077540750592 -1662125077582751488 -1662125077627752448 -1662125077669753344 -1662125077711754240 -1662125077753755136 -1662125077795756032 -1662125077837756928 -1662125077879757824 -1662125077924758784 -1662125077969759744 -1662125078011760640 -1662125078056761600 -1662125078098762496 -1662125078143763456 -1662125078188764416 -1662125078227765248 -1662125078272766208 -1662125078314767104 -1662125078359768064 -1662125078401768960 -1662125078446769920 -1662125078494770944 -1662125078539771904 -1662125078587772928 -1662125078635773952 -1662125078677774848 -1662125078725775872 -1662125078767776768 -1662125078809777664 -1662125078848778496 -1662125078896779520 -1662125078938780416 -1662125078986781440 -1662125079025782272 -1662125079070783232 -1662125079112784128 -1662125079157785088 -1662125079199785984 -1662125079244786944 -1662125079289787904 -1662125079331788800 -1662125079373789696 -1662125079412790528 -1662125079457791488 -1662125079502792448 -1662125079541793280 -1662125079589794304 -1662125079625795072 -1662125079676796160 -1662125079715796992 -1662125079760797952 -1662125079802798848 -1662125079847799808 -1662125079892800768 -1662125079934801664 -1662125079976802560 -1662125080024803584 -1662125080066804480 -1662125080114805504 -1662125080162806528 -1662125080204807424 -1662125080246808320 -1662125080291809280 -1662125080336810240 -1662125080381811200 -1662125080423812096 -1662125080468813056 -1662125080510813952 -1662125080552814848 -1662125080597815808 -1662125080639816704 -1662125080684817664 -1662125080729818624 -1662125080771819520 -1662125080819820544 -1662125080861821440 -1662125080900822272 -1662125080948823296 -1662125080990824192 -1662125081032825088 -1662125081080826112 -1662125081122827008 -1662125081164827904 -1662125081206828800 -1662125081248829696 -1662125081296830720 -1662125081338831616 -1662125081380832512 -1662125081425833472 -1662125081467834368 -1662125081515835392 -1662125081557836288 -1662125081605837312 -1662125081653838336 -1662125081698839296 -1662125081743840256 -1662125081788841216 -1662125081833842176 -1662125081872843008 -1662125081923844096 -1662125081965844992 -1662125082010845952 -1662125082055846912 -1662125082097847808 -1662125082136848640 -1662125082178849536 -1662125082217850368 -1662125082256851200 -1662125082298852096 -1662125082346853120 -1662125082388854016 -1662125082433854976 -1662125082475855872 -1662125082520856832 -1662125082565857792 -1662125082610858752 -1662125082652859648 -1662125082697860608 -1662125082742861568 -1662125082781862400 -1662125082820863232 -1662125082859864064 -1662125082901864960 -1662125082943865856 -1662125082982866688 -1662125083024867584 -1662125083066868480 -1662125083111869440 -1662125083159870464 -1662125083207871488 -1662125083249872384 -1662125083294873344 -1662125083336874240 -1662125083378875136 -1662125083420876032 -1662125083462876928 -1662125083510877952 -1662125083555878912 -1662125083597879808 -1662125083639880704 -1662125083684881664 -1662125083726882560 -1662125083774883584 -1662125083813884416 -1662125083855885312 -1662125083900886272 -1662125083942887168 -1662125083984888064 -1662125084026888960 -1662125084068889856 -1662125084113890816 -1662125084155891712 -1662125084200892672 -1662125084242893568 -1662125084284894464 -1662125084326895360 -1662125084371896320 -1662125084416897280 -1662125084464898304 -1662125084509899264 -1662125084557900288 -1662125084605901312 -1662125084653902336 -1662125084695903232 -1662125084737904128 -1662125084776904960 -1662125084818905856 -1662125084857906688 -1662125084899907584 -1662125084944908544 -1662125084989909504 -1662125085031910400 -1662125085076911360 -1662125085127912448 -1662125085169913344 -1662125085214914304 -1662125085259915264 -1662125085301916160 -1662125085346917120 -1662125085388918016 -1662125085439919104 -1662125085481920000 -1662125085523920896 -1662125085565921792 -1662125085604922624 -1662125085649923584 -1662125085694924544 -1662125085739925504 -1662125085781926400 -1662125085826927360 -1662125085868928256 -1662125085913929216 -1662125085955930112 -1662125086000931072 -1662125086045932032 -1662125086087932928 -1662125086126933760 -1662125086168934656 -1662125086210935552 -1662125086249936384 -1662125086291937280 -1662125086333938176 -1662125086378939136 -1662125086423940096 -1662125086468941056 -1662125086519942144 -1662125086558942976 -1662125086603943936 -1662125086648944896 -1662125086693945856 -1662125086744946944 -1662125086783947776 -1662125086825948672 -1662125086870949632 -1662125086909950464 -1662125086951951360 -1662125086993952256 -1662125087038953216 -1662125087083954176 -1662125087125955072 -1662125087170956032 -1662125087215956992 -1662125087257957888 -1662125087299958784 -1662125087341959680 -1662125087386960640 -1662125087428961536 -1662125087473962496 -1662125087515963392 -1662125087557964288 -1662125087599965184 -1662125087644966144 -1662125087686967040 -1662125087731968000 -1662125087773968896 -1662125087812969728 -1662125087857970688 -1662125087896971520 -1662125087938972416 -1662125087977973248 -1662125088016974080 -1662125088061975040 -1662125088100975872 -1662125088151976960 -1662125088196977920 -1662125088241978880 -1662125088283979776 -1662125088334980864 -1662125088376981760 -1662125088418982656 -1662125088466983680 -1662125088511984640 -1662125088553985536 -1662125088601986560 -1662125088643987456 -1662125088685988352 -1662125088727989248 -1662125088766990080 -1662125088811991040 -1662125088856992000 -1662125088898992896 -1662125088943993856 -1662125088982994688 -1662125089018995456 -1662125089063996416 -1662125089108997376 -1662125089150998272 -1662125089189999104 -1662125089232000000 -1662125089277000960 -1662125089322001920 -1662125089373003008 -1662125089415003904 -1662125089457004800 -1662125089499005696 -1662125089550006784 -1662125089598007808 -1662125089640008704 -1662125089682009600 -1662125089727010560 -1662125089772011520 -1662125089814012416 -1662125089856013312 -1662125089898014208 -1662125089946015232 -1662125089991016192 -1662125090033017088 -1662125090075017984 -1662125090123019008 -1662125090165019904 -1662125090204020736 -1662125090243021568 -1662125090282022400 -1662125090327023360 -1662125090366024192 -1662125090402024960 -1662125090447025920 -1662125090489026816 -1662125090528027648 -1662125090573028608 -1662125090618029568 -1662125090660030464 -1662125090705031424 -1662125090747032320 -1662125090789033216 -1662125090834034176 -1662125090879035136 -1662125090930036224 -1662125090975037184 -1662125091020038144 -1662125091065039104 -1662125091110040064 -1662125091155041024 -1662125091197041920 -1662125091239042816 -1662125091284043776 -1662125091326044672 -1662125091368045568 -1662125091419046656 -1662125091461047552 -1662125091506048512 -1662125091548049408 -1662125091593050368 -1662125091635051264 -1662125091677052160 -1662125091719053056 -1662125091761053952 -1662125091806054912 -1662125091845055744 -1662125091887056640 -1662125091929057536 -1662125091977058560 -1662125092022059520 -1662125092067060480 -1662125092106061312 -1662125092148062208 -1662125092193063168 -1662125092235064064 -1662125092277064960 -1662125092319065856 -1662125092361066752 -1662125092406067712 -1662125092451068672 -1662125092496069632 -1662125092535070464 -1662125092580071424 -1662125092622072320 -1662125092667073280 -1662125092709074176 -1662125092751075072 -1662125092796076032 -1662125092838076928 -1662125092883077888 -1662125092925078784 -1662125092967079680 -1662125093012080640 -1662125093054081536 -1662125093102082560 -1662125093141083392 -1662125093183084288 -1662125093219085056 -1662125093261085952 -1662125093303086848 -1662125093348087808 -1662125093393088768 -1662125093435089664 -1662125093477090560 -1662125093522091520 -1662125093564092416 -1662125093606093312 -1662125093648094208 -1662125093690095104 -1662125093732096000 -1662125093771096832 -1662125093816097792 -1662125093858098688 -1662125093900099584 -1662125093942100480 -1662125093981101312 -1662125094023102208 -1662125094065103104 -1662125094110104064 -1662125094152104960 -1662125094194105856 -1662125094239106816 -1662125094284107776 -1662125094329108736 -1662125094377109760 -1662125094422110720 -1662125094467111680 -1662125094506112512 -1662125094548113408 -1662125094590114304 -1662125094638115328 -1662125094680116224 -1662125094722117120 -1662125094770118144 -1662125094815119104 -1662125094860120064 -1662125094908121088 -1662125094950121984 -1662125094995122944 -1662125095040123904 -1662125095085124864 -1662125095127125760 -1662125095169126656 -1662125095214127616 -1662125095253128448 -1662125095298129408 -1662125095340130304 -1662125095382131200 -1662125095424132096 -1662125095475133184 -1662125095517134080 -1662125095568135168 -1662125095613136128 -1662125095649136896 -1662125095685137664 -1662125095727138560 -1662125095772139520 -1662125095817140480 -1662125095856141312 -1662125095901142272 -1662125095940143104 -1662125095985144064 -1662125096024144896 -1662125096069145856 -1662125096114146816 -1662125096159147776 -1662125096201148672 -1662125096246149632 -1662125096291150592 -1662125096336151552 -1662125096381152512 -1662125096423153408 -1662125096465154304 -1662125096510155264 -1662125096555156224 -1662125096600157184 -1662125096648158208 -1662125096693159168 -1662125096732160000 -1662125096780161024 -1662125096819161856 -1662125096870162944 -1662125096909163776 -1662125096951164672 -1662125096993165568 -1662125097035166464 -1662125097080167424 -1662125097125168384 -1662125097170169344 -1662125097212170240 -1662125097251171072 -1662125097296172032 -1662125097338172928 -1662125097383173888 -1662125097428174848 -1662125097467175680 -1662125097512176640 -1662125097554177536 -1662125097596178432 -1662125097638179328 -1662125097680180224 -1662125097722181120 -1662125097764182016 -1662125097806182912 -1662125097848183808 -1662125097899184896 -1662125097944185856 -1662125097992186880 -1662125098034187776 -1662125098076188672 -1662125098118189568 -1662125098160190464 -1662125098205191424 -1662125098247192320 -1662125098289193216 -1662125098328194048 -1662125098373195008 -1662125098415195904 -1662125098457196800 -1662125098502197760 -1662125098544198656 -1662125098586199552 -1662125098637200640 -1662125098682201600 -1662125098724202496 -1662125098772203520 -1662125098814204416 -1662125098850205184 -1662125098892206080 -1662125098937207040 -1662125098985208064 -1662125099027208960 -1662125099072209920 -1662125099114210816 -1662125099153211648 -1662125099195212544 -1662125099240213504 -1662125099282214400 -1662125099330215424 -1662125099378216448 -1662125099423217408 -1662125099468218368 -1662125099510219264 -1662125099555220224 -1662125099600221184 -1662125099645222144 -1662125099687223040 -1662125099732224000 -1662125099774224896 -1662125099816225792 -1662125099861226752 -1662125099906227712 -1662125099951228672 -1662125099996229632 -1662125100041230592 -1662125100083231488 -1662125100122232320 -1662125100161233152 -1662125100209234176 -1662125100251235072 -1662125100296236032 -1662125100338236928 -1662125100383237888 -1662125100428238848 -1662125100470239744 -1662125100515240704 -1662125100551241472 -1662125100596242432 -1662125100635243264 -1662125100680244224 -1662125100722245120 -1662125100764246016 -1662125100806246912 -1662125100845247744 -1662125100890248704 -1662125100932249600 -1662125100977250560 -1662125101016251392 -1662125101061252352 -1662125101103253248 -1662125101145254144 -1662125101187255040 -1662125101229255936 -1662125101271256832 -1662125101316257792 -1662125101364258816 -1662125101412259840 -1662125101457260800 -1662125101499261696 -1662125101541262592 -1662125101580263424 -1662125101625264384 -1662125101673265408 -1662125101715266304 -1662125101760267264 -1662125101802268160 -1662125101844269056 -1662125101892270080 -1662125101934270976 -1662125101979271936 -1662125102027272960 -1662125102072273920 -1662125102114274816 -1662125102162275840 -1662125102204276736 -1662125102240277504 -1662125102279278336 -1662125102318279168 -1662125102363280128 -1662125102405281024 -1662125102441281792 -1662125102480282624 -1662125102522283520 -1662125102567284480 -1662125102612285440 -1662125102654286336 -1662125102696287232 -1662125102735288064 -1662125102777288960 -1662125102828290048 -1662125102870290944 -1662125102918291968 -1662125102963292928 -1662125103008293888 -1662125103050294784 -1662125103092295680 -1662125103137296640 -1662125103179297536 -1662125103221298432 -1662125103269299456 -1662125103308300288 -1662125103356301312 -1662125103401302272 -1662125103446303232 -1662125103485304064 -1662125103524304896 -1662125103563305728 -1662125103602306560 -1662125103644307456 -1662125103686308352 -1662125103728309248 -1662125103770310144 -1662125103812311040 -1662125103854311936 -1662125103896312832 -1662125103938313728 -1662125103980314624 -1662125104022315520 -1662125104064316416 -1662125104109317376 -1662125104151318272 -1662125104196319232 -1662125104241320192 -1662125104286321152 -1662125104328322048 -1662125104370322944 -1662125104412323840 -1662125104457324800 -1662125104496325632 -1662125104541326592 -1662125104592327680 -1662125104637328640 -1662125104682329600 -1662125104724330496 -1662125104769331456 -1662125104814332416 -1662125104859333376 -1662125104901334272 -1662125104952335360 -1662125104994336256 -1662125105036337152 -1662125105078338048 -1662125105126339072 -1662125105168339968 -1662125105210340864 -1662125105252341760 -1662125105294342656 -1662125105336343552 -1662125105381344512 -1662125105423345408 -1662125105468346368 -1662125105510347264 -1662125105552348160 -1662125105603349248 -1662125105648350208 -1662125105690351104 -1662125105729351936 -1662125105774352896 -1662125105819353856 -1662125105861354752 -1662125105906355712 -1662125105957356800 -1662125106002357760 -1662125106044358656 -1662125106089359616 -1662125106137360640 -1662125106176361472 -1662125106218362368 -1662125106260363264 -1662125106305364224 -1662125106350365184 -1662125106395366144 -1662125106440367104 -1662125106485368064 -1662125106527368960 -1662125106566369792 -1662125106611370752 -1662125106656371712 -1662125106701372672 -1662125106743373568 -1662125106791374592 -1662125106833375488 -1662125106878376448 -1662125106917377280 -1662125106959378176 -1662125107004379136 -1662125107046380032 -1662125107085380864 -1662125107133381888 -1662125107172382720 -1662125107208383488 -1662125107253384448 -1662125107298385408 -1662125107346386432 -1662125107388387328 -1662125107430388224 -1662125107472389120 -1662125107514390016 -1662125107553390848 -1662125107595391744 -1662125107637392640 -1662125107679393536 -1662125107718394368 -1662125107760395264 -1662125107802396160 -1662125107850397184 -1662125107895398144 -1662125107937399040 -1662125107982400000 -1662125108027400960 -1662125108069401856 -1662125108111402752 -1662125108156403712 -1662125108198404608 -1662125108240405504 -1662125108285406464 -1662125108333407488 -1662125108378408448 -1662125108423409408 -1662125108468410368 -1662125108507411200 -1662125108549412096 -1662125108588412928 -1662125108633413888 -1662125108672414720 -1662125108723415808 -1662125108765416704 -1662125108804417536 -1662125108849418496 -1662125108888419328 -1662125108933420288 -1662125108978421248 -1662125109017422080 -1662125109059422976 -1662125109101423872 -1662125109140424704 -1662125109185425664 -1662125109227426560 -1662125109269427456 -1662125109314428416 -1662125109359429376 -1662125109395430144 -1662125109437431040 -1662125109479431936 -1662125109521432832 -1662125109560433664 -1662125109602434560 -1662125109641435392 -1662125109689436416 -1662125109731437312 -1662125109776438272 -1662125109821439232 -1662125109860440064 -1662125109902440960 -1662125109944441856 -1662125109989442816 -1662125110028443648 -1662125110073444608 -1662125110121445632 -1662125110160446464 -1662125110202447360 -1662125110244448256 -1662125110286449152 -1662125110331450112 -1662125110370450944 -1662125110412451840 -1662125110457452800 -1662125110499453696 -1662125110544454656 -1662125110589455616 -1662125110631456512 -1662125110673457408 -1662125110715458304 -1662125110760459264 -1662125110808460288 -1662125110850461184 -1662125110889462016 -1662125110937463040 -1662125110988464128 -1662125111030465024 -1662125111078466048 -1662125111120466944 -1662125111162467840 -1662125111201468672 -1662125111243469568 -1662125111288470528 -1662125111330471424 -1662125111375472384 -1662125111414473216 -1662125111459474176 -1662125111501475072 -1662125111543475968 -1662125111585476864 -1662125111627477760 -1662125111672478720 -1662125111714479616 -1662125111759480576 -1662125111801481472 -1662125111843482368 -1662125111888483328 -1662125111930484224 -1662125111972485120 -1662125112017486080 -1662125112062487040 -1662125112107488000 -1662125112155489024 -1662125112197489920 -1662125112236490752 -1662125112278491648 -1662125112323492608 -1662125112368493568 -1662125112410494464 -1662125112452495360 -1662125112500496384 -1662125112539497216 -1662125112581498112 -1662125112623499008 -1662125112665499904 -1662125112704500736 -1662125112755501824 -1662125112794502656 -1662125112836503552 -1662125112881504512 -1662125112929505536 -1662125112977506560 -1662125113019507456 -1662125113064508416 -1662125113106509312 -1662125113151510272 -1662125113196511232 -1662125113238512128 -1662125113283513088 -1662125113322513920 -1662125113367514880 -1662125113415515904 -1662125113454516736 -1662125113496517632 -1662125113538518528 -1662125113583519488 -1662125113628520448 -1662125113670521344 -1662125113718522368 -1662125113763523328 -1662125113811524352 -1662125113853525248 -1662125113895526144 -1662125113940527104 -1662125113982528000 -1662125114021528832 -1662125114060529664 -1662125114099530496 -1662125114141531392 -1662125114183532288 -1662125114222533120 -1662125114267534080 -1662125114312535040 -1662125114357536000 -1662125114399536896 -1662125114441537792 -1662125114483538688 -1662125114531539712 -1662125114582540800 -1662125114624541696 -1662125114666542592 -1662125114708543488 -1662125114750544384 -1662125114792545280 -1662125114834546176 -1662125114876547072 -1662125114924548096 -1662125114969549056 -1662125115020550144 -1662125115065551104 -1662125115104551936 -1662125115146552832 -1662125115188553728 -1662125115233554688 -1662125115278555648 -1662125115323556608 -1662125115368557568 -1662125115410558464 -1662125115455559424 -1662125115497560320 -1662125115542561280 -1662125115581562112 -1662125115620562944 -1662125115662563840 -1662125115701564672 -1662125115746565632 -1662125115788566528 -1662125115833567488 -1662125115878568448 -1662125115923569408 -1662125115965570304 -1662125116007571200 -1662125116049572096 -1662125116094573056 -1662125116130573824 -1662125116175574784 -1662125116220575744 -1662125116268576768 -1662125116310577664 -1662125116349578496 -1662125116391579392 -1662125116436580352 -1662125116481581312 -1662125116526582272 -1662125116571583232 -1662125116607584000 -1662125116649584896 -1662125116691585792 -1662125116736586752 -1662125116781587712 -1662125116823588608 -1662125116862589440 -1662125116904590336 -1662125116943591168 -1662125116982592000 -1662125117027592960 -1662125117072593920 -1662125117117594880 -1662125117156595712 -1662125117201596672 -1662125117237597440 -1662125117276598272 -1662125117321599232 -1662125117363600128 -1662125117405601024 -1662125117447601920 -1662125117492602880 -1662125117537603840 -1662125117579604736 -1662125117618605568 -1662125117663606528 -1662125117705607424 -1662125117744608256 -1662125117789609216 -1662125117828610048 -1662125117870610944 -1662125117918611968 -1662125117963612928 -1662125118005613824 -1662125118047614720 -1662125118089615616 -1662125118131616512 -1662125118173617408 -1662125118215618304 -1662125118260619264 -1662125118299620096 -1662125118341620992 -1662125118386621952 -1662125118425622784 -1662125118470623744 -1662125118509624576 -1662125118554625536 -1662125118599626496 -1662125118641627392 -1662125118683628288 -1662125118725629184 -1662125118767630080 -1662125118809630976 -1662125118854631936 -1662125118896632832 -1662125118941633792 -1662125118980634624 -1662125119022635520 -1662125119070636544 -1662125119115637504 -1662125119154638336 -1662125119196639232 -1662125119238640128 -1662125119277640960 -1662125119322641920 -1662125119370642944 -1662125119415643904 -1662125119460644864 -1662125119505645824 -1662125119547646720 -1662125119580647424 -1662125119625648384 -1662125119670649344 -1662125119712650240 -1662125119754651136 -1662125119802652160 -1662125119844653056 -1662125119886653952 -1662125119928654848 -1662125119970655744 -1662125120012656640 -1662125120057657600 -1662125120102658560 -1662125120150659584 -1662125120195660544 -1662125120240661504 -1662125120282662400 -1662125120324663296 -1662125120369664256 -1662125120417665280 -1662125120459666176 -1662125120507667200 -1662125120555668224 -1662125120597669120 -1662125120639670016 -1662125120681670912 -1662125120723671808 -1662125120765672704 -1662125120804673536 -1662125120846674432 -1662125120885675264 -1662125120927676160 -1662125120969677056 -1662125121011677952 -1662125121053678848 -1662125121095679744 -1662125121137680640 -1662125121185681664 -1662125121230682624 -1662125121269683456 -1662125121311684352 -1662125121353685248 -1662125121398686208 -1662125121437687040 -1662125121488688128 -1662125121530689024 -1662125121575689984 -1662125121617690880 -1662125121662691840 -1662125121704692736 -1662125121749693696 -1662125121791694592 -1662125121833695488 -1662125121875696384 -1662125121920697344 -1662125121962698240 -1662125122007699200 -1662125122049700096 -1662125122091700992 -1662125122133701888 -1662125122175702784 -1662125122217703680 -1662125122259704576 -1662125122301705472 -1662125122340706304 -1662125122385707264 -1662125122430708224 -1662125122469709056 -1662125122511709952 -1662125122556710912 -1662125122601711872 -1662125122643712768 -1662125122685713664 -1662125122736714752 -1662125122778715648 -1662125122820716544 -1662125122868717568 -1662125122910718464 -1662125122952719360 -1662125122991720192 -1662125123033721088 -1662125123075721984 -1662125123120722944 -1662125123162723840 -1662125123201724672 -1662125123243725568 -1662125123285726464 -1662125123324727296 -1662125123366728192 -1662125123408729088 -1662125123453730048 -1662125123501731072 -1662125123543731968 -1662125123585732864 -1662125123627733760 -1662125123669734656 -1662125123717735680 -1662125123762736640 -1662125123804737536 -1662125123852738560 -1662125123891739392 -1662125123936740352 -1662125123975741184 -1662125124020742144 -1662125124059742976 -1662125124104743936 -1662125124146744832 -1662125124194745856 -1662125124239746816 -1662125124281747712 -1662125124329748736 -1662125124368749568 -1662125124410750464 -1662125124452751360 -1662125124494752256 -1662125124536753152 -1662125124578754048 -1662125124620754944 -1662125124665755904 -1662125124707756800 -1662125124746757632 -1662125124791758592 -1662125124833759488 -1662125124869760256 -1662125124911761152 -1662125124956762112 -1662125124998763008 -1662125125040763904 -1662125125085764864 -1662125125127765760 -1662125125172766720 -1662125125214767616 -1662125125262768640 -1662125125304769536 -1662125125346770432 -1662125125385771264 -1662125125427772160 -1662125125472773120 -1662125125514774016 -1662125125559774976 -1662125125601775872 -1662125125652776960 -1662125125700777984 -1662125125742778880 -1662125125790779904 -1662125125841780992 -1662125125883781888 -1662125125925782784 -1662125125976783872 -1662125126021784832 -1662125126066785792 -1662125126111786752 -1662125126153787648 -1662125126192788480 -1662125126231789312 -1662125126279790336 -1662125126321791232 -1662125126366792192 -1662125126408793088 -1662125126447793920 -1662125126495794944 -1662125126537795840 -1662125126582796800 -1662125126627797760 -1662125126669798656 -1662125126714799616 -1662125126753800448 -1662125126798801408 -1662125126831802112 -1662125126873803008 -1662125126915803904 -1662125126957804800 -1662125127002805760 -1662125127041806592 -1662125127089807616 -1662125127131808512 -1662125127170809344 -1662125127212810240 -1662125127254811136 -1662125127293811968 -1662125127335812864 -1662125127377813760 -1662125127419814656 -1662125127464815616 -1662125127503816448 -1662125127545817344 -1662125127584818176 -1662125127629819136 -1662125127677820160 -1662125127719821056 -1662125127761821952 -1662125127800822784 -1662125127842823680 -1662125127881824512 -1662125127926825472 -1662125127968826368 -1662125128007827200 -1662125128046828032 -1662125128088828928 -1662125128130829824 -1662125128175830784 -1662125128217831680 -1662125128259832576 -1662125128304833536 -1662125128340834304 -1662125128382835200 -1662125128424836096 -1662125128463836928 -1662125128508837888 -1662125128562839040 -1662125128610840064 -1662125128652840960 -1662125128697841920 -1662125128739842816 -1662125128781843712 -1662125128829844736 -1662125128871845632 -1662125128919846656 -1662125128958847488 -1662125129003848448 -1662125129045849344 -1662125129087850240 -1662125129126851072 -1662125129174852096 -1662125129219853056 -1662125129264854016 -1662125129306854912 -1662125129345855744 -1662125129390856704 -1662125129435857664 -1662125129480858624 -1662125129522859520 -1662125129567860480 -1662125129609861376 -1662125129651862272 -1662125129696863232 -1662125129738864128 -1662125129783865088 -1662125129825865984 -1662125129867866880 -1662125129912867840 -1662125129951868672 -1662125129993869568 -1662125130038870528 -1662125130083871488 -1662125130128872448 -1662125130167873280 -1662125130206874112 -1662125130248875008 -1662125130296876032 -1662125130338876928 -1662125130380877824 -1662125130422878720 -1662125130464879616 -1662125130506880512 -1662125130548881408 -1662125130593882368 -1662125130638883328 -1662125130680884224 -1662125130728885248 -1662125130767886080 -1662125130809886976 -1662125130854887936 -1662125130899888896 -1662125130941889792 -1662125130983890688 -1662125131025891584 -1662125131064892416 -1662125131109893376 -1662125131154894336 -1662125131196895232 -1662125131238896128 -1662125131283897088 -1662125131325897984 -1662125131367898880 -1662125131415899904 -1662125131457900800 -1662125131496901632 -1662125131541902592 -1662125131583903488 -1662125131625904384 -1662125131670905344 -1662125131712906240 -1662125131760907264 -1662125131805908224 -1662125131847909120 -1662125131892910080 -1662125131943911168 -1662125131988912128 -1662125132027912960 -1662125132066913792 -1662125132108914688 -1662125132153915648 -1662125132198916608 -1662125132243917568 -1662125132288918528 -1662125132330919424 -1662125132372920320 -1662125132417921280 -1662125132459922176 -1662125132504923136 -1662125132549924096 -1662125132594925056 -1662125132636925952 -1662125132675926784 -1662125132720927744 -1662125132759928576 -1662125132804929536 -1662125132849930496 -1662125132891931392 -1662125132933932288 -1662125132975933184 -1662125133020934144 -1662125133065935104 -1662125133107936000 -1662125133149936896 -1662125133191937792 -1662125133236938752 -1662125133278939648 -1662125133323940608 -1662125133365941504 -1662125133410942464 -1662125133452943360 -1662125133494944256 -1662125133536945152 -1662125133578946048 -1662125133626947072 -1662125133668947968 -1662125133710948864 -1662125133752949760 -1662125133791950592 -1662125133833951488 -1662125133878952448 -1662125133920953344 -1662125133962954240 -1662125134010955264 -1662125134055956224 -1662125134100957184 -1662125134148958208 -1662125134187959040 -1662125134229959936 -1662125134271960832 -1662125134313961728 -1662125134358962688 -1662125134403963648 -1662125134445964544 -1662125134490965504 -1662125134532966400 -1662125134577967360 -1662125134625968384 -1662125134670969344 -1662125134715970304 -1662125134757971200 -1662125134799972096 -1662125134847973120 -1662125134892974080 -1662125134937975040 -1662125134973975808 -1662125135018976768 -1662125135057977600 -1662125135102978560 -1662125135144979456 -1662125135192980480 -1662125135237981440 -1662125135279982336 -1662125135330983424 -1662125135378984448 -1662125135420985344 -1662125135465986304 -1662125135510987264 -1662125135549988096 -1662125135594989056 -1662125135639990016 -1662125135681990912 -1662125135726991872 -1662125135768992768 -1662125135807993600 -1662125135855994624 -1662125135903995648 -1662125135945996544 -1662125135987997440 -1662125136029998336 -1662125136071999232 -1662125136120000256 -1662125136165001216 -1662125136204002048 -1662125136243002880 -1662125136285003776 -1662125136330004736 -1662125136372005632 -1662125136414006528 -1662125136456007424 -1662125136501008384 -1662125136540009216 -1662125136585010176 -1662125136627011072 -1662125136663011840 -1662125136705012736 -1662125136750013696 -1662125136792014592 -1662125136834015488 -1662125136876016384 -1662125136921017344 -1662125136960018176 -1662125136999019008 -1662125137041019904 -1662125137083020800 -1662125137122021632 -1662125137164022528 -1662125137209023488 -1662125137251024384 -1662125137290025216 -1662125137329026048 -1662125137371026944 -1662125137416027904 -1662125137464028928 -1662125137509029888 -1662125137551030784 -1662125137593031680 -1662125137635032576 -1662125137677033472 -1662125137719034368 -1662125137770035456 -1662125137809036288 -1662125137851037184 -1662125137890038016 -1662125137932038912 -1662125137977039872 -1662125138016040704 -1662125138058041600 -1662125138100042496 -1662125138142043392 -1662125138181044224 -1662125138223045120 -1662125138268046080 -1662125138313047040 -1662125138358048000 -1662125138406049024 -1662125138457050112 -1662125138499051008 -1662125138547052032 -1662125138589052928 -1662125138634053888 -1662125138676054784 -1662125138721055744 -1662125138763056640 -1662125138811057664 -1662125138853058560 -1662125138895059456 -1662125138937060352 -1662125138979061248 -1662125139021062144 -1662125139063063040 -1662125139102063872 -1662125139144064768 -1662125139192065792 -1662125139237066752 -1662125139279067648 -1662125139318068480 -1662125139366069504 -1662125139408070400 -1662125139450071296 -1662125139492072192 -1662125139534073088 -1662125139585074176 -1662125139630075136 -1662125139675076096 -1662125139720077056 -1662125139762077952 -1662125139801078784 -1662125139843079680 -1662125139882080512 -1662125139924081408 -1662125139963082240 -1662125140005083136 -1662125140047084032 -1662125140089084928 -1662125140128085760 -1662125140173086720 -1662125140218087680 -1662125140263088640 -1662125140305089536 -1662125140347090432 -1662125140386091264 -1662125140428092160 -1662125140470093056 -1662125140518094080 -1662125140560094976 -1662125140602095872 -1662125140644096768 -1662125140689097728 -1662125140731098624 -1662125140779099648 -1662125140830100736 -1662125140872101632 -1662125140914102528 -1662125140959103488 -1662125141001104384 -1662125141040105216 -1662125141082106112 -1662125141124107008 -1662125141166107904 -1662125141211108864 -1662125141253109760 -1662125141298110720 -1662125141343111680 -1662125141382112512 -1662125141424113408 -1662125141466114304 -1662125141511115264 -1662125141553116160 -1662125141595117056 -1662125141640118016 -1662125141682118912 -1662125141724119808 -1662125141769120768 -1662125141817121792 -1662125141859122688 -1662125141904123648 -1662125141949124608 -1662125141994125568 -1662125142036126464 -1662125142075127296 -1662125142117128192 -1662125142159129088 -1662125142207130112 -1662125142252131072 -1662125142294131968 -1662125142336132864 -1662125142375133696 -1662125142420134656 -1662125142465135616 -1662125142507136512 -1662125142555137536 -1662125142600138496 -1662125142642139392 -1662125142681140224 -1662125142723141120 -1662125142765142016 -1662125142807142912 -1662125142849143808 -1662125142891144704 -1662125142936145664 -1662125142978146560 -1662125143026147584 -1662125143071148544 -1662125143113149440 -1662125143158150400 -1662125143197151232 -1662125143242152192 -1662125143290153216 -1662125143332154112 -1662125143377155072 -1662125143419155968 -1662125143473157120 -1662125143515158016 -1662125143560158976 -1662125143602159872 -1662125143641160704 -1662125143686161664 -1662125143725162496 -1662125143773163520 -1662125143818164480 -1662125143860165376 -1662125143911166464 -1662125143953167360 -1662125143992168192 -1662125144037169152 -1662125144085170176 -1662125144127171072 -1662125144172172032 -1662125144220173056 -1662125144268174080 -1662125144316175104 -1662125144355175936 -1662125144397176832 -1662125144442177792 -1662125144484178688 -1662125144526179584 -1662125144568180480 -1662125144610181376 -1662125144655182336 -1662125144703183360 -1662125144748184320 -1662125144793185280 -1662125144835186176 -1662125144883187200 -1662125144925188096 -1662125144970189056 -1662125145021190144 -1662125145072191232 -1662125145114192128 -1662125145156193024 -1662125145198193920 -1662125145240194816 -1662125145285195776 -1662125145333196800 -1662125145381197824 -1662125145426198784 -1662125145471199744 -1662125145513200640 -1662125145564201728 -1662125145600202496 -1662125145639203328 -1662125145684204288 -1662125145726205184 -1662125145762205952 -1662125145807206912 -1662125145849207808 -1662125145897208832 -1662125145939209728 -1662125145981210624 -1662125146029211648 -1662125146074212608 -1662125146119213568 -1662125146161214464 -1662125146203215360 -1662125146245216256 -1662125146290217216 -1662125146335218176 -1662125146380219136 -1662125146422220032 -1662125146464220928 -1662125146506221824 -1662125146545222656 -1662125146596223744 -1662125146638224640 -1662125146680225536 -1662125146722226432 -1662125146764227328 -1662125146809228288 -1662125146851229184 -1662125146893230080 -1662125146938231040 -1662125146977231872 -1662125147019232768 -1662125147061233664 -1662125147106234624 -1662125147151235584 -1662125147193236480 -1662125147235237376 -1662125147280238336 -1662125147325239296 -1662125147370240256 -1662125147415241216 -1662125147457242112 -1662125147499243008 -1662125147541243904 -1662125147583244800 -1662125147628245760 -1662125147673246720 -1662125147715247616 -1662125147757248512 -1662125147796249344 -1662125147841250304 -1662125147883251200 -1662125147931252224 -1662125147973253120 -1662125148012253952 -1662125148057254912 -1662125148099255808 -1662125148138256640 -1662125148186257664 -1662125148228258560 -1662125148270259456 -1662125148312260352 -1662125148354261248 -1662125148399262208 -1662125148441263104 -1662125148483264000 -1662125148528264960 -1662125148567265792 -1662125148618266880 -1662125148657267712 -1662125148702268672 -1662125148744269568 -1662125148786270464 -1662125148834271488 -1662125148879272448 -1662125148927273472 -1662125148975274496 -1662125149020275456 -1662125149062276352 -1662125149104277248 -1662125149146278144 -1662125149197279232 -1662125149242280192 -1662125149284281088 -1662125149329282048 -1662125149377283072 -1662125149419283968 -1662125149458284800 -1662125149494285568 -1662125149530286336 -1662125149572287232 -1662125149617288192 -1662125149659289088 -1662125149698289920 -1662125149743290880 -1662125149788291840 -1662125149830292736 -1662125149875293696 -1662125149920294656 -1662125149962295552 -1662125150007296512 -1662125150049297408 -1662125150091298304 -1662125150133299200 -1662125150184300288 -1662125150229301248 -1662125150271302144 -1662125150313303040 -1662125150358304000 -1662125150400304896 -1662125150445305856 -1662125150484306688 -1662125150526307584 -1662125150577308672 -1662125150622309632 -1662125150667310592 -1662125150709311488 -1662125150754312448 -1662125150796313344 -1662125150841314304 -1662125150883315200 -1662125150928316160 -1662125150973317120 -1662125151015318016 -1662125151054318848 -1662125151093319680 -1662125151135320576 -1662125151174321408 -1662125151213322240 -1662125151258323200 -1662125151300324096 -1662125151345325056 -1662125151393326080 -1662125151435326976 -1662125151477327872 -1662125151522328832 -1662125151561329664 -1662125151606330624 -1662125151651331584 -1662125151696332544 -1662125151738333440 -1662125151780334336 -1662125151825335296 -1662125151870336256 -1662125151912337152 -1662125151960338176 -1662125152002339072 -1662125152044339968 -1662125152086340864 -1662125152131341824 -1662125152173342720 -1662125152215343616 -1662125152254344448 -1662125152296345344 -1662125152344346368 -1662125152389347328 -1662125152428348160 -1662125152473349120 -1662125152518350080 -1662125152563351040 -1662125152611352064 -1662125152653352960 -1662125152698353920 -1662125152743354880 -1662125152782355712 -1662125152824356608 -1662125152869357568 -1662125152914358528 -1662125152956359424 -1662125152992360192 -1662125153031361024 -1662125153067361792 -1662125153109362688 -1662125153154363648 -1662125153199364608 -1662125153241365504 -1662125153283366400 -1662125153325367296 -1662125153367368192 -1662125153412369152 -1662125153454370048 -1662125153490370816 -1662125153535371776 -1662125153580372736 -1662125153622373632 -1662125153664374528 -1662125153706375424 -1662125153748376320 -1662125153790377216 -1662125153835378176 -1662125153874379008 -1662125153916379904 -1662125153958380800 -1662125154000381696 -1662125154045382656 -1662125154093383680 -1662125154135384576 -1662125154180385536 -1662125154228386560 -1662125154270387456 -1662125154312388352 -1662125154354389248 -1662125154402390272 -1662125154447391232 -1662125154492392192 -1662125154534393088 -1662125154576393984 -1662125154618394880 -1662125154660395776 -1662125154699396608 -1662125154741397504 -1662125154783398400 -1662125154831399424 -1662125154873400320 -1662125154915401216 -1662125154957402112 -1662125154996402944 -1662125155038403840 -1662125155080404736 -1662125155119405568 -1662125155167406592 -1662125155206407424 -1662125155245408256 -1662125155287409152 -1662125155332410112 -1662125155377411072 -1662125155419411968 -1662125155464412928 -1662125155503413760 -1662125155548414720 -1662125155593415680 -1662125155632416512 -1662125155671417344 -1662125155713418240 -1662125155755419136 -1662125155797420032 -1662125155842420992 -1662125155887421952 -1662125155929422848 -1662125155971423744 -1662125156013424640 -1662125156052425472 -1662125156094426368 -1662125156136427264 -1662125156181428224 -1662125156223429120 -1662125156265430016 -1662125156316431104 -1662125156355431936 -1662125156397432832 -1662125156436433664 -1662125156481434624 -1662125156523435520 -1662125156568436480 -1662125156610437376 -1662125156652438272 -1662125156697439232 -1662125156739440128 -1662125156778440960 -1662125156823441920 -1662125156865442816 -1662125156916443904 -1662125156958444800 -1662125157003445760 -1662125157051446784 -1662125157093447680 -1662125157138448640 -1662125157183449600 -1662125157228450560 -1662125157276451584 -1662125157321452544 -1662125157366453504 -1662125157414454528 -1662125157456455424 -1662125157498456320 -1662125157540457216 -1662125157582458112 -1662125157627459072 -1662125157672460032 -1662125157714460928 -1662125157759461888 -1662125157804462848 -1662125157846463744 -1662125157891464704 -1662125157933465600 -1662125157978466560 -1662125158026467584 -1662125158074468608 -1662125158116469504 -1662125158158470400 -1662125158200471296 -1662125158242472192 -1662125158284473088 -1662125158326473984 -1662125158368474880 -1662125158407475712 -1662125158449476608 -1662125158491477504 -1662125158536478464 -1662125158578479360 -1662125158626480384 -1662125158671481344 -1662125158713482240 -1662125158755483136 -1662125158800484096 -1662125158842484992 -1662125158890486016 -1662125158935486976 -1662125158980487936 -1662125159025488896 -1662125159067489792 -1662125159109490688 -1662125159151491584 -1662125159193492480 -1662125159235493376 -1662125159277494272 -1662125159319495168 -1662125159361496064 -1662125159406497024 -1662125159448497920 -1662125159490498816 -1662125159535499776 -1662125159583500800 -1662125159625501696 -1662125159667502592 -1662125159706503424 -1662125159742504192 -1662125159781505024 -1662125159823505920 -1662125159865506816 -1662125159913507840 -1662125159961508864 -1662125160003509760 -1662125160045510656 -1662125160090511616 -1662125160138512640 -1662125160180513536 -1662125160222514432 -1662125160261515264 -1662125160303516160 -1662125160348517120 -1662125160387517952 -1662125160432518912 -1662125160474519808 -1662125160519520768 -1662125160558521600 -1662125160597522432 -1662125160645523456 -1662125160687524352 -1662125160729525248 -1662125160771526144 -1662125160813527040 -1662125160855527936 -1662125160900528896 -1662125160942529792 -1662125160990530816 -1662125161038531840 -1662125161080532736 -1662125161128533760 -1662125161176534784 -1662125161218535680 -1662125161266536704 -1662125161314537728 -1662125161359538688 -1662125161401539584 -1662125161443540480 -1662125161491541504 -1662125161533542400 -1662125161578543360 -1662125161620544256 -1662125161662545152 -1662125161701545984 -1662125161749547008 -1662125161791547904 -1662125161833548800 -1662125161875549696 -1662125161923550720 -1662125161971551744 -1662125162013552640 -1662125162055553536 -1662125162100554496 -1662125162145555456 -1662125162187556352 -1662125162229557248 -1662125162271558144 -1662125162319559168 -1662125162355559936 -1662125162397560832 -1662125162442561792 -1662125162484562688 -1662125162532563712 -1662125162574564608 -1662125162616565504 -1662125162661566464 -1662125162703567360 -1662125162748568320 -1662125162793569280 -1662125162832570112 -1662125162877571072 -1662125162919571968 -1662125162961572864 -1662125163006573824 -1662125163048574720 -1662125163093575680 -1662125163138576640 -1662125163183577600 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt deleted file mode 100644 index 7283c7fd50..0000000000 --- a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_Algae_track2.txt +++ /dev/null @@ -1,2489 +0,0 @@ -1662120285510217728 -1662120285552218624 -1662120285594219520 -1662120285636220416 -1662120285681221376 -1662120285723222272 -1662120285768223232 -1662120285810224128 -1662120285858225152 -1662120285897225984 -1662120285936226816 -1662120285981227776 -1662120286023228672 -1662120286065229568 -1662120286107230464 -1662120286149231360 -1662120286191232256 -1662120286233233152 -1662120286281234176 -1662120286323235072 -1662120286371236096 -1662120286413236992 -1662120286455237888 -1662120286497238784 -1662120286539239680 -1662120286581240576 -1662120286620241408 -1662120286662242304 -1662120286701243136 -1662120286740243968 -1662120286782244864 -1662120286827245824 -1662120286875246848 -1662120286920247808 -1662120286968248832 -1662120287010249728 -1662120287052250624 -1662120287097251584 -1662120287139252480 -1662120287181253376 -1662120287220254208 -1662120287265255168 -1662120287307256064 -1662120287352257024 -1662120287397257984 -1662120287436258816 -1662120287475259648 -1662120287517260544 -1662120287559261440 -1662120287601262336 -1662120287646263296 -1662120287688264192 -1662120287733265152 -1662120287772265984 -1662120287814266880 -1662120287862267904 -1662120287907268864 -1662120287952269824 -1662120288000270848 -1662120288039271680 -1662120288087272704 -1662120288135273728 -1662120288177274624 -1662120288225275648 -1662120288267276544 -1662120288309277440 -1662120288354278400 -1662120288396279296 -1662120288438280192 -1662120288483281152 -1662120288528282112 -1662120288576283136 -1662120288624284160 -1662120288666285056 -1662120288708285952 -1662120288747286784 -1662120288792287744 -1662120288834288640 -1662120288873289472 -1662120288918290432 -1662120288963291392 -1662120289008292352 -1662120289050293248 -1662120289092294144 -1662120289131294976 -1662120289176295936 -1662120289218296832 -1662120289260297728 -1662120289311298816 -1662120289356299776 -1662120289398300672 -1662120289440301568 -1662120289485302528 -1662120289527303424 -1662120289569304320 -1662120289608305152 -1662120289653306112 -1662120289695307008 -1662120289734307840 -1662120289773308672 -1662120289812309504 -1662120289854310400 -1662120289896311296 -1662120289938312192 -1662120289983313152 -1662120290025314048 -1662120290067314944 -1662120290115315968 -1662120290157316864 -1662120290202317824 -1662120290247318784 -1662120290292319744 -1662120290340320768 -1662120290385321728 -1662120290430322688 -1662120290478323712 -1662120290526324736 -1662120290568325632 -1662120290613326592 -1662120290652327424 -1662120290694328320 -1662120290730329088 -1662120290772329984 -1662120290814330880 -1662120290853331712 -1662120290898332672 -1662120290937333504 -1662120290979334400 -1662120291021335296 -1662120291060336128 -1662120291108337152 -1662120291150338048 -1662120291195339008 -1662120291240339968 -1662120291291341056 -1662120291336342016 -1662120291381342976 -1662120291423343872 -1662120291477345024 -1662120291519345920 -1662120291567346944 -1662120291606347776 -1662120291648348672 -1662120291690349568 -1662120291735350528 -1662120291777351424 -1662120291825352448 -1662120291870353408 -1662120291912354304 -1662120291954355200 -1662120291996356096 -1662120292041357056 -1662120292080357888 -1662120292119358720 -1662120292167359744 -1662120292209360640 -1662120292251361536 -1662120292293362432 -1662120292335363328 -1662120292377364224 -1662120292419365120 -1662120292470366208 -1662120292512367104 -1662120292560368128 -1662120292602369024 -1662120292647369984 -1662120292692370944 -1662120292734371840 -1662120292776372736 -1662120292818373632 -1662120292860374528 -1662120292902375424 -1662120292947376384 -1662120292989377280 -1662120293031378176 -1662120293076379136 -1662120293118380032 -1662120293160380928 -1662120293202381824 -1662120293244382720 -1662120293289383680 -1662120293331384576 -1662120293376385536 -1662120293418386432 -1662120293463387392 -1662120293505388288 -1662120293547389184 -1662120293592390144 -1662120293634391040 -1662120293679392000 -1662120293724392960 -1662120293766393856 -1662120293811394816 -1662120293856395776 -1662120293895396608 -1662120293940397568 -1662120293988398592 -1662120294033399552 -1662120294078400512 -1662120294123401472 -1662120294168402432 -1662120294213403392 -1662120294249404160 -1662120294291405056 -1662120294330405888 -1662120294372406784 -1662120294420407808 -1662120294462408704 -1662120294507409664 -1662120294546410496 -1662120294588411392 -1662120294633412352 -1662120294684413440 -1662120294729414400 -1662120294774415360 -1662120294816416256 -1662120294861417216 -1662120294903418112 -1662120294951419136 -1662120294996420096 -1662120295044421120 -1662120295083421952 -1662120295128422912 -1662120295170423808 -1662120295218424832 -1662120295263425792 -1662120295305426688 -1662120295347427584 -1662120295389428480 -1662120295434429440 -1662120295476430336 -1662120295521431296 -1662120295566432256 -1662120295605433088 -1662120295647433984 -1662120295692434944 -1662120295734435840 -1662120295776436736 -1662120295818437632 -1662120295866438656 -1662120295911439616 -1662120295953440512 -1662120295995441408 -1662120296037442304 -1662120296082443264 -1662120296130444288 -1662120296169445120 -1662120296208445952 -1662120296250446848 -1662120296295447808 -1662120296337448704 -1662120296379449600 -1662120296421450496 -1662120296457451264 -1662120296499452160 -1662120296541453056 -1662120296589454080 -1662120296637455104 -1662120296682456064 -1662120296724456960 -1662120296766457856 -1662120296808458752 -1662120296850459648 -1662120296892460544 -1662120296937461504 -1662120296979462400 -1662120297021463296 -1662120297066464256 -1662120297111465216 -1662120297153466112 -1662120297201467136 -1662120297246468096 -1662120297288468992 -1662120297327469824 -1662120297372470784 -1662120297414471680 -1662120297459472640 -1662120297504473600 -1662120297552474624 -1662120297597475584 -1662120297639476480 -1662120297684477440 -1662120297726478336 -1662120297765479168 -1662120297804480000 -1662120297843480832 -1662120297885481728 -1662120297927482624 -1662120297972483584 -1662120298005484288 -1662120298053485312 -1662120298095486208 -1662120298137487104 -1662120298179488000 -1662120298227489024 -1662120298269489920 -1662120298311490816 -1662120298350491648 -1662120298395492608 -1662120298446493696 -1662120298491494656 -1662120298533495552 -1662120298575496448 -1662120298617497344 -1662120298662498304 -1662120298713499392 -1662120298755500288 -1662120298800501248 -1662120298842502144 -1662120298884503040 -1662120298926503936 -1662120298968504832 -1662120299010505728 -1662120299052506624 -1662120299094507520 -1662120299136508416 -1662120299178509312 -1662120299220510208 -1662120299262511104 -1662120299307512064 -1662120299352513024 -1662120299391513856 -1662120299433514752 -1662120299481515776 -1662120299523516672 -1662120299568517632 -1662120299613518592 -1662120299658519552 -1662120299700520448 -1662120299742521344 -1662120299787522304 -1662120299832523264 -1662120299874524160 -1662120299916525056 -1662120299961526016 -1662120300006526976 -1662120300048527872 -1662120300084528640 -1662120300126529536 -1662120300171530496 -1662120300216531456 -1662120300261532416 -1662120300303533312 -1662120300348534272 -1662120300390535168 -1662120300432536064 -1662120300474536960 -1662120300516537856 -1662120300564538880 -1662120300609539840 -1662120300651540736 -1662120300693541632 -1662120300735542528 -1662120300777543424 -1662120300822544384 -1662120300864545280 -1662120300915546368 -1662120300960547328 -1662120301002548224 -1662120301044549120 -1662120301086550016 -1662120301128550912 -1662120301176551936 -1662120301221552896 -1662120301260553728 -1662120301308554752 -1662120301353555712 -1662120301401556736 -1662120301443557632 -1662120301485558528 -1662120301527559424 -1662120301572560384 -1662120301614561280 -1662120301662562304 -1662120301704563200 -1662120301746564096 -1662120301785564928 -1662120301827565824 -1662120301869566720 -1662120301911567616 -1662120301950568448 -1662120301995569408 -1662120302037570304 -1662120302085571328 -1662120302130572288 -1662120302175573248 -1662120302220574208 -1662120302265575168 -1662120302307576064 -1662120302346576896 -1662120302391577856 -1662120302439578880 -1662120302484579840 -1662120302532580864 -1662120302574581760 -1662120302616582656 -1662120302658583552 -1662120302697584384 -1662120302742585344 -1662120302787586304 -1662120302829587200 -1662120302871588096 -1662120302916589056 -1662120302958589952 -1662120303000590848 -1662120303051591936 -1662120303099592960 -1662120303141593856 -1662120303183594752 -1662120303231595776 -1662120303279596800 -1662120303321597696 -1662120303360598528 -1662120303399599360 -1662120303450600448 -1662120303495601408 -1662120303537602304 -1662120303576603136 -1662120303618604032 -1662120303657604864 -1662120303702605824 -1662120303750606848 -1662120303792607744 -1662120303837608704 -1662120303879609600 -1662120303930610688 -1662120303975611648 -1662120304017612544 -1662120304059613440 -1662120304104614400 -1662120304149615360 -1662120304191616256 -1662120304236617216 -1662120304278618112 -1662120304320619008 -1662120304362619904 -1662120304401620736 -1662120304443621632 -1662120304485622528 -1662120304530623488 -1662120304578624512 -1662120304623625472 -1662120304665626368 -1662120304710627328 -1662120304755628288 -1662120304800629248 -1662120304848630272 -1662120304893631232 -1662120304938632192 -1662120304980633088 -1662120305022633984 -1662120305067634944 -1662120305112635904 -1662120305148636672 -1662120305196637696 -1662120305235638528 -1662120305274639360 -1662120305319640320 -1662120305364641280 -1662120305403642112 -1662120305445643008 -1662120305490643968 -1662120305535644928 -1662120305577645824 -1662120305619646720 -1662120305664647680 -1662120305703648512 -1662120305745649408 -1662120305790650368 -1662120305838651392 -1662120305883652352 -1662120305928653312 -1662120305970654208 -1662120306012655104 -1662120306054656000 -1662120306102657024 -1662120306150658048 -1662120306192658944 -1662120306237659904 -1662120306282660864 -1662120306324661760 -1662120306369662720 -1662120306417663744 -1662120306462664704 -1662120306507665664 -1662120306549666560 -1662120306591667456 -1662120306633668352 -1662120306678669312 -1662120306723670272 -1662120306765671168 -1662120306810672128 -1662120306855673088 -1662120306897673984 -1662120306939674880 -1662120306978675712 -1662120307017676544 -1662120307065677568 -1662120307104678400 -1662120307149679360 -1662120307191680256 -1662120307236681216 -1662120307281682176 -1662120307323683072 -1662120307365683968 -1662120307407684864 -1662120307449685760 -1662120307491686656 -1662120307527687424 -1662120307572688384 -1662120307614689280 -1662120307656690176 -1662120307707691264 -1662120307752692224 -1662120307794693120 -1662120307836694016 -1662120307878694912 -1662120307923695872 -1662120307971696896 -1662120308016697856 -1662120308058698752 -1662120308100699648 -1662120308142700544 -1662120308181701376 -1662120308226702336 -1662120308271703296 -1662120308313704192 -1662120308355705088 -1662120308403706112 -1662120308451707136 -1662120308496708096 -1662120308538708992 -1662120308580709888 -1662120308622710784 -1662120308661711616 -1662120308709712640 -1662120308751713536 -1662120308790714368 -1662120308835715328 -1662120308880716288 -1662120308922717184 -1662120308964718080 -1662120309003718912 -1662120309045719808 -1662120309090720768 -1662120309135721728 -1662120309177722624 -1662120309216723456 -1662120309258724352 -1662120309300725248 -1662120309345726208 -1662120309390727168 -1662120309435728128 -1662120309474728960 -1662120309516729856 -1662120309561730816 -1662120309603731712 -1662120309645732608 -1662120309690733568 -1662120309729734400 -1662120309777735424 -1662120309819736320 -1662120309864737280 -1662120309915738368 -1662120309957739264 -1662120310002740224 -1662120310044741120 -1662120310092742144 -1662120310134743040 -1662120310179744000 -1662120310224744960 -1662120310266745856 -1662120310311746816 -1662120310353747712 -1662120310395748608 -1662120310440749568 -1662120310482750464 -1662120310527751424 -1662120310572752384 -1662120310611753216 -1662120310662754304 -1662120310704755200 -1662120310746756096 -1662120310788756992 -1662120310839758080 -1662120310881758976 -1662120310923759872 -1662120310971760896 -1662120311016761856 -1662120311061762816 -1662120311109763840 -1662120311151764736 -1662120311190765568 -1662120311241766656 -1662120311283767552 -1662120311325768448 -1662120311367769344 -1662120311412770304 -1662120311454771200 -1662120311505772288 -1662120311547773184 -1662120311592774144 -1662120311634775040 -1662120311676775936 -1662120311721776896 -1662120311763777792 -1662120311808778752 -1662120311850779648 -1662120311892780544 -1662120311937781504 -1662120311982782464 -1662120312027783424 -1662120312063784192 -1662120312108785152 -1662120312150786048 -1662120312195787008 -1662120312234787840 -1662120312279788800 -1662120312327789824 -1662120312369790720 -1662120312411791616 -1662120312453792512 -1662120312495793408 -1662120312540794368 -1662120312588795392 -1662120312636796416 -1662120312678797312 -1662120312723798272 -1662120312765799168 -1662120312804800000 -1662120312849800960 -1662120312894801920 -1662120312939802880 -1662120312981803776 -1662120313026804736 -1662120313068805632 -1662120313110806528 -1662120313152807424 -1662120313197808384 -1662120313242809344 -1662120313284810240 -1662120313326811136 -1662120313371812096 -1662120313413812992 -1662120313455813888 -1662120313497814784 -1662120313545815808 -1662120313584816640 -1662120313626817536 -1662120313668818432 -1662120313713819392 -1662120313755820288 -1662120313797821184 -1662120313839822080 -1662120313884823040 -1662120313929824000 -1662120313977825024 -1662120314031826176 -1662120314073827072 -1662120314115827968 -1662120314160828928 -1662120314202829824 -1662120314247830784 -1662120314295831808 -1662120314340832768 -1662120314379833600 -1662120314421834496 -1662120314466835456 -1662120314508836352 -1662120314553837312 -1662120314598838272 -1662120314637839104 -1662120314682840064 -1662120314724840960 -1662120314772841984 -1662120314811842816 -1662120314856843776 -1662120314898844672 -1662120314940845568 -1662120314988846592 -1662120315033847552 -1662120315078848512 -1662120315123849472 -1662120315168850432 -1662120315210851328 -1662120315252852224 -1662120315294853120 -1662120315345854208 -1662120315390855168 -1662120315435856128 -1662120315489857280 -1662120315537858304 -1662120315582859264 -1662120315630860288 -1662120315675861248 -1662120315717862144 -1662120315762863104 -1662120315807864064 -1662120315849864960 -1662120315891865856 -1662120315933866752 -1662120315975867648 -1662120316017868544 -1662120316062869504 -1662120316104870400 -1662120316149871360 -1662120316191872256 -1662120316230873088 -1662120316275874048 -1662120316317874944 -1662120316362875904 -1662120316404876800 -1662120316449877760 -1662120316494878720 -1662120316539879680 -1662120316581880576 -1662120316620881408 -1662120316665882368 -1662120316704883200 -1662120316746884096 -1662120316791885056 -1662120316836886016 -1662120316878886912 -1662120316917887744 -1662120316962888704 -1662120317001889536 -1662120317049890560 -1662120317100891648 -1662120317142892544 -1662120317187893504 -1662120317232894464 -1662120317277895424 -1662120317322896384 -1662120317367897344 -1662120317409898240 -1662120317454899200 -1662120317496900096 -1662120317544901120 -1662120317586902016 -1662120317628902912 -1662120317673903872 -1662120317715904768 -1662120317757905664 -1662120317802906624 -1662120317844907520 -1662120317886908416 -1662120317934909440 -1662120317976910336 -1662120318018911232 -1662120318060912128 -1662120318102913024 -1662120318147913984 -1662120318192914944 -1662120318231915776 -1662120318270916608 -1662120318315917568 -1662120318357918464 -1662120318399919360 -1662120318447920384 -1662120318492921344 -1662120318534922240 -1662120318576923136 -1662120318618924032 -1662120318663924992 -1662120318708925952 -1662120318753926912 -1662120318798927872 -1662120318843928832 -1662120318891929856 -1662120318936930816 -1662120318978931712 -1662120319017932544 -1662120319062933504 -1662120319104934400 -1662120319149935360 -1662120319191936256 -1662120319236937216 -1662120319278938112 -1662120319323939072 -1662120319365939968 -1662120319413940992 -1662120319455941888 -1662120319500942848 -1662120319542943744 -1662120319587944704 -1662120319632945664 -1662120319680946688 -1662120319725947648 -1662120319770948608 -1662120319812949504 -1662120319854950400 -1662120319899951360 -1662120319941952256 -1662120319986953216 -1662120320028954112 -1662120320073955072 -1662120320115955968 -1662120320160956928 -1662120320202957824 -1662120320247958784 -1662120320295959808 -1662120320340960768 -1662120320379961600 -1662120320424962560 -1662120320469963520 -1662120320511964416 -1662120320556965376 -1662120320601966336 -1662120320646967296 -1662120320688968192 -1662120320727969024 -1662120320769969920 -1662120320814970880 -1662120320862971904 -1662120320904972800 -1662120320946973696 -1662120320988974592 -1662120321033975552 -1662120321075976448 -1662120321120977408 -1662120321162978304 -1662120321210979328 -1662120321255980288 -1662120321306981376 -1662120321348982272 -1662120321393983232 -1662120321438984192 -1662120321477985024 -1662120321522985984 -1662120321561986816 -1662120321603987712 -1662120321651988736 -1662120321693989632 -1662120321732990464 -1662120321780991488 -1662120321822992384 -1662120321858993152 -1662120321900994048 -1662120321942994944 -1662120321987995904 -1662120322026996736 -1662120322068997632 -1662120322110998528 -1662120322149999360 -1662120322195000320 -1662120322237001216 -1662120322285002240 -1662120322330003200 -1662120322372004096 -1662120322417005056 -1662120322459005952 -1662120322501006848 -1662120322543007744 -1662120322585008640 -1662120322624009472 -1662120322666010368 -1662120322708011264 -1662120322750012160 -1662120322789012992 -1662120322828013824 -1662120322882014976 -1662120322924015872 -1662120322975016960 -1662120323014017792 -1662120323056018688 -1662120323101019648 -1662120323146020608 -1662120323185021440 -1662120323227022336 -1662120323272023296 -1662120323317024256 -1662120323359025152 -1662120323401026048 -1662120323443026944 -1662120323488027904 -1662120323530028800 -1662120323575029760 -1662120323620030720 -1662120323668031744 -1662120323710032640 -1662120323749033472 -1662120323794034432 -1662120323836035328 -1662120323875036160 -1662120323920037120 -1662120323959037952 -1662120324004038912 -1662120324046039808 -1662120324091040768 -1662120324139041792 -1662120324178042624 -1662120324223043584 -1662120324265044480 -1662120324304045312 -1662120324343046144 -1662120324385047040 -1662120324427047936 -1662120324469048832 -1662120324517049856 -1662120324559050752 -1662120324601051648 -1662120324640052480 -1662120324682053376 -1662120324724054272 -1662120324766055168 -1662120324808056064 -1662120324853057024 -1662120324901058048 -1662120324943058944 -1662120324988059904 -1662120325036060928 -1662120325078061824 -1662120325120062720 -1662120325159063552 -1662120325204064512 -1662120325255065600 -1662120325300066560 -1662120325342067456 -1662120325384068352 -1662120325429069312 -1662120325468070144 -1662120325510071040 -1662120325549071872 -1662120325603073024 -1662120325642073856 -1662120325687074816 -1662120325726075648 -1662120325768076544 -1662120325810077440 -1662120325852078336 -1662120325894079232 -1662120325939080192 -1662120325984081152 -1662120326026082048 -1662120326074083072 -1662120326119084032 -1662120326164084992 -1662120326209085952 -1662120326257086976 -1662120326302087936 -1662120326344088832 -1662120326386089728 -1662120326428090624 -1662120326470091520 -1662120326512092416 -1662120326554093312 -1662120326596094208 -1662120326638095104 -1662120326683096064 -1662120326725096960 -1662120326767097856 -1662120326809098752 -1662120326857099776 -1662120326902100736 -1662120326947101696 -1662120326995102720 -1662120327040103680 -1662120327088104704 -1662120327133105664 -1662120327175106560 -1662120327220107520 -1662120327268108544 -1662120327310109440 -1662120327355110400 -1662120327394111232 -1662120327436112128 -1662120327490113280 -1662120327532114176 -1662120327574115072 -1662120327619116032 -1662120327661116928 -1662120327706117888 -1662120327748118784 -1662120327793119744 -1662120327832120576 -1662120327874121472 -1662120327919122432 -1662120327964123392 -1662120328009124352 -1662120328054125312 -1662120328099126272 -1662120328144127232 -1662120328189128192 -1662120328231129088 -1662120328273129984 -1662120328312130816 -1662120328354131712 -1662120328396132608 -1662120328441133568 -1662120328486134528 -1662120328531135488 -1662120328573136384 -1662120328612137216 -1662120328660138240 -1662120328705139200 -1662120328747140096 -1662120328795141120 -1662120328837142016 -1662120328879142912 -1662120328921143808 -1662120328963144704 -1662120329005145600 -1662120329047146496 -1662120329089147392 -1662120329137148416 -1662120329182149376 -1662120329227150336 -1662120329272151296 -1662120329317152256 -1662120329362153216 -1662120329410154240 -1662120329455155200 -1662120329497156096 -1662120329536156928 -1662120329581157888 -1662120329623158784 -1662120329668159744 -1662120329713160704 -1662120329758161664 -1662120329800162560 -1662120329842163456 -1662120329884164352 -1662120329926165248 -1662120329971166208 -1662120330010167040 -1662120330052167936 -1662120330100168960 -1662120330145169920 -1662120330190170880 -1662120330235171840 -1662120330277172736 -1662120330316173568 -1662120330364174592 -1662120330406175488 -1662120330448176384 -1662120330487177216 -1662120330526178048 -1662120330571179008 -1662120330613179904 -1662120330658180864 -1662120330703181824 -1662120330748182784 -1662120330793183744 -1662120330838184704 -1662120330877185536 -1662120330928186624 -1662120330967187456 -1662120331006188288 -1662120331051189248 -1662120331090190080 -1662120331132190976 -1662120331174191872 -1662120331219192832 -1662120331261193728 -1662120331306194688 -1662120331354195712 -1662120331393196544 -1662120331435197440 -1662120331477198336 -1662120331513199104 -1662120331561200128 -1662120331609201152 -1662120331648201984 -1662120331690202880 -1662120331735203840 -1662120331780204800 -1662120331825205760 -1662120331864206592 -1662120331906207488 -1662120331951208448 -1662120331996209408 -1662120332038210304 -1662120332080211200 -1662120332125212160 -1662120332164212992 -1662120332206213888 -1662120332251214848 -1662120332293215744 -1662120332335216640 -1662120332374217472 -1662120332416218368 -1662120332458219264 -1662120332500220160 -1662120332545221120 -1662120332584221952 -1662120332629222912 -1662120332674223872 -1662120332719224832 -1662120332761225728 -1662120332806226688 -1662120332848227584 -1662120332890228480 -1662120332932229376 -1662120332974230272 -1662120333019231232 -1662120333064232192 -1662120333106233088 -1662120333154234112 -1662120333199235072 -1662120333238235904 -1662120333286236928 -1662120333328237824 -1662120333367238656 -1662120333409239552 -1662120333448240384 -1662120333490241280 -1662120333529242112 -1662120333571243008 -1662120333610243840 -1662120333649244672 -1662120333691245568 -1662120333736246528 -1662120333781247488 -1662120333826248448 -1662120333868249344 -1662120333913250304 -1662120333958251264 -1662120334003252224 -1662120334048253184 -1662120334090254080 -1662120334132254976 -1662120334171255808 -1662120334213256704 -1662120334258257664 -1662120334303258624 -1662120334348259584 -1662120334393260544 -1662120334438261504 -1662120334480262400 -1662120334525263360 -1662120334570264320 -1662120334612265216 -1662120334657266176 -1662120334702267136 -1662120334744268032 -1662120334795269120 -1662120334837270016 -1662120334882270976 -1662120334918271744 -1662120334960272640 -1662120335002273536 -1662120335047274496 -1662120335095275520 -1662120335137276416 -1662120335185277440 -1662120335230278400 -1662120335272279296 -1662120335314280192 -1662120335362281216 -1662120335404282112 -1662120335449283072 -1662120335485283840 -1662120335530284800 -1662120335572285696 -1662120335614286592 -1662120335656287488 -1662120335701288448 -1662120335746289408 -1662120335788290304 -1662120335833291264 -1662120335878292224 -1662120335923293184 -1662120335962294016 -1662120336010295040 -1662120336052295936 -1662120336088296704 -1662120336127297536 -1662120336172298496 -1662120336214299392 -1662120336250300160 -1662120336292301056 -1662120336334301952 -1662120336376302848 -1662120336427303936 -1662120336475304960 -1662120336517305856 -1662120336562306816 -1662120336601307648 -1662120336637308416 -1662120336679309312 -1662120336724310272 -1662120336763311104 -1662120336799311872 -1662120336838312704 -1662120336883313664 -1662120336922314496 -1662120336970315520 -1662120337015316480 -1662120337057317376 -1662120337102318336 -1662120337141319168 -1662120337186320128 -1662120337231321088 -1662120337276322048 -1662120337324323072 -1662120337369324032 -1662120337414324992 -1662120337459325952 -1662120337504326912 -1662120337546327808 -1662120337591328768 -1662120337636329728 -1662120337675330560 -1662120337711331328 -1662120337756332288 -1662120337801333248 -1662120337843334144 -1662120337882334976 -1662120337924335872 -1662120337969336832 -1662120338014337792 -1662120338059338752 -1662120338104339712 -1662120338146340608 -1662120338191341568 -1662120338233342464 -1662120338275343360 -1662120338323344384 -1662120338368345344 -1662120338416346368 -1662120338461347328 -1662120338503348224 -1662120338548349184 -1662120338590350080 -1662120338632350976 -1662120338674351872 -1662120338713352704 -1662120338752353536 -1662120338797354496 -1662120338842355456 -1662120338890356480 -1662120338932357376 -1662120338974358272 -1662120339016359168 -1662120339055360000 -1662120339100360960 -1662120339145361920 -1662120339190362880 -1662120339241363968 -1662120339286364928 -1662120339334365952 -1662120339382366976 -1662120339427367936 -1662120339466368768 -1662120339502369536 -1662120339544370432 -1662120339586371328 -1662120339625372160 -1662120339667373056 -1662120339706373888 -1662120339748374784 -1662120339793375744 -1662120339832376576 -1662120339874377472 -1662120339916378368 -1662120339958379264 -1662120340000380160 -1662120340042381056 -1662120340084381952 -1662120340126382848 -1662120340171383808 -1662120340216384768 -1662120340258385664 -1662120340306386688 -1662120340351387648 -1662120340393388544 -1662120340432389376 -1662120340480390400 -1662120340522391296 -1662120340564392192 -1662120340609393152 -1662120340651394048 -1662120340696395008 -1662120340738395904 -1662120340780396800 -1662120340825397760 -1662120340873398784 -1662120340912399616 -1662120340957400576 -1662120341002401536 -1662120341044402432 -1662120341089403392 -1662120341131404288 -1662120341176405248 -1662120341215406080 -1662120341263407104 -1662120341305408000 -1662120341344408832 -1662120341383409664 -1662120341428410624 -1662120341470411520 -1662120341512412416 -1662120341560413440 -1662120341605414400 -1662120341650415360 -1662120341692416256 -1662120341734417152 -1662120341773417984 -1662120341815418880 -1662120341857419776 -1662120341899420672 -1662120341938421504 -1662120341980422400 -1662120342025423360 -1662120342067424256 -1662120342112425216 -1662120342160426240 -1662120342202427136 -1662120342244428032 -1662120342286428928 -1662120342328429824 -1662120342373430784 -1662120342418431744 -1662120342466432768 -1662120342514433792 -1662120342556434688 -1662120342595435520 -1662120342637436416 -1662120342676437248 -1662120342718438144 -1662120342760439040 -1662120342799439872 -1662120342838440704 -1662120342877441536 -1662120342925442560 -1662120342964443392 -1662120343009444352 -1662120343048445184 -1662120343090446080 -1662120343135447040 -1662120343177447936 -1662120343222448896 -1662120343264449792 -1662120343309450752 -1662120343351451648 -1662120343402452736 -1662120343447453696 -1662120343489454592 -1662120343534455552 -1662120343579456512 -1662120343618457344 -1662120343663458304 -1662120343711459328 -1662120343762460416 -1662120343801461248 -1662120343849462272 -1662120343891463168 -1662120343936464128 -1662120343978465024 -1662120344023465984 -1662120344062466816 -1662120344107467776 -1662120344146468608 -1662120344188469504 -1662120344230470400 -1662120344275471360 -1662120344314472192 -1662120344356473088 -1662120344401474048 -1662120344443474944 -1662120344491475968 -1662120344533476864 -1662120344581477888 -1662120344620478720 -1662120344665479680 -1662120344713480704 -1662120344758481664 -1662120344800482560 -1662120344842483456 -1662120344884484352 -1662120344926485248 -1662120344968486144 -1662120345010487040 -1662120345055488000 -1662120345100488960 -1662120345145489920 -1662120345187490816 -1662120345229491712 -1662120345268492544 -1662120345310493440 -1662120345358494464 -1662120345397495296 -1662120345439496192 -1662120345484497152 -1662120345526498048 -1662120345568498944 -1662120345613499904 -1662120345655500800 -1662120345697501696 -1662120345736502528 -1662120345781503488 -1662120345826504448 -1662120345874505472 -1662120345919506432 -1662120345961507328 -1662120346006508288 -1662120346051509248 -1662120346096510208 -1662120346138511104 -1662120346180512000 -1662120346219512832 -1662120346264513792 -1662120346309514752 -1662120346354515712 -1662120346399516672 -1662120346441517568 -1662120346486518528 -1662120346528519424 -1662120346573520384 -1662120346618521344 -1662120346660522240 -1662120346702523136 -1662120346744524032 -1662120346786524928 -1662120346828525824 -1662120346876526848 -1662120346915527680 -1662120346957528576 -1662120347005529600 -1662120347047530496 -1662120347086531328 -1662120347128532224 -1662120347170533120 -1662120347212534016 -1662120347257534976 -1662120347299535872 -1662120347344536832 -1662120347389537792 -1662120347431538688 -1662120347476539648 -1662120347518540544 -1662120347560541440 -1662120347608542464 -1662120347653543424 -1662120347695544320 -1662120347737545216 -1662120347779546112 -1662120347824547072 -1662120347863547904 -1662120347905548800 -1662120347947549696 -1662120347986550528 -1662120348031551488 -1662120348073552384 -1662120348118553344 -1662120348157554176 -1662120348202555136 -1662120348244556032 -1662120348289556992 -1662120348331557888 -1662120348376558848 -1662120348421559808 -1662120348460560640 -1662120348502561536 -1662120348544562432 -1662120348589563392 -1662120348637564416 -1662120348679565312 -1662120348718566144 -1662120348760567040 -1662120348802567936 -1662120348841568768 -1662120348880569600 -1662120348922570496 -1662120348964571392 -1662120349009572352 -1662120349057573376 -1662120349102574336 -1662120349144575232 -1662120349186576128 -1662120349231577088 -1662120349273577984 -1662120349318578944 -1662120349363579904 -1662120349402580736 -1662120349444581632 -1662120349489582592 -1662120349531583488 -1662120349573584384 -1662120349612585216 -1662120349651586048 -1662120349696587008 -1662120349738587904 -1662120349780588800 -1662120349822589696 -1662120349864590592 -1662120349906591488 -1662120349948592384 -1662120349990593280 -1662120350032594176 -1662120350077595136 -1662120350122596096 -1662120350164596992 -1662120350209597952 -1662120350251598848 -1662120350293599744 -1662120350338600704 -1662120350380601600 -1662120350425602560 -1662120350467603456 -1662120350509604352 -1662120350551605248 -1662120350596606208 -1662120350638607104 -1662120350683608064 -1662120350728609024 -1662120350770609920 -1662120350812610816 -1662120350857611776 -1662120350902612736 -1662120350944613632 -1662120350986614528 -1662120351028615424 -1662120351067616256 -1662120351109617152 -1662120351151618048 -1662120351193618944 -1662120351235619840 -1662120351280620800 -1662120351325621760 -1662120351367622656 -1662120351409623552 -1662120351451624448 -1662120351496625408 -1662120351547626496 -1662120351589627392 -1662120351637628416 -1662120351679629312 -1662120351721630208 -1662120351766631168 -1662120351811632128 -1662120351856633088 -1662120351898633984 -1662120351940634880 -1662120351985635840 -1662120352027636736 -1662120352069637632 -1662120352111638528 -1662120352153639424 -1662120352195640320 -1662120352240641280 -1662120352285642240 -1662120352324643072 -1662120352366643968 -1662120352408644864 -1662120352447645696 -1662120352489646592 -1662120352534647552 -1662120352573648384 -1662120352621649408 -1662120352663650304 -1662120352705651200 -1662120352750652160 -1662120352795653120 -1662120352837654016 -1662120352882654976 -1662120352924655872 -1662120352972656896 -1662120353011657728 -1662120353053658624 -1662120353098659584 -1662120353143660544 -1662120353185661440 -1662120353227662336 -1662120353272663296 -1662120353320664320 -1662120353365665280 -1662120353410666240 -1662120353452667136 -1662120353494668032 -1662120353539668992 -1662120353581669888 -1662120353632670976 -1662120353683672064 -1662120353725672960 -1662120353767673856 -1662120353812674816 -1662120353854675712 -1662120353902676736 -1662120353947677696 -1662120353992678656 -1662120354037679616 -1662120354079680512 -1662120354121681408 -1662120354166682368 -1662120354208683264 -1662120354250684160 -1662120354292685056 -1662120354334685952 -1662120354376686848 -1662120354418687744 -1662120354463688704 -1662120354505689600 -1662120354547690496 -1662120354592691456 -1662120354637692416 -1662120354682693376 -1662120354727694336 -1662120354775695360 -1662120354817696256 -1662120354859697152 -1662120354901698048 -1662120354940698880 -1662120354982699776 -1662120355024700672 -1662120355066701568 -1662120355114702592 -1662120355162703616 -1662120355210704640 -1662120355249705472 -1662120355297706496 -1662120355336707328 -1662120355378708224 -1662120355420709120 -1662120355459709952 -1662120355504710912 -1662120355555712000 -1662120355600712960 -1662120355648713984 -1662120355690714880 -1662120355732715776 -1662120355777716736 -1662120355819717632 -1662120355861718528 -1662120355903719424 -1662120355945720320 -1662120355987721216 -1662120356029722112 -1662120356077723136 -1662120356122724096 -1662120356161724928 -1662120356203725824 -1662120356245726720 -1662120356290727680 -1662120356338728704 -1662120356383729664 -1662120356428730624 -1662120356470731520 -1662120356518732544 -1662120356560733440 -1662120356605734400 -1662120356647735296 -1662120356689736192 -1662120356731737088 -1662120356773737984 -1662120356815738880 -1662120356857739776 -1662120356896740608 -1662120356944741632 -1662120356986742528 -1662120357025743360 -1662120357070744320 -1662120357109745152 -1662120357154746112 -1662120357196747008 -1662120357241747968 -1662120357277748736 -1662120357319749632 -1662120357361750528 -1662120357406751488 -1662120357454752512 -1662120357499753472 -1662120357541754368 -1662120357586755328 -1662120357625756160 -1662120357664756992 -1662120357712758016 -1662120357754758912 -1662120357793759744 -1662120357835760640 -1662120357880761600 -1662120357925762560 -1662120357973763584 -1662120358015764480 -1662120358060765440 -1662120358102766336 -1662120358147767296 -1662120358195768320 -1662120358237769216 -1662120358285770240 -1662120358327771136 -1662120358375772160 -1662120358417773056 -1662120358459773952 -1662120358501774848 -1662120358543775744 -1662120358591776768 -1662120358636777728 -1662120358678778624 -1662120358726779648 -1662120358771780608 -1662120358813781504 -1662120358852782336 -1662120358894783232 -1662120358933784064 -1662120358975784960 -1662120359020785920 -1662120359065786880 -1662120359107787776 -1662120359158788864 -1662120359200789760 -1662120359242790656 -1662120359284791552 -1662120359326792448 -1662120359368793344 -1662120359407794176 -1662120359452795136 -1662120359494796032 -1662120359539796992 -1662120359581797888 -1662120359623798784 -1662120359671799808 -1662120359713800704 -1662120359755801600 -1662120359803802624 -1662120359845803520 -1662120359887804416 -1662120359926805248 -1662120359971806208 -1662120360013807104 -1662120360064808192 -1662120360106809088 -1662120360148809984 -1662120360190810880 -1662120360232811776 -1662120360274812672 -1662120360316813568 -1662120360361814528 -1662120360403815424 -1662120360445816320 -1662120360487817216 -1662120360529818112 -1662120360571819008 -1662120360613819904 -1662120360658820864 -1662120360703821824 -1662120360748822784 -1662120360787823616 -1662120360829824512 -1662120360877825536 -1662120360919826432 -1662120360964827392 -1662120361009828352 -1662120361054829312 -1662120361105830400 -1662120361150831360 -1662120361189832192 -1662120361231833088 -1662120361276834048 -1662120361318834944 -1662120361360835840 -1662120361408836864 -1662120361450837760 -1662120361489838592 -1662120361531839488 -1662120361573840384 -1662120361615841280 -1662120361660842240 -1662120361702843136 -1662120361747844096 -1662120361786844928 -1662120361831845888 -1662120361876846848 -1662120361918847744 -1662120361963848704 -1662120362008849664 -1662120362053850624 -1662120362092851456 -1662120362137852416 -1662120362179853312 -1662120362224854272 -1662120362266855168 -1662120362308856064 -1662120362347856896 -1662120362389857792 -1662120362428858624 -1662120362470859520 -1662120362515860480 -1662120362554861312 -1662120362596862208 -1662120362641863168 -1662120362680864000 -1662120362725864960 -1662120362767865856 -1662120362815866880 -1662120362857867776 -1662120362905868800 -1662120362947869696 -1662120362995870720 -1662120363037871616 -1662120363082872576 -1662120363124873472 -1662120363166874368 -1662120363208875264 -1662120363247876096 -1662120363289876992 -1662120363331877888 -1662120363373878784 -1662120363415879680 -1662120363454880512 -1662120363499881472 -1662120363544882432 -1662120363589883392 -1662120363634884352 -1662120363676885248 -1662120363718886144 -1662120363760887040 -1662120363802887936 -1662120363847888896 -1662120363886889728 -1662120363928890624 -1662120363973891584 -1662120364018892544 -1662120364060893440 -1662120364102894336 -1662120364147895296 -1662120364192896256 -1662120364231897088 -1662120364273897984 -1662120364315898880 -1662120364360899840 -1662120364405900800 -1662120364447901696 -1662120364489902592 -1662120364531903488 -1662120364573904384 -1662120364618905344 -1662120364666906368 -1662120364708907264 -1662120364756908288 -1662120364798909184 -1662120364843910144 -1662120364888911104 -1662120364930912000 -1662120364975912960 -1662120365020913920 -1662120365065914880 -1662120365110915840 -1662120365158916864 -1662120365200917760 -1662120365242918656 -1662120365284919552 -1662120365323920384 -1662120365365921280 -1662120365407922176 -1662120365449923072 -1662120365488923904 -1662120365527924736 -1662120365566925568 -1662120365611926528 -1662120365653927424 -1662120365698928384 -1662120365743929344 -1662120365788930304 -1662120365830931200 -1662120365872932096 -1662120365917933056 -1662120365959933952 -1662120365998934784 -1662120366040935680 -1662120366082936576 -1662120366124937472 -1662120366166938368 -1662120366211939328 -1662120366253940224 -1662120366301941248 -1662120366343942144 -1662120366397943296 -1662120366442944256 -1662120366484945152 -1662120366529946112 -1662120366574947072 -1662120366619948032 -1662120366661948928 -1662120366706949888 -1662120366748950784 -1662120366790951680 -1662120366835952640 -1662120366874953472 -1662120366916954368 -1662120366955955200 -1662120366994956032 -1662120367039956992 -1662120367081957888 -1662120367126958848 -1662120367168959744 -1662120367210960640 -1662120367249961472 -1662120367294962432 -1662120367336963328 -1662120367375964160 -1662120367420965120 -1662120367465966080 -1662120367507966976 -1662120367546967808 -1662120367591968768 -1662120367636969728 -1662120367675970560 -1662120367714971392 -1662120367759972352 -1662120367801973248 -1662120367846974208 -1662120367888975104 -1662120367933976064 -1662120367975976960 -1662120368020977920 -1662120368065978880 -1662120368110979840 -1662120368152980736 -1662120368194981632 -1662120368236982528 -1662120368275983360 -1662120368320984320 -1662120368359985152 -1662120368404986112 -1662120368446987008 -1662120368485987840 -1662120368530988800 -1662120368575989760 -1662120368617990656 -1662120368662991616 -1662120368704992512 -1662120368746993408 -1662120368791994368 -1662120368833995264 -1662120368875996160 -1662120368920997120 -1662120368965998080 -1662120369010999040 -1662120369056000000 -1662120369101000960 -1662120369146001920 -1662120369188002816 -1662120369230003712 -1662120369272004608 -1662120369317005568 -1662120369359006464 -1662120369404007424 -1662120369449008384 -1662120369500009472 -1662120369542010368 -1662120369584011264 -1662120369623012096 -1662120369665012992 -1662120369704013824 -1662120369749014784 -1662120369794015744 -1662120369836016640 -1662120369878017536 -1662120369923018496 -1662120369965019392 -1662120370007020288 -1662120370046021120 -1662120370088022016 -1662120370130022912 -1662120370175023872 -1662120370217024768 -1662120370259025664 -1662120370298026496 -1662120370340027392 -1662120370385028352 -1662120370427029248 -1662120370469030144 -1662120370511031040 -1662120370556032000 -1662120370604033024 -1662120370652034048 -1662120370697035008 -1662120370739035904 -1662120370781036800 -1662120370826037760 -1662120370877038848 -1662120370919039744 -1662120370961040640 -1662120371000041472 -1662120371045042432 -1662120371087043328 -1662120371126044160 -1662120371162044928 -1662120371207045888 -1662120371252046848 -1662120371294047744 -1662120371336048640 -1662120371381049600 -1662120371423050496 -1662120371468051456 -1662120371510052352 -1662120371552053248 -1662120371597054208 -1662120371642055168 -1662120371690056192 -1662120371735057152 -1662120371786058240 -1662120371828059136 -1662120371867059968 -1662120371912060928 -1662120371960061952 -1662120372005062912 -1662120372053063936 -1662120372098064896 -1662120372143065856 -1662120372185066752 -1662120372227067648 -1662120372272068608 -1662120372317069568 -1662120372362070528 -1662120372407071488 -1662120372452072448 -1662120372494073344 -1662120372536074240 -1662120372578075136 -1662120372623076096 -1662120372668077056 -1662120372713078016 -1662120372755078912 -1662120372800079872 -1662120372839080704 -1662120372881081600 -1662120372923082496 -1662120372968083456 -1662120373016084480 -1662120373055085312 -1662120373097086208 -1662120373139087104 -1662120373178087936 -1662120373220088832 -1662120373262089728 -1662120373307090688 -1662120373355091712 -1662120373394092544 -1662120373436093440 -1662120373481094400 -1662120373523095296 -1662120373565096192 -1662120373604097024 -1662120373652098048 -1662120373697099008 -1662120373748100096 -1662120373790100992 -1662120373832101888 -1662120373874102784 -1662120373919103744 -1662120373961104640 -1662120374000105472 -1662120374045106432 -1662120374090107392 -1662120374138108416 -1662120374183109376 -1662120374225110272 -1662120374270111232 -1662120374312112128 -1662120374354113024 -1662120374396113920 -1662120374438114816 -1662120374480115712 -1662120374525116672 -1662120374564117504 -1662120374609118464 -1662120374651119360 -1662120374699120384 -1662120374741121280 -1662120374786122240 -1662120374831123200 -1662120374873124096 -1662120374918125056 -1662120374966126080 -1662120375008126976 -1662120375056128000 -1662120375101128960 -1662120375146129920 -1662120375188130816 -1662120375236131840 -1662120375278132736 -1662120375323133696 -1662120375365134592 -1662120375413135616 -1662120375455136512 -1662120375497137408 -1662120375539138304 -1662120375581139200 -1662120375626140160 -1662120375668141056 -1662120375707141888 -1662120375752142848 -1662120375794143744 -1662120375839144704 -1662120375884145664 -1662120375929146624 -1662120375968147456 -1662120376010148352 -1662120376052149248 -1662120376094150144 -1662120376136151040 -1662120376175151872 -1662120376226152960 -1662120376268153856 -1662120376310154752 -1662120376355155712 -1662120376394156544 -1662120376436157440 -1662120376481158400 -1662120376523159296 -1662120376562160128 -1662120376604161024 -1662120376646161920 -1662120376688162816 -1662120376730163712 -1662120376775164672 -1662120376817165568 -1662120376859166464 -1662120376907167488 -1662120376952168448 -1662120376991169280 -1662120377036170240 -1662120377081171200 -1662120377123172096 -1662120377165172992 -1662120377204173824 -1662120377246174720 -1662120377288175616 -1662120377330176512 -1662120377372177408 -1662120377414178304 -1662120377456179200 -1662120377495180032 -1662120377537180928 -1662120377579181824 -1662120377621182720 -1662120377666183680 -1662120377711184640 -1662120377759185664 -1662120377801186560 -1662120377843187456 -1662120377882188288 -1662120377927189248 -1662120377966190080 -1662120378011191040 -1662120378053191936 -1662120378098192896 -1662120378140193792 -1662120378185194752 -1662120378224195584 -1662120378266196480 -1662120378308197376 -1662120378350198272 -1662120378392199168 -1662120378440200192 -1662120378482201088 -1662120378527202048 -1662120378569202944 -1662120378611203840 -1662120378656204800 -1662120378701205760 -1662120378746206720 -1662120378791207680 -1662120378833208576 -1662120378875209472 -1662120378917210368 -1662120378959211264 -1662120378998212096 -1662120379040212992 -1662120379082213888 -1662120379121214720 -1662120379160215552 -1662120379202216448 -1662120379247217408 -1662120379289218304 -1662120379331219200 -1662120379373220096 -1662120379418221056 -1662120379460221952 -1662120379505222912 -1662120379547223808 -1662120379604225024 -1662120379652226048 -1662120379691226880 -1662120379733227776 -1662120379775228672 -1662120379820229632 -1662120379868230656 -1662120379913231616 -1662120379955232512 -1662120379997233408 -1662120380042234368 -1662120380078235136 -1662120380123236096 -1662120380165236992 -1662120380216238080 -1662120380258238976 -1662120380300239872 -1662120380339240704 -1662120380384241664 -1662120380426242560 -1662120380468243456 -1662120380513244416 -1662120380564245504 -1662120380609246464 -1662120380654247424 -1662120380693248256 -1662120380735249152 -1662120380777250048 -1662120380816250880 -1662120380858251776 -1662120380906252800 -1662120380954253824 -1662120380999254784 -1662120381041255680 -1662120381083256576 -1662120381128257536 -1662120381170258432 -1662120381212259328 -1662120381251260160 -1662120381293261056 -1662120381335261952 -1662120381377262848 -1662120381428263936 -1662120381473264896 -1662120381512265728 -1662120381557266688 -1662120381599267584 -1662120381641268480 -1662120381686269440 -1662120381734270464 -1662120381776271360 -1662120381815272192 -1662120381857273088 -1662120381902274048 -1662120381950275072 -1662120381995276032 -1662120382037276928 -1662120382082277888 -1662120382127278848 -1662120382169279744 -1662120382214280704 -1662120382256281600 -1662120382301282560 -1662120382343283456 -1662120382385284352 -1662120382424285184 -1662120382463286016 -1662120382508286976 -1662120382547287808 -1662120382589288704 -1662120382631289600 -1662120382676290560 -1662120382721291520 -1662120382763292416 -1662120382808293376 -1662120382850294272 -1662120382898295296 -1662120382937296128 -1662120382976296960 -1662120383018297856 -1662120383063298816 -1662120383105299712 -1662120383147300608 -1662120383192301568 -1662120383234302464 -1662120383279303424 -1662120383321304320 -1662120383366305280 -1662120383417306368 -1662120383462307328 -1662120383504308224 -1662120383552309248 -1662120383594310144 -1662120383636311040 -1662120383678311936 -1662120383720312832 -1662120383768313856 -1662120383813314816 -1662120383858315776 -1662120383903316736 -1662120383945317632 -1662120383987318528 -1662120384032319488 -1662120384071320320 -1662120384113321216 -1662120384155322112 -1662120384200323072 -1662120384242323968 -1662120384287324928 -1662120384329325824 -1662120384371326720 -1662120384413327616 -1662120384455328512 -1662120384500329472 -1662120384542330368 -1662120384587331328 -1662120384632332288 -1662120384674333184 -1662120384719334144 -1662120384761335040 -1662120384803335936 -1662120384845336832 -1662120384890337792 -1662120384935338752 -1662120384974339584 -1662120385025340672 -1662120385070341632 -1662120385112342528 -1662120385160343552 -1662120385202344448 -1662120385241345280 -1662120385283346176 -1662120385325347072 -1662120385370348032 -1662120385418349056 -1662120385463350016 -1662120385514351104 -1662120385556352000 -1662120385598352896 -1662120385637353728 -1662120385679354624 -1662120385721355520 -1662120385766356480 -1662120385805357312 -1662120385847358208 -1662120385889359104 -1662120385934360064 -1662120385976360960 -1662120386021361920 -1662120386066362880 -1662120386108363776 -1662120386147364608 -1662120386186365440 -1662120386231366400 -1662120386270367232 -1662120386315368192 -1662120386360369152 -1662120386405370112 -1662120386447371008 -1662120386486371840 -1662120386531372800 -1662120386576373760 -1662120386615374592 -1662120386660375552 -1662120386699376384 -1662120386738377216 -1662120386783378176 -1662120386822379008 -1662120386870380032 -1662120386912380928 -1662120386951381760 -1662120386993382656 -1662120387032383488 -1662120387083384576 -1662120387122385408 -1662120387164386304 -1662120387206387200 -1662120387248388096 -1662120387293389056 -1662120387335389952 -1662120387371390720 -1662120387416391680 -1662120387461392640 -1662120387503393536 -1662120387548394496 -1662120387590395392 -1662120387629396224 -1662120387668397056 -1662120387713398016 -1662120387755398912 -1662120387800399872 -1662120387842400768 -1662120387887401728 -1662120387929402624 -1662120387971403520 -1662120388016404480 -1662120388055405312 -1662120388097406208 -1662120388142407168 -1662120388184408064 -1662120388223408896 -1662120388265409792 -1662120388304410624 -1662120388346411520 -1662120388388412416 -1662120388430413312 -1662120388472414208 -1662120388520415232 -1662120388565416192 -1662120388607417088 -1662120388649417984 -1662120388688418816 -1662120388733419776 -1662120388778420736 -1662120388823421696 -1662120388862422528 -1662120388904423424 -1662120388946424320 -1662120388991425280 -1662120389036426240 -1662120389078427136 -1662120389123428096 -1662120389165428992 -1662120389204429824 -1662120389252430848 -1662120389291431680 -1662120389333432576 -1662120389375433472 -1662120389414434304 -1662120389456435200 -1662120389498436096 -1662120389540436992 -1662120389585437952 -1662120389627438848 -1662120389669439744 -1662120389711440640 -1662120389756441600 -1662120389798442496 -1662120389846443520 -1662120389888444416 -1662120389933445376 -1662120389972446208 -1662120390014447104 -1662120390056448000 -1662120390101448960 -1662120390143449856 -1662120390185450752 -1662120390233451776 -1662120390278452736 -1662120390323453696 -1662120390365454592 -1662120390410455552 -1662120390455456512 -1662120390497457408 -1662120390533458176 -1662120390575459072 -1662120390617459968 -1662120390659460864 -1662120390704461824 -1662120390749462784 -1662120390791463680 -1662120390836464640 -1662120390878465536 -1662120390923466496 -1662120390974467584 -1662120391013468416 -1662120391055469312 -1662120391097470208 -1662120391145471232 -1662120391187472128 -1662120391229473024 -1662120391271473920 -1662120391319474944 -1662120391358475776 -1662120391403476736 -1662120391445477632 -1662120391487478528 -1662120391529479424 -1662120391571480320 -1662120391613481216 -1662120391655482112 -1662120391700483072 -1662120391739483904 -1662120391784484864 -1662120391835485952 -1662120391883486976 -1662120391925487872 -1662120391967488768 -1662120392012489728 -1662120392057490688 -1662120392099491584 -1662120392144492544 -1662120392186493440 -1662120392231494400 -1662120392273495296 -1662120392312496128 -1662120392357497088 -1662120392399497984 -1662120392444498944 -1662120392492499968 -1662120392543501056 -1662120392585501952 -1662120392630502912 -1662120392669503744 -1662120392711504640 -1662120392753505536 -1662120392801506560 -1662120392846507520 -1662120392891508480 -1662120392933509376 -1662120392981510400 -1662120393026511360 -1662120393068512256 -1662120393113513216 -1662120393158514176 -1662120393200515072 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track1.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track1.txt deleted file mode 100644 index f8502440d4..0000000000 --- a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track1.txt +++ /dev/null @@ -1,2030 +0,0 @@ -1662015311059723520 -1662015311101724416 -1662015311146725376 -1662015311203726592 -1662015311248727552 -1662015311293728512 -1662015311335729408 -1662015311377730304 -1662015311422731264 -1662015311464732160 -1662015311506733056 -1662015311548733952 -1662015311590734848 -1662015311635735808 -1662015311677736704 -1662015311719737600 -1662015311761738496 -1662015311809739520 -1662015311857740544 -1662015311902741504 -1662015311944742400 -1662015311986743296 -1662015312031744256 -1662015312076745216 -1662015312130746368 -1662015312169747200 -1662015312208748032 -1662015312253748992 -1662015312295749888 -1662015312340750848 -1662015312379751680 -1662015312424752640 -1662015312463753472 -1662015312508754432 -1662015312550755328 -1662015312592756224 -1662015312631757056 -1662015312679758080 -1662015312724759040 -1662015312766759936 -1662015312811760896 -1662015312856761856 -1662015312901762816 -1662015312943763712 -1662015312985764608 -1662015313027765504 -1662015313075766528 -1662015313117767424 -1662015313159768320 -1662015313201769216 -1662015313240770048 -1662015313282770944 -1662015313327771904 -1662015313369772800 -1662015313411773696 -1662015313456774656 -1662015313498775552 -1662015313540776448 -1662015313591777536 -1662015313630778368 -1662015313672779264 -1662015313717780224 -1662015313756781056 -1662015313801782016 -1662015313843782912 -1662015313885783808 -1662015313927784704 -1662015313972785664 -1662015314014786560 -1662015314056787456 -1662015314101788416 -1662015314143789312 -1662015314185790208 -1662015314227791104 -1662015314272792064 -1662015314317793024 -1662015314362793984 -1662015314413795072 -1662015314455795968 -1662015314497796864 -1662015314539797760 -1662015314581798656 -1662015314626799616 -1662015314668800512 -1662015314716801536 -1662015314761802496 -1662015314803803392 -1662015314848804352 -1662015314896805376 -1662015314938806272 -1662015314980807168 -1662015315028808192 -1662015315073809152 -1662015315115810048 -1662015315154810880 -1662015315199811840 -1662015315238812672 -1662015315280813568 -1662015315328814592 -1662015315379815680 -1662015315427816704 -1662015315475817728 -1662015315532818944 -1662015315577819904 -1662015315619820800 -1662015315670821888 -1662015315721822976 -1662015315766823936 -1662015315814824960 -1662015315859825920 -1662015315904826880 -1662015315949827840 -1662015315991828736 -1662015316033829632 -1662015316078830592 -1662015316126831616 -1662015316174832640 -1662015316219833600 -1662015316270834688 -1662015316315835648 -1662015316366836736 -1662015316414837760 -1662015316462838784 -1662015316507839744 -1662015316552840704 -1662015316597841664 -1662015316648842752 -1662015316690843648 -1662015316729844480 -1662015316774845440 -1662015316822846464 -1662015316867847424 -1662015316909848320 -1662015316951849216 -1662015316993850112 -1662015317038851072 -1662015317083852032 -1662015317128852992 -1662015317170853888 -1662015317218854912 -1662015317260855808 -1662015317302856704 -1662015317344857600 -1662015317389858560 -1662015317434859520 -1662015317473860352 -1662015317515861248 -1662015317560862208 -1662015317605863168 -1662015317647864064 -1662015317692865024 -1662015317740866048 -1662015317782866944 -1662015317830867968 -1662015317872868864 -1662015317914869760 -1662015317962870784 -1662015318010871808 -1662015318058872832 -1662015318109873920 -1662015318148874752 -1662015318193875712 -1662015318235876608 -1662015318280877568 -1662015318325878528 -1662015318367879424 -1662015318412880384 -1662015318454881280 -1662015318499882240 -1662015318547883264 -1662015318589884160 -1662015318631885056 -1662015318682886144 -1662015318727887104 -1662015318769888000 -1662015318814888960 -1662015318859889920 -1662015318907890944 -1662015318952891904 -1662015318994892800 -1662015319036893696 -1662015319078894592 -1662015319120895488 -1662015319162896384 -1662015319207897344 -1662015319249898240 -1662015319291899136 -1662015319339900160 -1662015319387901184 -1662015319432902144 -1662015319474903040 -1662015319516903936 -1662015319561904896 -1662015319609905920 -1662015319654906880 -1662015319699907840 -1662015319741908736 -1662015319792909824 -1662015319840910848 -1662015319891911936 -1662015319939912960 -1662015319981913856 -1662015320023914752 -1662015320077915904 -1662015320125916928 -1662015320167917824 -1662015320209918720 -1662015320251919616 -1662015320296920576 -1662015320338921472 -1662015320389922560 -1662015320437923584 -1662015320485924608 -1662015320530925568 -1662015320575926528 -1662015320617927424 -1662015320659928320 -1662015320704929280 -1662015320746930176 -1662015320791931136 -1662015320839932160 -1662015320881933056 -1662015320926934016 -1662015320968934912 -1662015321010935808 -1662015321058936832 -1662015321103937792 -1662015321145938688 -1662015321193939712 -1662015321241940736 -1662015321283941632 -1662015321328942592 -1662015321373943552 -1662015321415944448 -1662015321454945280 -1662015321499946240 -1662015321541947136 -1662015321592948224 -1662015321637949184 -1662015321685950208 -1662015321727951104 -1662015321775952128 -1662015321817953024 -1662015321859953920 -1662015321901954816 -1662015321943955712 -1662015321985956608 -1662015322033957632 -1662015322084958720 -1662015322126959616 -1662015322171960576 -1662015322222961664 -1662015322267962624 -1662015322309963520 -1662015322351964416 -1662015322396965376 -1662015322438966272 -1662015322483967232 -1662015322528968192 -1662015322567969024 -1662015322609969920 -1662015322651970816 -1662015322699971840 -1662015322741972736 -1662015322786973696 -1662015322828974592 -1662015322876975616 -1662015322918976512 -1662015322966977536 -1662015323008978432 -1662015323059979520 -1662015323101980416 -1662015323143981312 -1662015323188982272 -1662015323230983168 -1662015323272984064 -1662015323314984960 -1662015323359985920 -1662015323404986880 -1662015323455987968 -1662015323494988800 -1662015323542989824 -1662015323584990720 -1662015323629991680 -1662015323671992576 -1662015323713993472 -1662015323755994368 -1662015323803995392 -1662015323848996352 -1662015323896997376 -1662015323938998272 -1662015323980999168 -1662015324026000128 -1662015324071001088 -1662015324113001984 -1662015324164003072 -1662015324206003968 -1662015324251004928 -1662015324293005824 -1662015324338006784 -1662015324386007808 -1662015324431008768 -1662015324473009664 -1662015324515010560 -1662015324560011520 -1662015324605012480 -1662015324653013504 -1662015324695014400 -1662015324740015360 -1662015324785016320 -1662015324827017216 -1662015324875018240 -1662015324917019136 -1662015324965020160 -1662015325013021184 -1662015325055022080 -1662015325100023040 -1662015325145024000 -1662015325190024960 -1662015325232025856 -1662015325274026752 -1662015325322027776 -1662015325367028736 -1662015325412029696 -1662015325457030656 -1662015325505031680 -1662015325547032576 -1662015325592033536 -1662015325634034432 -1662015325676035328 -1662015325718036224 -1662015325760037120 -1662015325805038080 -1662015325847038976 -1662015325889039872 -1662015325934040832 -1662015325985041920 -1662015326036043008 -1662015326084044032 -1662015326126044928 -1662015326177046016 -1662015326225047040 -1662015326276048128 -1662015326321049088 -1662015326363049984 -1662015326408050944 -1662015326453051904 -1662015326495052800 -1662015326537053696 -1662015326582054656 -1662015326627055616 -1662015326681056768 -1662015326723057664 -1662015326771058688 -1662015326813059584 -1662015326855060480 -1662015326897061376 -1662015326942062336 -1662015326987063296 -1662015327029064192 -1662015327074065152 -1662015327116066048 -1662015327161067008 -1662015327203067904 -1662015327245068800 -1662015327290069760 -1662015327335070720 -1662015327380071680 -1662015327419072512 -1662015327464073472 -1662015327509074432 -1662015327554075392 -1662015327596076288 -1662015327644077312 -1662015327686078208 -1662015327731079168 -1662015327776080128 -1662015327818081024 -1662015327863081984 -1662015327905082880 -1662015327950083840 -1662015327992084736 -1662015328034085632 -1662015328076086528 -1662015328118087424 -1662015328163088384 -1662015328205089280 -1662015328247090176 -1662015328292091136 -1662015328334092032 -1662015328376092928 -1662015328418093824 -1662015328457094656 -1662015328499095552 -1662015328544096512 -1662015328589097472 -1662015328634098432 -1662015328682099456 -1662015328724100352 -1662015328775101440 -1662015328820102400 -1662015328868103424 -1662015328907104256 -1662015328955105280 -1662015329012106496 -1662015329066107648 -1662015329108108544 -1662015329153109504 -1662015329198110464 -1662015329243111424 -1662015329288112384 -1662015329336113408 -1662015329378114304 -1662015329423115264 -1662015329468116224 -1662015329513117184 -1662015329555118080 -1662015329597118976 -1662015329639119872 -1662015329681120768 -1662015329726121728 -1662015329771122688 -1662015329816123648 -1662015329861124608 -1662015329906125568 -1662015329948126464 -1662015329996127488 -1662015330044128512 -1662015330086129408 -1662015330134130432 -1662015330185131520 -1662015330227132416 -1662015330272133376 -1662015330320134400 -1662015330368135424 -1662015330413136384 -1662015330458137344 -1662015330506138368 -1662015330548139264 -1662015330596140288 -1662015330638141184 -1662015330683142144 -1662015330725143040 -1662015330770144000 -1662015330815144960 -1662015330857145856 -1662015330914147072 -1662015330959148032 -1662015331010149120 -1662015331049149952 -1662015331094150912 -1662015331136151808 -1662015331178152704 -1662015331223153664 -1662015331265154560 -1662015331310155520 -1662015331355156480 -1662015331397157376 -1662015331442158336 -1662015331487159296 -1662015331529160192 -1662015331571161088 -1662015331619162112 -1662015331667163136 -1662015331709164032 -1662015331751164928 -1662015331796165888 -1662015331847166976 -1662015331895168000 -1662015331940168960 -1662015331994170112 -1662015332039171072 -1662015332081171968 -1662015332123172864 -1662015332165173760 -1662015332213174784 -1662015332255175680 -1662015332300176640 -1662015332342177536 -1662015332384178432 -1662015332432179456 -1662015332477180416 -1662015332525181440 -1662015332567182336 -1662015332609183232 -1662015332654184192 -1662015332699185152 -1662015332747186176 -1662015332792187136 -1662015332837188096 -1662015332885189120 -1662015332930190080 -1662015332972190976 -1662015333017191936 -1662015333065192960 -1662015333107193856 -1662015333149194752 -1662015333191195648 -1662015333242196736 -1662015333293197824 -1662015333335198720 -1662015333380199680 -1662015333422200576 -1662015333470201600 -1662015333515202560 -1662015333557203456 -1662015333602204416 -1662015333647205376 -1662015333689206272 -1662015333734207232 -1662015333776208128 -1662015333821209088 -1662015333863209984 -1662015333905210880 -1662015333947211776 -1662015333992212736 -1662015334037213696 -1662015334082214656 -1662015334124215552 -1662015334169216512 -1662015334214217472 -1662015334259218432 -1662015334301219328 -1662015334343220224 -1662015334385221120 -1662015334427222016 -1662015334472222976 -1662015334520224000 -1662015334559224832 -1662015334604225792 -1662015334649226752 -1662015334694227712 -1662015334739228672 -1662015334781229568 -1662015334826230528 -1662015334874231552 -1662015334925232640 -1662015334967233536 -1662015335018234624 -1662015335063235584 -1662015335111236608 -1662015335153237504 -1662015335195238400 -1662015335240239360 -1662015335285240320 -1662015335330241280 -1662015335369242112 -1662015335423243264 -1662015335465244160 -1662015335507245056 -1662015335552246016 -1662015335597246976 -1662015335639247872 -1662015335690248960 -1662015335735249920 -1662015335774250752 -1662015335822251776 -1662015335864252672 -1662015335909253632 -1662015335957254656 -1662015336005255680 -1662015336047256576 -1662015336101257728 -1662015336149258752 -1662015336191259648 -1662015336233260544 -1662015336275261440 -1662015336317262336 -1662015336365263360 -1662015336407264256 -1662015336449265152 -1662015336497266176 -1662015336536267008 -1662015336581267968 -1662015336626268928 -1662015336671269888 -1662015336716270848 -1662015336767271936 -1662015336812272896 -1662015336857273856 -1662015336902274816 -1662015336950275840 -1662015336992276736 -1662015337034277632 -1662015337076278528 -1662015337118279424 -1662015337163280384 -1662015337208281344 -1662015337250282240 -1662015337295283200 -1662015337343284224 -1662015337385285120 -1662015337427286016 -1662015337469286912 -1662015337517287936 -1662015337568289024 -1662015337610289920 -1662015337652290816 -1662015337694291712 -1662015337733292544 -1662015337778293504 -1662015337826294528 -1662015337871295488 -1662015337913296384 -1662015337958297344 -1662015338000298240 -1662015338042299136 -1662015338087300096 -1662015338135301120 -1662015338177302016 -1662015338219302912 -1662015338258303744 -1662015338300304640 -1662015338345305600 -1662015338396306688 -1662015338438307584 -1662015338474308352 -1662015338519309312 -1662015338561310208 -1662015338606311168 -1662015338645312000 -1662015338687312896 -1662015338732313856 -1662015338774314752 -1662015338816315648 -1662015338858316544 -1662015338900317440 -1662015338942318336 -1662015338984319232 -1662015339026320128 -1662015339068321024 -1662015339113321984 -1662015339161323008 -1662015339206323968 -1662015339248324864 -1662015339296325888 -1662015339338326784 -1662015339380327680 -1662015339422328576 -1662015339467329536 -1662015339509330432 -1662015339551331328 -1662015339596332288 -1662015339641333248 -1662015339686334208 -1662015339728335104 -1662015339770336000 -1662015339809336832 -1662015339857337856 -1662015339902338816 -1662015339944339712 -1662015339986340608 -1662015340028341504 -1662015340079342592 -1662015340121343488 -1662015340163344384 -1662015340205345280 -1662015340259346432 -1662015340301347328 -1662015340346348288 -1662015340388349184 -1662015340433350144 -1662015340475351040 -1662015340520352000 -1662015340565352960 -1662015340613353984 -1662015340655354880 -1662015340697355776 -1662015340745356800 -1662015340793357824 -1662015340835358720 -1662015340874359552 -1662015340919360512 -1662015340964361472 -1662015341006362368 -1662015341051363328 -1662015341093364224 -1662015341141365248 -1662015341183366144 -1662015341225367040 -1662015341270368000 -1662015341312368896 -1662015341354369792 -1662015341399370752 -1662015341438371584 -1662015341480372480 -1662015341525373440 -1662015341570374400 -1662015341615375360 -1662015341663376384 -1662015341705377280 -1662015341750378240 -1662015341798379264 -1662015341840380160 -1662015341882381056 -1662015341930382080 -1662015341969382912 -1662015342011383808 -1662015342053384704 -1662015342095385600 -1662015342140386560 -1662015342185387520 -1662015342230388480 -1662015342278389504 -1662015342326390528 -1662015342371391488 -1662015342416392448 -1662015342458393344 -1662015342500394240 -1662015342539395072 -1662015342581395968 -1662015342632397056 -1662015342674397952 -1662015342716398848 -1662015342764399872 -1662015342803400704 -1662015342845401600 -1662015342884402432 -1662015342926403328 -1662015342968404224 -1662015343013405184 -1662015343055406080 -1662015343097406976 -1662015343148408064 -1662015343193409024 -1662015343238409984 -1662015343286411008 -1662015343331411968 -1662015343373412864 -1662015343418413824 -1662015343466414848 -1662015343511415808 -1662015343553416704 -1662015343595417600 -1662015343637418496 -1662015343685419520 -1662015343727420416 -1662015343772421376 -1662015343823422464 -1662015343865423360 -1662015343907424256 -1662015343952425216 -1662015343997426176 -1662015344039427072 -1662015344084428032 -1662015344129428992 -1662015344177430016 -1662015344219430912 -1662015344264431872 -1662015344315432960 -1662015344357433856 -1662015344405434880 -1662015344447435776 -1662015344495436800 -1662015344537437696 -1662015344585438720 -1662015344627439616 -1662015344672440576 -1662015344717441536 -1662015344759442432 -1662015344810443520 -1662015344855444480 -1662015344894445312 -1662015344939446272 -1662015344987447296 -1662015345029448192 -1662015345074449152 -1662015345119450112 -1662015345161451008 -1662015345206451968 -1662015345248452864 -1662015345296453888 -1662015345338454784 -1662015345380455680 -1662015345428456704 -1662015345476457728 -1662015345521458688 -1662015345560459520 -1662015345608460544 -1662015345656461568 -1662015345695462400 -1662015345737463296 -1662015345779464192 -1662015345824465152 -1662015345866466048 -1662015345914467072 -1662015345956467968 -1662015346001468928 -1662015346052470016 -1662015346094470912 -1662015346136471808 -1662015346184472832 -1662015346229473792 -1662015346277474816 -1662015346322475776 -1662015346364476672 -1662015346406477568 -1662015346448478464 -1662015346490479360 -1662015346535480320 -1662015346577481216 -1662015346622482176 -1662015346661483008 -1662015346706483968 -1662015346748484864 -1662015346790485760 -1662015346835486720 -1662015346883487744 -1662015346922488576 -1662015346964489472 -1662015347009490432 -1662015347051491328 -1662015347093492224 -1662015347138493184 -1662015347180494080 -1662015347222494976 -1662015347270496000 -1662015347315496960 -1662015347354497792 -1662015347396498688 -1662015347438499584 -1662015347483500544 -1662015347525501440 -1662015347567502336 -1662015347609503232 -1662015347663504384 -1662015347705505280 -1662015347750506240 -1662015347798507264 -1662015347840508160 -1662015347885509120 -1662015347933510144 -1662015347975511040 -1662015348017511936 -1662015348062512896 -1662015348107513856 -1662015348155514880 -1662015348197515776 -1662015348239516672 -1662015348284517632 -1662015348332518656 -1662015348377519616 -1662015348419520512 -1662015348464521472 -1662015348509522432 -1662015348557523456 -1662015348602524416 -1662015348644525312 -1662015348683526144 -1662015348725527040 -1662015348770528000 -1662015348812528896 -1662015348854529792 -1662015348899530752 -1662015348944531712 -1662015348992532736 -1662015349034533632 -1662015349076534528 -1662015349121535488 -1662015349163536384 -1662015349205537280 -1662015349247538176 -1662015349292539136 -1662015349343540224 -1662015349391541248 -1662015349433542144 -1662015349475543040 -1662015349517543936 -1662015349562544896 -1662015349604545792 -1662015349649546752 -1662015349694547712 -1662015349739548672 -1662015349781549568 -1662015349826550528 -1662015349865551360 -1662015349907552256 -1662015349949553152 -1662015349994554112 -1662015350045555200 -1662015350090556160 -1662015350135557120 -1662015350177558016 -1662015350219558912 -1662015350255559680 -1662015350297560576 -1662015350339561472 -1662015350387562496 -1662015350438563584 -1662015350480564480 -1662015350522565376 -1662015350564566272 -1662015350606567168 -1662015350651568128 -1662015350693569024 -1662015350738569984 -1662015350786571008 -1662015350831571968 -1662015350873572864 -1662015350918573824 -1662015350963574784 -1662015351005575680 -1662015351050576640 -1662015351095577600 -1662015351140578560 -1662015351182579456 -1662015351224580352 -1662015351269581312 -1662015351314582272 -1662015351359583232 -1662015351398584064 -1662015351443585024 -1662015351488585984 -1662015351530586880 -1662015351575587840 -1662015351626588928 -1662015351668589824 -1662015351716590848 -1662015351767591936 -1662015351809592832 -1662015351857593856 -1662015351905594880 -1662015351950595840 -1662015351992596736 -1662015352037597696 -1662015352082598656 -1662015352127599616 -1662015352166600448 -1662015352214601472 -1662015352256602368 -1662015352298603264 -1662015352340604160 -1662015352373604864 -1662015352412605696 -1662015352454606592 -1662015352499607552 -1662015352544608512 -1662015352592609536 -1662015352637610496 -1662015352679611392 -1662015352724612352 -1662015352769613312 -1662015352814614272 -1662015352859615232 -1662015352901616128 -1662015352949617152 -1662015352994618112 -1662015353036619008 -1662015353081619968 -1662015353126620928 -1662015353174621952 -1662015353219622912 -1662015353264623872 -1662015353309624832 -1662015353351625728 -1662015353396626688 -1662015353438627584 -1662015353483628544 -1662015353525629440 -1662015353564630272 -1662015353606631168 -1662015353648632064 -1662015353690632960 -1662015353738633984 -1662015353780634880 -1662015353822635776 -1662015353861636608 -1662015353909637632 -1662015353954638592 -1662015353993639424 -1662015354035640320 -1662015354083641344 -1662015354122642176 -1662015354164643072 -1662015354209644032 -1662015354251644928 -1662015354299645952 -1662015354341646848 -1662015354380647680 -1662015354425648640 -1662015354470649600 -1662015354512650496 -1662015354554651392 -1662015354599652352 -1662015354647653376 -1662015354689654272 -1662015354731655168 -1662015354779656192 -1662015354824657152 -1662015354863657984 -1662015354911659008 -1662015354953659904 -1662015354992660736 -1662015355037661696 -1662015355085662720 -1662015355130663680 -1662015355172664576 -1662015355217665536 -1662015355259666432 -1662015355301667328 -1662015355343668224 -1662015355388669184 -1662015355433670144 -1662015355475671040 -1662015355520672000 -1662015355565672960 -1662015355604673792 -1662015355649674752 -1662015355691675648 -1662015355739676672 -1662015355781677568 -1662015355823678464 -1662015355865679360 -1662015355907680256 -1662015355949681152 -1662015355997682176 -1662015356042683136 -1662015356087684096 -1662015356129684992 -1662015356174685952 -1662015356216686848 -1662015356261687808 -1662015356303688704 -1662015356351689728 -1662015356399690752 -1662015356441691648 -1662015356480692480 -1662015356522693376 -1662015356564694272 -1662015356612695296 -1662015356654696192 -1662015356699697152 -1662015356741698048 -1662015356783698944 -1662015356828699904 -1662015356864700672 -1662015356906701568 -1662015356951702528 -1662015356993703424 -1662015357035704320 -1662015357083705344 -1662015357128706304 -1662015357170707200 -1662015357212708096 -1662015357254708992 -1662015357293709824 -1662015357338710784 -1662015357383711744 -1662015357428712704 -1662015357482713856 -1662015357524714752 -1662015357566715648 -1662015357611716608 -1662015357659717632 -1662015357704718592 -1662015357746719488 -1662015357794720512 -1662015357836721408 -1662015357884722432 -1662015357929723392 -1662015357971724288 -1662015358013725184 -1662015358058726144 -1662015358103727104 -1662015358145728000 -1662015358187728896 -1662015358241730048 -1662015358280730880 -1662015358325731840 -1662015358367732736 -1662015358409733632 -1662015358451734528 -1662015358493735424 -1662015358544736512 -1662015358586737408 -1662015358631738368 -1662015358676739328 -1662015358718740224 -1662015358763741184 -1662015358811742208 -1662015358853743104 -1662015358895744000 -1662015358943745024 -1662015358988745984 -1662015359036747008 -1662015359078747904 -1662015359123748864 -1662015359165749760 -1662015359207750656 -1662015359246751488 -1662015359294752512 -1662015359336753408 -1662015359381754368 -1662015359423755264 -1662015359462756096 -1662015359504756992 -1662015359546757888 -1662015359588758784 -1662015359630759680 -1662015359675760640 -1662015359714761472 -1662015359756762368 -1662015359798763264 -1662015359843764224 -1662015359888765184 -1662015359927766016 -1662015359969766912 -1662015360011767808 -1662015360053768704 -1662015360098769664 -1662015360143770624 -1662015360185771520 -1662015360230772480 -1662015360275773440 -1662015360320774400 -1662015360371775488 -1662015360413776384 -1662015360452777216 -1662015360503778304 -1662015360542779136 -1662015360590780160 -1662015360635781120 -1662015360680782080 -1662015360722782976 -1662015360767783936 -1662015360812784896 -1662015360863785984 -1662015360905786880 -1662015360947787776 -1662015360989788672 -1662015361037789696 -1662015361079790592 -1662015361121791488 -1662015361169792512 -1662015361214793472 -1662015361259794432 -1662015361301795328 -1662015361346796288 -1662015361394797312 -1662015361436798208 -1662015361478799104 -1662015361520800000 -1662015361571801088 -1662015361613801984 -1662015361658802944 -1662015361700803840 -1662015361751804928 -1662015361793805824 -1662015361838806784 -1662015361880807680 -1662015361922808576 -1662015361967809536 -1662015362012810496 -1662015362054811392 -1662015362099812352 -1662015362144813312 -1662015362189814272 -1662015362234815232 -1662015362279816192 -1662015362321817088 -1662015362363817984 -1662015362408818944 -1662015362444819712 -1662015362480820480 -1662015362522821376 -1662015362567822336 -1662015362612823296 -1662015362654824192 -1662015362702825216 -1662015362744826112 -1662015362792827136 -1662015362840828160 -1662015362885829120 -1662015362927830016 -1662015362969830912 -1662015363014831872 -1662015363056832768 -1662015363098833664 -1662015363140834560 -1662015363185835520 -1662015363230836480 -1662015363269837312 -1662015363311838208 -1662015363353839104 -1662015363401840128 -1662015363446841088 -1662015363494842112 -1662015363536843008 -1662015363581843968 -1662015363623844864 -1662015363665845760 -1662015363716846848 -1662015363758847744 -1662015363800848640 -1662015363842849536 -1662015363884850432 -1662015363926851328 -1662015363971852288 -1662015364016853248 -1662015364061854208 -1662015364106855168 -1662015364151856128 -1662015364196857088 -1662015364241858048 -1662015364283858944 -1662015364325859840 -1662015364370860800 -1662015364421861888 -1662015364469862912 -1662015364508863744 -1662015364556864768 -1662015364601865728 -1662015364643866624 -1662015364685867520 -1662015364730868480 -1662015364778869504 -1662015364823870464 -1662015364865871360 -1662015364904872192 -1662015364946873088 -1662015364991874048 -1662015365042875136 -1662015365087876096 -1662015365129876992 -1662015365177878016 -1662015365225879040 -1662015365267879936 -1662015365315880960 -1662015365357881856 -1662015365399882752 -1662015365441883648 -1662015365483884544 -1662015365525885440 -1662015365570886400 -1662015365612887296 -1662015365657888256 -1662015365696889088 -1662015365741890048 -1662015365783890944 -1662015365828891904 -1662015365870892800 -1662015365915893760 -1662015365960894720 -1662015366002895616 -1662015366050896640 -1662015366092897536 -1662015366137898496 -1662015366179899392 -1662015366224900352 -1662015366266901248 -1662015366314902272 -1662015366359903232 -1662015366407904256 -1662015366449905152 -1662015366503906304 -1662015366545907200 -1662015366590908160 -1662015366635909120 -1662015366680910080 -1662015366722910976 -1662015366773912064 -1662015366818913024 -1662015366863913984 -1662015366914915072 -1662015366959916032 -1662015367004916992 -1662015367046917888 -1662015367091918848 -1662015367145920000 -1662015367190920960 -1662015367232921856 -1662015367274922752 -1662015367319923712 -1662015367364924672 -1662015367409925632 -1662015367451926528 -1662015367496927488 -1662015367538928384 -1662015367583929344 -1662015367628930304 -1662015367667931136 -1662015367712932096 -1662015367757933056 -1662015367799933952 -1662015367841934848 -1662015367880935680 -1662015367922936576 -1662015367970937600 -1662015368012938496 -1662015368054939392 -1662015368099940352 -1662015368144941312 -1662015368183942144 -1662015368228943104 -1662015368273944064 -1662015368315944960 -1662015368360945920 -1662015368402946816 -1662015368453947904 -1662015368495948800 -1662015368537949696 -1662015368579950592 -1662015368627951616 -1662015368672952576 -1662015368723953664 -1662015368768954624 -1662015368816955648 -1662015368861956608 -1662015368900957440 -1662015368948958464 -1662015368990959360 -1662015369035960320 -1662015369077961216 -1662015369119962112 -1662015369158962944 -1662015369200963840 -1662015369242964736 -1662015369284965632 -1662015369329966592 -1662015369377967616 -1662015369419968512 -1662015369461969408 -1662015369509970432 -1662015369560971520 -1662015369602972416 -1662015369641973248 -1662015369686974208 -1662015369725975040 -1662015369770976000 -1662015369809976832 -1662015369854977792 -1662015369896978688 -1662015369935979520 -1662015369977980416 -1662015370022981376 -1662015370064982272 -1662015370103983104 -1662015370151984128 -1662015370196985088 -1662015370238985984 -1662015370280986880 -1662015370322987776 -1662015370373988864 -1662015370415989760 -1662015370457990656 -1662015370502991616 -1662015370547992576 -1662015370592993536 -1662015370640994560 -1662015370682995456 -1662015370724996352 -1662015370775997440 -1662015370820998400 -1662015370862999296 -1662015370908000256 -1662015370950001152 -1662015370995002112 -1662015371040003072 -1662015371085004032 -1662015371133005056 -1662015371172005888 -1662015371214006784 -1662015371256007680 -1662015371298008576 -1662015371340009472 -1662015371385010432 -1662015371430011392 -1662015371478012416 -1662015371526013440 -1662015371571014400 -1662015371616015360 -1662015371661016320 -1662015371703017216 -1662015371742018048 -1662015371781018880 -1662015371826019840 -1662015371865020672 -1662015371913021696 -1662015371958022656 -1662015372003023616 -1662015372045024512 -1662015372087025408 -1662015372129026304 -1662015372177027328 -1662015372216028160 -1662015372258029056 -1662015372303030016 -1662015372345030912 -1662015372384031744 -1662015372438032896 -1662015372483033856 -1662015372525034752 -1662015372570035712 -1662015372615036672 -1662015372660037632 -1662015372702038528 -1662015372747039488 -1662015372792040448 -1662015372834041344 -1662015372876042240 -1662015372915043072 -1662015372960044032 -1662015373005044992 -1662015373047045888 -1662015373089046784 -1662015373134047744 -1662015373179048704 -1662015373227049728 -1662015373278050816 -1662015373323051776 -1662015373368052736 -1662015373416053760 -1662015373464054784 -1662015373512055808 -1662015373557056768 -1662015373590057472 -1662015373635058432 -1662015373677059328 -1662015373722060288 -1662015373770061312 -1662015373812062208 -1662015373854063104 -1662015373896064000 -1662015373941064960 -1662015373986065920 -1662015374028066816 -1662015374070067712 -1662015374112068608 -1662015374157069568 -1662015374199070464 -1662015374244071424 -1662015374292072448 -1662015374334073344 -1662015374373074176 -1662015374415075072 -1662015374460076032 -1662015374511077120 -1662015374553078016 -1662015374595078912 -1662015374643079936 -1662015374697081088 -1662015374742082048 -1662015374784082944 -1662015374823083776 -1662015374868084736 -1662015374913085696 -1662015374958086656 -1662015375003087616 -1662015375045088512 -1662015375087089408 -1662015375129090304 -1662015375180091392 -1662015375225092352 -1662015375276093440 -1662015375315094272 -1662015375360095232 -1662015375402096128 -1662015375453097216 -1662015375498098176 -1662015375549099264 -1662015375591100160 -1662015375636101120 -1662015375678102016 -1662015375720102912 -1662015375765103872 -1662015375813104896 -1662015375858105856 -1662015375903106816 -1662015375948107776 -1662015375996108800 -1662015376038109696 -1662015376080110592 -1662015376119111424 -1662015376167112448 -1662015376209113344 -1662015376257114368 -1662015376305115392 -1662015376347116288 -1662015376392117248 -1662015376434118144 -1662015376479119104 -1662015376524120064 -1662015376569121024 -1662015376614121984 -1662015376656122880 -1662015376707123968 -1662015376752124928 -1662015376803126016 -1662015376848126976 -1662015376893127936 -1662015376938128896 -1662015376980129792 -1662015377028130816 -1662015377073131776 -1662015377115132672 -1662015377154133504 -1662015377196134400 -1662015377238135296 -1662015377286136320 -1662015377337137408 -1662015377379138304 -1662015377424139264 -1662015377466140160 -1662015377514141184 -1662015377556142080 -1662015377604143104 -1662015377649144064 -1662015377694145024 -1662015377739145984 -1662015377781146880 -1662015377823147776 -1662015377868148736 -1662015377907149568 -1662015377949150464 -1662015377991151360 -1662015378036152320 -1662015378081153280 -1662015378120154112 -1662015378165155072 -1662015378207155968 -1662015378249156864 -1662015378285157632 -1662015378327158528 -1662015378366159360 -1662015378408160256 -1662015378456161280 -1662015378495162112 -1662015378546163200 -1662015378591164160 -1662015378636165120 -1662015378684166144 -1662015378726167040 -1662015378768167936 -1662015378813168896 -1662015378855169792 -1662015378894170624 -1662015378936171520 -1662015378978172416 -1662015379023173376 -1662015379065174272 -1662015379107175168 -1662015379149176064 -1662015379194177024 -1662015379236177920 -1662015379278178816 -1662015379323179776 -1662015379365180672 -1662015379419181824 -1662015379461182720 -1662015379500183552 -1662015379542184448 -1662015379584185344 -1662015379629186304 -1662015379680187392 -1662015379722188288 -1662015379767189248 -1662015379812190208 -1662015379854191104 -1662015379896192000 -1662015379941192960 -1662015379989193984 -1662015380037195008 -1662015380082195968 -1662015380130196992 -1662015380175197952 -1662015380220198912 -1662015380265199872 -1662015380313200896 -1662015380355201792 -1662015380397202688 -1662015380439203584 -1662015380481204480 -1662015380526205440 -1662015380568206336 -1662015380616207360 -1662015380658208256 -1662015380706209280 -1662015380760210432 -1662015380805211392 -1662015380853212416 -1662015380895213312 -1662015380937214208 -1662015380982215168 -1662015381027216128 -1662015381078217216 -1662015381120218112 -1662015381162219008 -1662015381204219904 -1662015381246220800 -1662015381288221696 -1662015381333222656 -1662015381378223616 -1662015381423224576 -1662015381468225536 -1662015381513226496 -1662015381558227456 -1662015381600228352 -1662015381639229184 -1662015381681230080 -1662015381723230976 -1662015381768231936 -1662015381816232960 -1662015381861233920 -1662015381903234816 -1662015381945235712 -1662015381990236672 -1662015382038237696 -1662015382086238720 -1662015382134239744 -1662015382182240768 -1662015382230241792 -1662015382278242816 -1662015382323243776 -1662015382365244672 -1662015382407245568 -1662015382458246656 -1662015382500247552 -1662015382545248512 -1662015382581249280 -1662015382623250176 -1662015382662251008 -1662015382713252096 -1662015382755252992 -1662015382797253888 -1662015382839254784 -1662015382878255616 -1662015382923256576 -1662015382965257472 -1662015383007258368 -1662015383052259328 -1662015383097260288 -1662015383145261312 -1662015383193262336 -1662015383238263296 -1662015383277264128 -1662015383319265024 -1662015383364265984 -1662015383409266944 -1662015383454267904 -1662015383496268800 -1662015383541269760 -1662015383583270656 -1662015383631271680 -1662015383676272640 -1662015383718273536 -1662015383763274496 -1662015383808275456 -1662015383850276352 -1662015383892277248 -1662015383934278144 -1662015383985279232 -1662015384024280064 -1662015384066280960 -1662015384108281856 -1662015384153282816 -1662015384198283776 -1662015384246284800 -1662015384288285696 -1662015384336286720 -1662015384381287680 -1662015384423288576 -1662015384465289472 -1662015384507290368 -1662015384558291456 -1662015384603292416 -1662015384642293248 -1662015384687294208 -1662015384732295168 -1662015384789296384 -1662015384831297280 -1662015384879298304 -1662015384921299200 -1662015384963300096 -1662015385005300992 -1662015385047301888 -1662015385089302784 -1662015385131303680 -1662015385176304640 -1662015385218305536 -1662015385263306496 -1662015385305307392 -1662015385347308288 -1662015385392309248 -1662015385434310144 -1662015385476311040 -1662015385518311936 -1662015385563312896 -1662015385608313856 -1662015385653314816 -1662015385710316032 -1662015385755316992 -1662015385797317888 -1662015385839318784 -1662015385884319744 -1662015385929320704 -1662015385974321664 -1662015386022322688 -1662015386061323520 -1662015386103324416 -1662015386145325312 -1662015386187326208 -1662015386229327104 -1662015386274328064 -1662015386322329088 -1662015386370330112 -1662015386412331008 -1662015386457331968 -1662015386502332928 -1662015386547333888 -1662015386595334912 -1662015386637335808 -1662015386688336896 -1662015386733337856 -1662015386778338816 -1662015386820339712 -1662015386868340736 -1662015386916341760 -1662015386961342720 -1662015387003343616 -1662015387048344576 -1662015387093345536 -1662015387141346560 -1662015387186347520 -1662015387228348416 -1662015387282349568 -1662015387330350592 -1662015387366351360 -1662015387408352256 -1662015387447353088 -1662015387489353984 -1662015387534354944 -1662015387579355904 -1662015387627356928 -1662015387669357824 -1662015387714358784 -1662015387759359744 -1662015387804360704 -1662015387858361856 -1662015387900362752 -1662015387945363712 -1662015387987364608 -1662015388029365504 -1662015388071366400 -1662015388119367424 -1662015388164368384 -1662015388209369344 -1662015388251370240 -1662015388293371136 -1662015388332371968 -1662015388374372864 -1662015388419373824 -1662015388464374784 -1662015388506375680 -1662015388548376576 -1662015388593377536 -1662015388644378624 -1662015388689379584 -1662015388731380480 -1662015388776381440 -1662015388818382336 -1662015388860383232 -1662015388905384192 -1662015388944385024 -1662015388992386048 -1662015389040387072 -1662015389082387968 -1662015389124388864 -1662015389163389696 -1662015389205390592 -1662015389247391488 -1662015389295392512 -1662015389337393408 -1662015389382394368 -1662015389424395264 -1662015389466396160 -1662015389508397056 -1662015389556398080 -1662015389598398976 -1662015389643399936 -1662015389682400768 -1662015389724401664 -1662015389766402560 -1662015389814403584 -1662015389859404544 -1662015389904405504 -1662015389940406272 -1662015389979407104 -1662015390021408000 -1662015390072409088 -1662015390120410112 -1662015390162411008 -1662015390210412032 -1662015390255412992 -1662015390300413952 -1662015390342414848 -1662015390384415744 -1662015390429416704 -1662015390468417536 -1662015390510418432 -1662015390555419392 -1662015390597420288 -1662015390639421184 -1662015390684422144 -1662015390726423040 -1662015390771424000 -1662015390813424896 -1662015390855425792 -1662015390897426688 -1662015390936427520 -1662015390978428416 -1662015391020429312 -1662015391062430208 -1662015391104431104 -1662015391152432128 -1662015391194433024 -1662015391236433920 -1662015391278434816 -1662015391326435840 -1662015391371436800 -1662015391416437760 -1662015391461438720 -1662015391503439616 -1662015391545440512 -1662015391587441408 -1662015391632442368 -1662015391677443328 -1662015391722444288 -1662015391764445184 -1662015391806446080 -1662015391848446976 -1662015391890447872 -1662015391932448768 -1662015391974449664 -1662015392019450624 -1662015392070451712 -1662015392112452608 -1662015392160453632 -1662015392202454528 -1662015392247455488 -1662015392289456384 -1662015392334457344 -1662015392379458304 -1662015392424459264 -1662015392469460224 -1662015392520461312 -1662015392562462208 -1662015392607463168 -1662015392652464128 -1662015392694465024 -1662015392739465984 -1662015392784466944 -1662015392829467904 -1662015392877468928 -1662015392916469760 -1662015392955470592 -1662015392997471488 -1662015393054472704 -1662015393102473728 -1662015393147474688 -1662015393192475648 -1662015393240476672 -1662015393282477568 -1662015393324478464 -1662015393372479488 -1662015393423480576 -1662015393468481536 -1662015393510482432 -1662015393552483328 -1662015393597484288 -1662015393642485248 -1662015393690486272 -1662015393732487168 -1662015393771488000 -1662015393819489024 -1662015393864489984 -1662015393906490880 -1662015393948491776 -1662015393993492736 -1662015394038493696 -1662015394089494784 -1662015394131495680 -1662015394173496576 -1662015394218497536 -1662015394260498432 -1662015394302499328 -1662015394347500288 -1662015394392501248 -1662015394434502144 -1662015394479503104 -1662015394521504000 -1662015394566504960 -1662015394608505856 -1662015394653506816 -1662015394698507776 -1662015394746508800 -1662015394788509696 -1662015394833510656 -1662015394878511616 -1662015394923512576 -1662015394965513472 -1662015395010514432 -1662015395061515520 -1662015395097516288 -1662015395139517184 -1662015395181518080 -1662015395223518976 -1662015395274520064 -1662015395316520960 -1662015395367522048 -1662015395409522944 -1662015395454523904 -1662015395499524864 -1662015395550525952 -1662015395589526784 -1662015395631527680 -1662015395679528704 -1662015395724529664 -1662015395766530560 -1662015395814531584 -1662015395856532480 -1662015395898533376 -1662015395943534336 -1662015395991535360 -1662015396036536320 -1662015396078537216 -1662015396126538240 -1662015396168539136 -1662015396216540160 -1662015396264541184 -1662015396309542144 -1662015396357543168 -1662015396399544064 -1662015396447545088 -1662015396492546048 -1662015396540547072 -1662015396582547968 -1662015396627548928 -1662015396675549952 -1662015396720550912 -1662015396765551872 -1662015396807552768 -1662015396852553728 -1662015396894554624 -1662015396939555584 -1662015396987556608 -1662015397020557312 -1662015397068558336 -1662015397116559360 -1662015397161560320 -1662015397203561216 -1662015397248562176 -1662015397287563008 -1662015397332563968 -1662015397377564928 -1662015397416565760 -1662015397458566656 -1662015397503567616 -1662015397545568512 -1662015397584569344 -1662015397632570368 -1662015397677571328 -1662015397722572288 -1662015397767573248 -1662015397815574272 -1662015397860575232 -1662015397905576192 -1662015397953577216 -1662015397995578112 -1662015398040579072 -1662015398085580032 -1662015398130580992 -1662015398172581888 -1662015398217582848 -1662015398259583744 -1662015398301584640 -1662015398349585664 -1662015398391586560 -1662015398436587520 -1662015398481588480 -1662015398523589376 -1662015398568590336 -1662015398613591296 -1662015398655592192 -1662015398700593152 -1662015398742594048 -1662015398793595136 -1662015398835596032 -1662015398883597056 -1662015398928598016 -1662015398967598848 -1662015399009599744 -1662015399054600704 -1662015399102601728 -1662015399150602752 -1662015399198603776 -1662015399240604672 -1662015399282605568 -1662015399330606592 -1662015399375607552 -1662015399423608576 -1662015399465609472 -1662015399507610368 -1662015399552611328 -1662015399591612160 -1662015399636613120 -1662015399678614016 -1662015399723614976 -1662015399765615872 -1662015399819617024 -1662015399867618048 -1662015399921619200 -1662015399960620032 -1662015400005620992 -1662015400050621952 -1662015400098622976 -1662015400140623872 -1662015400182624768 -1662015400227625728 -1662015400272626688 -1662015400311627520 -1662015400353628416 -1662015400404629504 -1662015400446630400 -1662015400488631296 -1662015400530632192 -1662015400575633152 -1662015400617634048 -1662015400665635072 -1662015400710636032 -1662015400752636928 diff --git a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track2.txt b/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track2.txt deleted file mode 100644 index c35350d63a..0000000000 --- a/Examples/Monocular/MIMIR_TimeStamps/SeaFloor_track2.txt +++ /dev/null @@ -1,2537 +0,0 @@ -1662122091767260928 -1662122091809261824 -1662122091851262720 -1662122091893263616 -1662122091935264512 -1662122091980265472 -1662122092022266368 -1662122092064267264 -1662122092106268160 -1662122092148269056 -1662122092193270016 -1662122092232270848 -1662122092280271872 -1662122092322272768 -1662122092364273664 -1662122092412274688 -1662122092454275584 -1662122092493276416 -1662122092535277312 -1662122092580278272 -1662122092625279232 -1662122092667280128 -1662122092709281024 -1662122092751281920 -1662122092796282880 -1662122092847283968 -1662122092889284864 -1662122092931285760 -1662122092970286592 -1662122093015287552 -1662122093060288512 -1662122093105289472 -1662122093153290496 -1662122093201291520 -1662122093240292352 -1662122093282293248 -1662122093324294144 -1662122093366295040 -1662122093408295936 -1662122093453296896 -1662122093501297920 -1662122093543298816 -1662122093591299840 -1662122093633300736 -1662122093675301632 -1662122093723302656 -1662122093768303616 -1662122093810304512 -1662122093855305472 -1662122093894306304 -1662122093939307264 -1662122093981308160 -1662122094023309056 -1662122094065309952 -1662122094110310912 -1662122094146311680 -1662122094191312640 -1662122094227313408 -1662122094275314432 -1662122094317315328 -1662122094359316224 -1662122094395316992 -1662122094437317888 -1662122094482318848 -1662122094524319744 -1662122094566320640 -1662122094611321600 -1662122094653322496 -1662122094695323392 -1662122094740324352 -1662122094782325248 -1662122094824326144 -1662122094872327168 -1662122094917328128 -1662122094965329152 -1662122095007330048 -1662122095052331008 -1662122095094331904 -1662122095139332864 -1662122095181333760 -1662122095220334592 -1662122095265335552 -1662122095316336640 -1662122095358337536 -1662122095406338560 -1662122095454339584 -1662122095496340480 -1662122095541341440 -1662122095586342400 -1662122095625343232 -1662122095667344128 -1662122095709345024 -1662122095751345920 -1662122095793346816 -1662122095835347712 -1662122095874348544 -1662122095916349440 -1662122095958350336 -1662122096000351232 -1662122096045352192 -1662122096084353024 -1662122096120353792 -1662122096162354688 -1662122096204355584 -1662122096243356416 -1662122096279357184 -1662122096327358208 -1662122096375359232 -1662122096417360128 -1662122096453360896 -1662122096495361792 -1662122096540362752 -1662122096585363712 -1662122096627364608 -1662122096669365504 -1662122096717366528 -1662122096759367424 -1662122096801368320 -1662122096843369216 -1662122096885370112 -1662122096924370944 -1662122096966371840 -1662122097005372672 -1662122097047373568 -1662122097089374464 -1662122097134375424 -1662122097179376384 -1662122097221377280 -1662122097263378176 -1662122097305379072 -1662122097347379968 -1662122097395380992 -1662122097437381888 -1662122097479382784 -1662122097521383680 -1662122097563384576 -1662122097605385472 -1662122097656386560 -1662122097704387584 -1662122097743388416 -1662122097785389312 -1662122097836390400 -1662122097881391360 -1662122097923392256 -1662122097968393216 -1662122098010394112 -1662122098052395008 -1662122098094395904 -1662122098136396800 -1662122098178397696 -1662122098226398720 -1662122098271399680 -1662122098316400640 -1662122098358401536 -1662122098397402368 -1662122098439403264 -1662122098481404160 -1662122098529405184 -1662122098577406208 -1662122098628407296 -1662122098670408192 -1662122098712409088 -1662122098757410048 -1662122098796410880 -1662122098841411840 -1662122098883412736 -1662122098922413568 -1662122098970414592 -1662122099012415488 -1662122099054416384 -1662122099096417280 -1662122099141418240 -1662122099183419136 -1662122099222419968 -1662122099267420928 -1662122099315421952 -1662122099360422912 -1662122099405423872 -1662122099450424832 -1662122099498425856 -1662122099537426688 -1662122099585427712 -1662122099624428544 -1662122099669429504 -1662122099711430400 -1662122099753431296 -1662122099798432256 -1662122099843433216 -1662122099888434176 -1662122099933435136 -1662122099969435904 -1662122100014436864 -1662122100056437760 -1662122100101438720 -1662122100146439680 -1662122100197440768 -1662122100236441600 -1662122100281442560 -1662122100323443456 -1662122100365444352 -1662122100410445312 -1662122100449446144 -1662122100494447104 -1662122100536448000 -1662122100578448896 -1662122100617449728 -1662122100659450624 -1662122100701451520 -1662122100743452416 -1662122100785453312 -1662122100824454144 -1662122100866455040 -1662122100908455936 -1662122100950456832 -1662122100992457728 -1662122101037458688 -1662122101079459584 -1662122101124460544 -1662122101160461312 -1662122101205462272 -1662122101244463104 -1662122101298464256 -1662122101340465152 -1662122101379465984 -1662122101421466880 -1662122101466467840 -1662122101514468864 -1662122101556469760 -1662122101601470720 -1662122101649471744 -1662122101694472704 -1662122101733473536 -1662122101784474624 -1662122101826475520 -1662122101865476352 -1662122101904477184 -1662122101949478144 -1662122101997479168 -1662122102042480128 -1662122102090481152 -1662122102129481984 -1662122102171482880 -1662122102213483776 -1662122102255484672 -1662122102297485568 -1662122102342486528 -1662122102384487424 -1662122102423488256 -1662122102465489152 -1662122102507490048 -1662122102546490880 -1662122102588491776 -1662122102627492608 -1662122102663493376 -1662122102705494272 -1662122102747495168 -1662122102789496064 -1662122102834497024 -1662122102876497920 -1662122102918498816 -1662122102960499712 -1662122103005500672 -1662122103044501504 -1662122103089502464 -1662122103131503360 -1662122103176504320 -1662122103221505280 -1662122103263506176 -1662122103308507136 -1662122103350508032 -1662122103392508928 -1662122103437509888 -1662122103479510784 -1662122103515511552 -1662122103557512448 -1662122103593513216 -1662122103635514112 -1662122103680515072 -1662122103725516032 -1662122103767516928 -1662122103809517824 -1662122103845518592 -1662122103887519488 -1662122103932520448 -1662122103974521344 -1662122104019522304 -1662122104061523200 -1662122104106524160 -1662122104148525056 -1662122104184525824 -1662122104223526656 -1662122104268527616 -1662122104310528512 -1662122104355529472 -1662122104397530368 -1662122104439531264 -1662122104478532096 -1662122104520532992 -1662122104562533888 -1662122104604534784 -1662122104646535680 -1662122104688536576 -1662122104730537472 -1662122104772538368 -1662122104814539264 -1662122104859540224 -1662122104904541184 -1662122104949542144 -1662122104988542976 -1662122105027543808 -1662122105072544768 -1662122105114545664 -1662122105159546624 -1662122105201547520 -1662122105243548416 -1662122105285549312 -1662122105327550208 -1662122105366551040 -1662122105408551936 -1662122105450552832 -1662122105489553664 -1662122105531554560 -1662122105573555456 -1662122105615556352 -1662122105657557248 -1662122105699558144 -1662122105747559168 -1662122105789560064 -1662122105834561024 -1662122105882562048 -1662122105924562944 -1662122105969563904 -1662122106008564736 -1662122106053565696 -1662122106092566528 -1662122106134567424 -1662122106173568256 -1662122106215569152 -1662122106251569920 -1662122106290570752 -1662122106326571520 -1662122106374572544 -1662122106416573440 -1662122106461574400 -1662122106506575360 -1662122106548576256 -1662122106584577024 -1662122106626577920 -1662122106665578752 -1662122106707579648 -1662122106752580608 -1662122106794581504 -1662122106836582400 -1662122106881583360 -1662122106923584256 -1662122106965585152 -1662122107007586048 -1662122107055587072 -1662122107097587968 -1662122107136588800 -1662122107172589568 -1662122107214590464 -1662122107259591424 -1662122107307592448 -1662122107349593344 -1662122107394594304 -1662122107433595136 -1662122107472595968 -1662122107517596928 -1662122107556597760 -1662122107598598656 -1662122107643599616 -1662122107682600448 -1662122107724601344 -1662122107769602304 -1662122107814603264 -1662122107862604288 -1662122107904605184 -1662122107949606144 -1662122107991607040 -1662122108030607872 -1662122108075608832 -1662122108117609728 -1662122108159610624 -1662122108207611648 -1662122108249612544 -1662122108291613440 -1662122108339614464 -1662122108387615488 -1662122108429616384 -1662122108471617280 -1662122108516618240 -1662122108558619136 -1662122108600620032 -1662122108642620928 -1662122108687621888 -1662122108729622784 -1662122108774623744 -1662122108816624640 -1662122108861625600 -1662122108909626624 -1662122108951627520 -1662122108990628352 -1662122109035629312 -1662122109083630336 -1662122109125631232 -1662122109164632064 -1662122109206632960 -1662122109245633792 -1662122109287634688 -1662122109332635648 -1662122109368636416 -1662122109410637312 -1662122109452638208 -1662122109491639040 -1662122109539640064 -1662122109587641088 -1662122109635642112 -1662122109674642944 -1662122109716643840 -1662122109761644800 -1662122109803645696 -1662122109845646592 -1662122109887647488 -1662122109929648384 -1662122109968649216 -1662122110010650112 -1662122110055651072 -1662122110097651968 -1662122110136652800 -1662122110178653696 -1662122110220654592 -1662122110265655552 -1662122110307656448 -1662122110352657408 -1662122110394658304 -1662122110436659200 -1662122110481660160 -1662122110526661120 -1662122110571662080 -1662122110613662976 -1662122110661664000 -1662122110703664896 -1662122110748665856 -1662122110793666816 -1662122110835667712 -1662122110880668672 -1662122110919669504 -1662122110970670592 -1662122111012671488 -1662122111054672384 -1662122111093673216 -1662122111138674176 -1662122111186675200 -1662122111225676032 -1662122111267676928 -1662122111309677824 -1662122111351678720 -1662122111393679616 -1662122111435680512 -1662122111477681408 -1662122111522682368 -1662122111570683392 -1662122111615684352 -1662122111657685248 -1662122111702686208 -1662122111747687168 -1662122111789688064 -1662122111834689024 -1662122111876689920 -1662122111918690816 -1662122111963691776 -1662122112005692672 -1662122112047693568 -1662122112089694464 -1662122112134695424 -1662122112182696448 -1662122112224697344 -1662122112266698240 -1662122112308699136 -1662122112353700096 -1662122112395700992 -1662122112434701824 -1662122112476702720 -1662122112521703680 -1662122112572704768 -1662122112617705728 -1662122112656706560 -1662122112698707456 -1662122112746708480 -1662122112788709376 -1662122112833710336 -1662122112875711232 -1662122112914712064 -1662122112953712896 -1662122112998713856 -1662122113037714688 -1662122113079715584 -1662122113118716416 -1662122113154717184 -1662122113196718080 -1662122113235718912 -1662122113277719808 -1662122113319720704 -1662122113355721472 -1662122113400722432 -1662122113448723456 -1662122113487724288 -1662122113529725184 -1662122113571726080 -1662122113613726976 -1662122113655727872 -1662122113700728832 -1662122113742729728 -1662122113784730624 -1662122113826731520 -1662122113871732480 -1662122113913733376 -1662122113958734336 -1662122114006735360 -1662122114048736256 -1662122114090737152 -1662122114132738048 -1662122114177739008 -1662122114222739968 -1662122114264740864 -1662122114309741824 -1662122114354742784 -1662122114396743680 -1662122114438744576 -1662122114489745664 -1662122114534746624 -1662122114579747584 -1662122114627748608 -1662122114669749504 -1662122114708750336 -1662122114750751232 -1662122114792752128 -1662122114837753088 -1662122114882754048 -1662122114921754880 -1662122114966755840 -1662122115008756736 -1662122115059757824 -1662122115110758912 -1662122115149759744 -1662122115194760704 -1662122115236761600 -1662122115278762496 -1662122115320763392 -1662122115365764352 -1662122115404765184 -1662122115446766080 -1662122115491767040 -1662122115533767936 -1662122115575768832 -1662122115620769792 -1662122115662770688 -1662122115707771648 -1662122115749772544 -1662122115788773376 -1662122115830774272 -1662122115875775232 -1662122115917776128 -1662122115959777024 -1662122115998777856 -1662122116043778816 -1662122116088779776 -1662122116136780800 -1662122116175781632 -1662122116217782528 -1662122116265783552 -1662122116307784448 -1662122116352785408 -1662122116394786304 -1662122116430787072 -1662122116475788032 -1662122116517788928 -1662122116562789888 -1662122116604790784 -1662122116643791616 -1662122116685792512 -1662122116727793408 -1662122116769794304 -1662122116811795200 -1662122116856796160 -1662122116901797120 -1662122116943798016 -1662122116985798912 -1662122117033799936 -1662122117075800832 -1662122117114801664 -1662122117153802496 -1662122117192803328 -1662122117240804352 -1662122117282805248 -1662122117324806144 -1662122117363806976 -1662122117408807936 -1662122117450808832 -1662122117495809792 -1662122117540810752 -1662122117582811648 -1662122117627812608 -1662122117669813504 -1662122117711814400 -1662122117759815424 -1662122117798816256 -1662122117846817280 -1662122117888818176 -1662122117933819136 -1662122117978820096 -1662122118023821056 -1662122118068822016 -1662122118113822976 -1662122118161824000 -1662122118206824960 -1662122118248825856 -1662122118287826688 -1662122118332827648 -1662122118374828544 -1662122118416829440 -1662122118461830400 -1662122118503831296 -1662122118548832256 -1662122118593833216 -1662122118638834176 -1662122118680835072 -1662122118722835968 -1662122118764836864 -1662122118806837760 -1662122118848838656 -1662122118890839552 -1662122118935840512 -1662122118977841408 -1662122119019842304 -1662122119061843200 -1662122119100844032 -1662122119145844992 -1662122119187845888 -1662122119226846720 -1662122119271847680 -1662122119319848704 -1662122119364849664 -1662122119403850496 -1662122119442851328 -1662122119484852224 -1662122119526853120 -1662122119571854080 -1662122119613854976 -1662122119652855808 -1662122119697856768 -1662122119739857664 -1662122119778858496 -1662122119823859456 -1662122119874860544 -1662122119922861568 -1662122119964862464 -1662122120009863424 -1662122120054864384 -1662122120096865280 -1662122120138866176 -1662122120180867072 -1662122120222867968 -1662122120270868992 -1662122120315869952 -1662122120360870912 -1662122120405871872 -1662122120450872832 -1662122120486873600 -1662122120525874432 -1662122120567875328 -1662122120609876224 -1662122120648877056 -1662122120690877952 -1662122120732878848 -1662122120777879808 -1662122120819880704 -1662122120858881536 -1662122120903882496 -1662122120948883456 -1662122120987884288 -1662122121023885056 -1662122121068886016 -1662122121110886912 -1662122121152887808 -1662122121194888704 -1662122121239889664 -1662122121281890560 -1662122121320891392 -1662122121365892352 -1662122121407893248 -1662122121449894144 -1662122121491895040 -1662122121536896000 -1662122121581896960 -1662122121626897920 -1662122121668898816 -1662122121710899712 -1662122121752900608 -1662122121797901568 -1662122121836902400 -1662122121878903296 -1662122121923904256 -1662122121968905216 -1662122122007906048 -1662122122049906944 -1662122122091907840 -1662122122136908800 -1662122122178909696 -1662122122223910656 -1662122122265911552 -1662122122307912448 -1662122122349913344 -1662122122394914304 -1662122122436915200 -1662122122481916160 -1662122122520916992 -1662122122568918016 -1662122122616919040 -1662122122661920000 -1662122122703920896 -1662122122745921792 -1662122122790922752 -1662122122832923648 -1662122122874924544 -1662122122913925376 -1662122122955926272 -1662122123000927232 -1662122123042928128 -1662122123087929088 -1662122123132930048 -1662122123171930880 -1662122123210931712 -1662122123249932544 -1662122123288933376 -1662122123330934272 -1662122123372935168 -1662122123414936064 -1662122123456936960 -1662122123498937856 -1662122123540938752 -1662122123579939584 -1662122123621940480 -1662122123663941376 -1662122123708942336 -1662122123753943296 -1662122123795944192 -1662122123837945088 -1662122123879945984 -1662122123918946816 -1662122123960947712 -1662122124005948672 -1662122124047949568 -1662122124092950528 -1662122124134951424 -1662122124179952384 -1662122124224953344 -1662122124266954240 -1662122124311955200 -1662122124359956224 -1662122124398957056 -1662122124440957952 -1662122124482958848 -1662122124530959872 -1662122124572960768 -1662122124617961728 -1662122124659962624 -1662122124701963520 -1662122124743964416 -1662122124788965376 -1662122124833966336 -1662122124878967296 -1662122124923968256 -1662122124968969216 -1662122125013970176 -1662122125058971136 -1662122125097971968 -1662122125139972864 -1662122125181973760 -1662122125226974720 -1662122125271975680 -1662122125310976512 -1662122125361977600 -1662122125400978432 -1662122125445979392 -1662122125493980416 -1662122125535981312 -1662122125583982336 -1662122125625983232 -1662122125670984192 -1662122125709985024 -1662122125751985920 -1662122125793986816 -1662122125835987712 -1662122125874988544 -1662122125916989440 -1662122125961990400 -1662122126003991296 -1662122126045992192 -1662122126087993088 -1662122126129993984 -1662122126171994880 -1662122126219995904 -1662122126264996864 -1662122126303997696 -1662122126351998720 -1662122126393999616 -1662122126436000512 -1662122126478001408 -1662122126523002368 -1662122126565003264 -1662122126601004032 -1662122126640004864 -1662122126685005824 -1662122126727006720 -1662122126769007616 -1662122126808008448 -1662122126850009344 -1662122126895010304 -1662122126940011264 -1662122126985012224 -1662122127021012992 -1662122127063013888 -1662122127105014784 -1662122127144015616 -1662122127189016576 -1662122127231017472 -1662122127273018368 -1662122127315019264 -1662122127363020288 -1662122127408021248 -1662122127462022400 -1662122127507023360 -1662122127549024256 -1662122127594025216 -1662122127639026176 -1662122127681027072 -1662122127729028096 -1662122127783029248 -1662122127828030208 -1662122127867031040 -1662122127909031936 -1662122127954032896 -1662122127999033856 -1662122128044034816 -1662122128086035712 -1662122128125036544 -1662122128170037504 -1662122128212038400 -1662122128257039360 -1662122128302040320 -1662122128347041280 -1662122128389042176 -1662122128440043264 -1662122128479044096 -1662122128518044928 -1662122128557045760 -1662122128599046656 -1662122128644047616 -1662122128689048576 -1662122128737049600 -1662122128776050432 -1662122128824051456 -1662122128866052352 -1662122128908053248 -1662122128950054144 -1662122128992055040 -1662122129034055936 -1662122129073056768 -1662122129115057664 -1662122129160058624 -1662122129208059648 -1662122129247060480 -1662122129295061504 -1662122129340062464 -1662122129382063360 -1662122129427064320 -1662122129472065280 -1662122129517066240 -1662122129559067136 -1662122129601068032 -1662122129640068864 -1662122129679069696 -1662122129727070720 -1662122129766071552 -1662122129808072448 -1662122129844073216 -1662122129889074176 -1662122129934075136 -1662122129976076032 -1662122130021076992 -1662122130066077952 -1662122130114078976 -1662122130159079936 -1662122130198080768 -1662122130240081664 -1662122130282082560 -1662122130330083584 -1662122130369084416 -1662122130414085376 -1662122130456086272 -1662122130498087168 -1662122130540088064 -1662122130582088960 -1662122130624089856 -1662122130669090816 -1662122130711091712 -1662122130753092608 -1662122130798093568 -1662122130840094464 -1662122130885095424 -1662122130927096320 -1662122130969097216 -1662122131011098112 -1662122131056099072 -1662122131095099904 -1662122131137100800 -1662122131182101760 -1662122131227102720 -1662122131263103488 -1662122131305104384 -1662122131350105344 -1662122131395106304 -1662122131437107200 -1662122131482108160 -1662122131527109120 -1662122131566109952 -1662122131605110784 -1662122131647111680 -1662122131689112576 -1662122131737113600 -1662122131776114432 -1662122131821115392 -1662122131863116288 -1662122131905117184 -1662122131947118080 -1662122131989118976 -1662122132028119808 -1662122132073120768 -1662122132115121664 -1662122132154122496 -1662122132205123584 -1662122132247124480 -1662122132286125312 -1662122132325126144 -1662122132370127104 -1662122132409127936 -1662122132454128896 -1662122132502129920 -1662122132541130752 -1662122132583131648 -1662122132628132608 -1662122132670133504 -1662122132712134400 -1662122132754135296 -1662122132799136256 -1662122132838137088 -1662122132877137920 -1662122132919138816 -1662122132964139776 -1662122133006140672 -1662122133051141632 -1662122133093142528 -1662122133135143424 -1662122133180144384 -1662122133225145344 -1662122133267146240 -1662122133309147136 -1662122133351148032 -1662122133393148928 -1662122133438149888 -1662122133480150784 -1662122133525151744 -1662122133567152640 -1662122133609153536 -1662122133654154496 -1662122133696155392 -1662122133744156416 -1662122133786157312 -1662122133831158272 -1662122133876159232 -1662122133921160192 -1662122133966161152 -1662122134011162112 -1662122134059163136 -1662122134101164032 -1662122134143164928 -1662122134188165888 -1662122134233166848 -1662122134281167872 -1662122134326168832 -1662122134368169728 -1662122134410170624 -1662122134452171520 -1662122134500172544 -1662122134539173376 -1662122134584174336 -1662122134626175232 -1662122134668176128 -1662122134710177024 -1662122134755177984 -1662122134797178880 -1662122134839179776 -1662122134887180800 -1662122134932181760 -1662122134971182592 -1662122135013183488 -1662122135052184320 -1662122135094185216 -1662122135133186048 -1662122135175186944 -1662122135217187840 -1662122135262188800 -1662122135310189824 -1662122135355190784 -1662122135400191744 -1662122135442192640 -1662122135487193600 -1662122135526194432 -1662122135571195392 -1662122135613196288 -1662122135652197120 -1662122135697198080 -1662122135736198912 -1662122135781199872 -1662122135823200768 -1662122135868201728 -1662122135907202560 -1662122135952203520 -1662122135994204416 -1662122136039205376 -1662122136081206272 -1662122136123207168 -1662122136168208128 -1662122136207208960 -1662122136252209920 -1662122136297210880 -1662122136342211840 -1662122136381212672 -1662122136426213632 -1662122136471214592 -1662122136516215552 -1662122136561216512 -1662122136600217344 -1662122136642218240 -1662122136684219136 -1662122136726220032 -1662122136771220992 -1662122136813221888 -1662122136861222912 -1662122136903223808 -1662122136951224832 -1662122136993225728 -1662122137035226624 -1662122137083227648 -1662122137125228544 -1662122137167229440 -1662122137209230336 -1662122137254231296 -1662122137290232064 -1662122137335233024 -1662122137371233792 -1662122137416234752 -1662122137461235712 -1662122137503236608 -1662122137551237632 -1662122137596238592 -1662122137641239552 -1662122137683240448 -1662122137728241408 -1662122137770242304 -1662122137815243264 -1662122137857244160 -1662122137902245120 -1662122137950246144 -1662122137998247168 -1662122138037248000 -1662122138082248960 -1662122138127249920 -1662122138169250816 -1662122138214251776 -1662122138265252864 -1662122138307253760 -1662122138349254656 -1662122138391255552 -1662122138433256448 -1662122138478257408 -1662122138520258304 -1662122138565259264 -1662122138610260224 -1662122138652261120 -1662122138688261888 -1662122138730262784 -1662122138772263680 -1662122138817264640 -1662122138862265600 -1662122138901266432 -1662122138940267264 -1662122138991268352 -1662122139030269184 -1662122139072270080 -1662122139117271040 -1662122139159271936 -1662122139201272832 -1662122139240273664 -1662122139282274560 -1662122139327275520 -1662122139369276416 -1662122139411277312 -1662122139450278144 -1662122139492279040 -1662122139534279936 -1662122139579280896 -1662122139621281792 -1662122139660282624 -1662122139702283520 -1662122139747284480 -1662122139792285440 -1662122139837286400 -1662122139879287296 -1662122139921288192 -1662122139963289088 -1662122140002289920 -1662122140044290816 -1662122140089291776 -1662122140128292608 -1662122140170293504 -1662122140209294336 -1662122140251295232 -1662122140296296192 -1662122140338297088 -1662122140383298048 -1662122140428299008 -1662122140470299904 -1662122140512300800 -1662122140560301824 -1662122140611302912 -1662122140659303936 -1662122140704304896 -1662122140746305792 -1662122140791306752 -1662122140833307648 -1662122140872308480 -1662122140914309376 -1662122140959310336 -1662122141004311296 -1662122141049312256 -1662122141094313216 -1662122141136314112 -1662122141178315008 -1662122141223315968 -1662122141268316928 -1662122141313317888 -1662122141352318720 -1662122141394319616 -1662122141436320512 -1662122141478321408 -1662122141523322368 -1662122141565323264 -1662122141610324224 -1662122141658325248 -1662122141706326272 -1662122141742327040 -1662122141790328064 -1662122141832328960 -1662122141871329792 -1662122141916330752 -1662122141961331712 -1662122142006332672 -1662122142045333504 -1662122142087334400 -1662122142129335296 -1662122142174336256 -1662122142216337152 -1662122142261338112 -1662122142303339008 -1662122142351340032 -1662122142393340928 -1662122142435341824 -1662122142480342784 -1662122142522343680 -1662122142561344512 -1662122142603345408 -1662122142648346368 -1662122142693347328 -1662122142735348224 -1662122142783349248 -1662122142825350144 -1662122142867351040 -1662122142915352064 -1662122142960353024 -1662122143002353920 -1662122143041354752 -1662122143086355712 -1662122143131356672 -1662122143173357568 -1662122143215358464 -1662122143260359424 -1662122143299360256 -1662122143341361152 -1662122143383362048 -1662122143425362944 -1662122143467363840 -1662122143512364800 -1662122143563365888 -1662122143605366784 -1662122143644367616 -1662122143683368448 -1662122143725369344 -1662122143767370240 -1662122143812371200 -1662122143854372096 -1662122143893372928 -1662122143935373824 -1662122143980374784 -1662122144022375680 -1662122144064376576 -1662122144112377600 -1662122144154378496 -1662122144199379456 -1662122144247380480 -1662122144289381376 -1662122144331382272 -1662122144373383168 -1662122144418384128 -1662122144454384896 -1662122144499385856 -1662122144541386752 -1662122144583387648 -1662122144628388608 -1662122144664389376 -1662122144709390336 -1662122144754391296 -1662122144793392128 -1662122144838393088 -1662122144883394048 -1662122144925394944 -1662122144973395968 -1662122145021396992 -1662122145063397888 -1662122145105398784 -1662122145144399616 -1662122145189400576 -1662122145231401472 -1662122145270402304 -1662122145315403264 -1662122145360404224 -1662122145408405248 -1662122145459406336 -1662122145504407296 -1662122145546408192 -1662122145588409088 -1662122145633410048 -1662122145678411008 -1662122145720411904 -1662122145765412864 -1662122145813413888 -1662122145855414784 -1662122145903415808 -1662122145948416768 -1662122145987417600 -1662122146032418560 -1662122146074419456 -1662122146122420480 -1662122146167421440 -1662122146212422400 -1662122146257423360 -1662122146302424320 -1662122146344425216 -1662122146389426176 -1662122146434427136 -1662122146476428032 -1662122146521428992 -1662122146563429888 -1662122146605430784 -1662122146647431680 -1662122146689432576 -1662122146734433536 -1662122146779434496 -1662122146821435392 -1662122146863436288 -1662122146908437248 -1662122146950438144 -1662122146992439040 -1662122147034439936 -1662122147070440704 -1662122147112441600 -1662122147163442688 -1662122147205443584 -1662122147244444416 -1662122147289445376 -1662122147331446272 -1662122147373447168 -1662122147415448064 -1662122147454448896 -1662122147496449792 -1662122147541450752 -1662122147583451648 -1662122147625452544 -1662122147670453504 -1662122147712454400 -1662122147754455296 -1662122147796456192 -1662122147838457088 -1662122147886458112 -1662122147931459072 -1662122147973459968 -1662122148018460928 -1662122148063461888 -1662122148105462784 -1662122148150463744 -1662122148192464640 -1662122148240465664 -1662122148279466496 -1662122148321467392 -1662122148366468352 -1662122148408469248 -1662122148447470080 -1662122148492471040 -1662122148534471936 -1662122148576472832 -1662122148621473792 -1662122148663474688 -1662122148705475584 -1662122148747476480 -1662122148792477440 -1662122148837478400 -1662122148882479360 -1662122148930480384 -1662122148972481280 -1662122149014482176 -1662122149059483136 -1662122149104484096 -1662122149146484992 -1662122149191485952 -1662122149233486848 -1662122149281487872 -1662122149323488768 -1662122149365489664 -1662122149407490560 -1662122149449491456 -1662122149491492352 -1662122149536493312 -1662122149575494144 -1662122149617495040 -1662122149659495936 -1662122149704496896 -1662122149746497792 -1662122149788498688 -1662122149830499584 -1662122149872500480 -1662122149914501376 -1662122149956502272 -1662122150001503232 -1662122150043504128 -1662122150088505088 -1662122150127505920 -1662122150169506816 -1662122150208507648 -1662122150250508544 -1662122150292509440 -1662122150334510336 -1662122150379511296 -1662122150421512192 -1662122150463513088 -1662122150511514112 -1662122150553515008 -1662122150592515840 -1662122150634516736 -1662122150679517696 -1662122150721518592 -1662122150763519488 -1662122150805520384 -1662122150847521280 -1662122150895522304 -1662122150940523264 -1662122150988524288 -1662122151033525248 -1662122151078526208 -1662122151123527168 -1662122151165528064 -1662122151210529024 -1662122151252529920 -1662122151297530880 -1662122151342531840 -1662122151384532736 -1662122151423533568 -1662122151465534464 -1662122151513535488 -1662122151561536512 -1662122151603537408 -1662122151648538368 -1662122151690539264 -1662122151735540224 -1662122151777541120 -1662122151819542016 -1662122151858542848 -1662122151903543808 -1662122151942544640 -1662122151987545600 -1662122152035546624 -1662122152077547520 -1662122152119548416 -1662122152164549376 -1662122152209550336 -1662122152254551296 -1662122152293552128 -1662122152335553024 -1662122152374553856 -1662122152416554752 -1662122152455555584 -1662122152497556480 -1662122152548557568 -1662122152587558400 -1662122152632559360 -1662122152674560256 -1662122152725561344 -1662122152770562304 -1662122152815563264 -1662122152857564160 -1662122152902565120 -1662122152941565952 -1662122152986566912 -1662122153028567808 -1662122153073568768 -1662122153115569664 -1662122153157570560 -1662122153199571456 -1662122153244572416 -1662122153286573312 -1662122153331574272 -1662122153376575232 -1662122153418576128 -1662122153463577088 -1662122153505577984 -1662122153550578944 -1662122153586579712 -1662122153637580800 -1662122153679581696 -1662122153721582592 -1662122153760583424 -1662122153805584384 -1662122153853585408 -1662122153901586432 -1662122153943587328 -1662122153982588160 -1662122154021588992 -1662122154063589888 -1662122154111590912 -1662122154153591808 -1662122154198592768 -1662122154243593728 -1662122154285594624 -1662122154324595456 -1662122154369596416 -1662122154411597312 -1662122154447598080 -1662122154489598976 -1662122154534599936 -1662122154579600896 -1662122154624601856 -1662122154666602752 -1662122154708603648 -1662122154750604544 -1662122154795605504 -1662122154837606400 -1662122154879607296 -1662122154924608256 -1662122154972609280 -1662122155014610176 -1662122155056611072 -1662122155095611904 -1662122155137612800 -1662122155179613696 -1662122155221614592 -1662122155260615424 -1662122155305616384 -1662122155347617280 -1662122155389618176 -1662122155434619136 -1662122155479620096 -1662122155524621056 -1662122155569622016 -1662122155611622912 -1662122155650623744 -1662122155695624704 -1662122155737625600 -1662122155779626496 -1662122155824627456 -1662122155866628352 -1662122155914629376 -1662122155953630208 -1662122155995631104 -1662122156043632128 -1662122156088633088 -1662122156130633984 -1662122156172634880 -1662122156214635776 -1662122156259636736 -1662122156307637760 -1662122156349638656 -1662122156397639680 -1662122156436640512 -1662122156481641472 -1662122156535642624 -1662122156574643456 -1662122156619644416 -1662122156667645440 -1662122156709646336 -1662122156751647232 -1662122156799648256 -1662122156841649152 -1662122156883650048 -1662122156928651008 -1662122156973651968 -1662122157015652864 -1662122157057653760 -1662122157102654720 -1662122157144655616 -1662122157183656448 -1662122157231657472 -1662122157273658368 -1662122157315659264 -1662122157363660288 -1662122157408661248 -1662122157450662144 -1662122157498663168 -1662122157537664000 -1662122157576664832 -1662122157618665728 -1662122157663666688 -1662122157705667584 -1662122157747668480 -1662122157789669376 -1662122157837670400 -1662122157882671360 -1662122157924672256 -1662122157966673152 -1662122158014674176 -1662122158062675200 -1662122158101676032 -1662122158149677056 -1662122158191677952 -1662122158236678912 -1662122158275679744 -1662122158317680640 -1662122158353681408 -1662122158395682304 -1662122158440683264 -1662122158482684160 -1662122158524685056 -1662122158572686080 -1662122158617687040 -1662122158662688000 -1662122158704688896 -1662122158746689792 -1662122158791690752 -1662122158830691584 -1662122158872692480 -1662122158911693312 -1662122158953694208 -1662122158998695168 -1662122159043696128 -1662122159085697024 -1662122159127697920 -1662122159163698688 -1662122159205699584 -1662122159247700480 -1662122159292701440 -1662122159337702400 -1662122159382703360 -1662122159421704192 -1662122159463705088 -1662122159502705920 -1662122159550706944 -1662122159589707776 -1662122159634708736 -1662122159673709568 -1662122159727710720 -1662122159766711552 -1662122159808712448 -1662122159850713344 -1662122159895714304 -1662122159940715264 -1662122159982716160 -1662122160021716992 -1662122160063717888 -1662122160108718848 -1662122160153719808 -1662122160201720832 -1662122160240721664 -1662122160282722560 -1662122160324723456 -1662122160366724352 -1662122160408725248 -1662122160456726272 -1662122160501727232 -1662122160546728192 -1662122160588729088 -1662122160636730112 -1662122160684731136 -1662122160732732160 -1662122160774733056 -1662122160816733952 -1662122160861734912 -1662122160903735808 -1662122160942736640 -1662122160984737536 -1662122161026738432 -1662122161068739328 -1662122161113740288 -1662122161158741248 -1662122161203742208 -1662122161245743104 -1662122161287744000 -1662122161332744960 -1662122161377745920 -1662122161419746816 -1662122161461747712 -1662122161503748608 -1662122161545749504 -1662122161593750528 -1662122161635751424 -1662122161680752384 -1662122161722753280 -1662122161764754176 -1662122161806755072 -1662122161845755904 -1662122161884756736 -1662122161926757632 -1662122161974758656 -1662122162016759552 -1662122162052760320 -1662122162091761152 -1662122162133762048 -1662122162178763008 -1662122162223763968 -1662122162265764864 -1662122162313765888 -1662122162355766784 -1662122162397767680 -1662122162439768576 -1662122162484769536 -1662122162523770368 -1662122162565771264 -1662122162607772160 -1662122162652773120 -1662122162694774016 -1662122162733774848 -1662122162778775808 -1662122162823776768 -1662122162868777728 -1662122162910778624 -1662122162949779456 -1662122162991780352 -1662122163039781376 -1662122163084782336 -1662122163126783232 -1662122163168784128 -1662122163213785088 -1662122163258786048 -1662122163297786880 -1662122163339787776 -1662122163378788608 -1662122163420789504 -1662122163456790272 -1662122163504791296 -1662122163549792256 -1662122163591793152 -1662122163633794048 -1662122163675794944 -1662122163717795840 -1662122163762796800 -1662122163804797696 -1662122163849798656 -1662122163888799488 -1662122163930800384 -1662122163972801280 -1662122164011802112 -1662122164050802944 -1662122164092803840 -1662122164134804736 -1662122164176805632 -1662122164221806592 -1662122164263807488 -1662122164305808384 -1662122164347809280 -1662122164392810240 -1662122164431811072 -1662122164470811904 -1662122164512812800 -1662122164548813568 -1662122164593814528 -1662122164635815424 -1662122164677816320 -1662122164719817216 -1662122164764818176 -1662122164812819200 -1662122164857820160 -1662122164893820928 -1662122164938821888 -1662122164980822784 -1662122165025823744 -1662122165070824704 -1662122165112825600 -1662122165157826560 -1662122165202827520 -1662122165244828416 -1662122165283829248 -1662122165325830144 -1662122165367831040 -1662122165412832000 -1662122165454832896 -1662122165499833856 -1662122165544834816 -1662122165586835712 -1662122165628836608 -1662122165670837504 -1662122165715838464 -1662122165760839424 -1662122165805840384 -1662122165853841408 -1662122165895842304 -1662122165934843136 -1662122165979844096 -1662122166021844992 -1662122166063845888 -1662122166105846784 -1662122166147847680 -1662122166189848576 -1662122166231849472 -1662122166276850432 -1662122166321851392 -1662122166360852224 -1662122166405853184 -1662122166450854144 -1662122166492855040 -1662122166531855872 -1662122166570856704 -1662122166615857664 -1662122166657858560 -1662122166702859520 -1662122166744860416 -1662122166786861312 -1662122166831862272 -1662122166876863232 -1662122166912864000 -1662122166951864832 -1662122166993865728 -1662122167035866624 -1662122167077867520 -1662122167116868352 -1662122167161869312 -1662122167206870272 -1662122167248871168 -1662122167296872192 -1662122167344873216 -1662122167386874112 -1662122167428875008 -1662122167470875904 -1662122167515876864 -1662122167560877824 -1662122167599878656 -1662122167638879488 -1662122167680880384 -1662122167722881280 -1662122167767882240 -1662122167815883264 -1662122167857884160 -1662122167899885056 -1662122167944886016 -1662122167989886976 -1662122168034887936 -1662122168079888896 -1662122168121889792 -1662122168163890688 -1662122168211891712 -1662122168253892608 -1662122168298893568 -1662122168331894272 -1662122168373895168 -1662122168415896064 -1662122168460897024 -1662122168502897920 -1662122168544898816 -1662122168586899712 -1662122168631900672 -1662122168670901504 -1662122168721902592 -1662122168763903488 -1662122168808904448 -1662122168850905344 -1662122168892906240 -1662122168931907072 -1662122168970907904 -1662122169012908800 -1662122169057909760 -1662122169096910592 -1662122169138911488 -1662122169180912384 -1662122169219913216 -1662122169264914176 -1662122169306915072 -1662122169354916096 -1662122169393916928 -1662122169438917888 -1662122169483918848 -1662122169522919680 -1662122169567920640 -1662122169609921536 -1662122169657922560 -1662122169702923520 -1662122169744924416 -1662122169786925312 -1662122169828926208 -1662122169870927104 -1662122169912928000 -1662122169957928960 -1662122169999929856 -1662122170041930752 -1662122170089931776 -1662122170128932608 -1662122170170933504 -1662122170209934336 -1662122170254935296 -1662122170296936192 -1662122170341937152 -1662122170389938176 -1662122170434939136 -1662122170476940032 -1662122170521940992 -1662122170563941888 -1662122170611942912 -1662122170659943936 -1662122170707944960 -1662122170749945856 -1662122170794946816 -1662122170839947776 -1662122170881948672 -1662122170920949504 -1662122170965950464 -1662122171016951552 -1662122171061952512 -1662122171106953472 -1662122171148954368 -1662122171193955328 -1662122171235956224 -1662122171280957184 -1662122171322958080 -1662122171364958976 -1662122171406959872 -1662122171451960832 -1662122171493961728 -1662122171541962752 -1662122171583963648 -1662122171625964544 -1662122171667965440 -1662122171715966464 -1662122171763967488 -1662122171805968384 -1662122171847969280 -1662122171892970240 -1662122171940971264 -1662122171982972160 -1662122172024973056 -1662122172066973952 -1662122172111974912 -1662122172153975808 -1662122172195976704 -1662122172237977600 -1662122172279978496 -1662122172318979328 -1662122172357980160 -1662122172402981120 -1662122172444982016 -1662122172489982976 -1662122172531983872 -1662122172576984832 -1662122172618985728 -1662122172663986688 -1662122172705987584 -1662122172750988544 -1662122172795989504 -1662122172837990400 -1662122172882991360 -1662122172924992256 -1662122172966993152 -1662122173011994112 -1662122173053995008 -1662122173095995904 -1662122173134996736 -1662122173185997824 -1662122173227998720 -1662122173275999744 -1662122173318000640 -1662122173363001600 -1662122173405002496 -1662122173447003392 -1662122173492004352 -1662122173537005312 -1662122173582006272 -1662122173627007232 -1662122173672008192 -1662122173717009152 -1662122173759010048 -1662122173804011008 -1662122173849011968 -1662122173894012928 -1662122173939013888 -1662122173981014784 -1662122174023015680 -1662122174065016576 -1662122174107017472 -1662122174149018368 -1662122174194019328 -1662122174236020224 -1662122174284021248 -1662122174329022208 -1662122174371023104 -1662122174416024064 -1662122174461025024 -1662122174503025920 -1662122174545026816 -1662122174593027840 -1662122174638028800 -1662122174680029696 -1662122174722030592 -1662122174764031488 -1662122174800032256 -1662122174845033216 -1662122174887034112 -1662122174926034944 -1662122174968035840 -1662122175007036672 -1662122175049037568 -1662122175091038464 -1662122175136039424 -1662122175175040256 -1662122175220041216 -1662122175262042112 -1662122175307043072 -1662122175352044032 -1662122175394044928 -1662122175442045952 -1662122175484046848 -1662122175535047936 -1662122175577048832 -1662122175625049856 -1662122175667050752 -1662122175712051712 -1662122175754052608 -1662122175799053568 -1662122175841054464 -1662122175883055360 -1662122175925056256 -1662122175973057280 -1662122176015058176 -1662122176057059072 -1662122176102060032 -1662122176144060928 -1662122176189061888 -1662122176231062784 -1662122176273063680 -1662122176312064512 -1662122176354065408 -1662122176396066304 -1662122176432067072 -1662122176474067968 -1662122176516068864 -1662122176558069760 -1662122176600070656 -1662122176636071424 -1662122176681072384 -1662122176726073344 -1662122176768074240 -1662122176816075264 -1662122176858076160 -1662122176900077056 -1662122176948078080 -1662122176990078976 -1662122177032079872 -1662122177077080832 -1662122177119081728 -1662122177161082624 -1662122177203083520 -1662122177245084416 -1662122177287085312 -1662122177332086272 -1662122177374087168 -1662122177416088064 -1662122177461089024 -1662122177506089984 -1662122177554091008 -1662122177596091904 -1662122177635092736 -1662122177680093696 -1662122177725094656 -1662122177770095616 -1662122177815096576 -1662122177860097536 -1662122177905098496 -1662122177947099392 -1662122177986100224 -1662122178028101120 -1662122178070102016 -1662122178112102912 -1662122178154103808 -1662122178202104832 -1662122178241105664 -1662122178280106496 -1662122178325107456 -1662122178370108416 -1662122178415109376 -1662122178454110208 -1662122178502111232 -1662122178547112192 -1662122178589113088 -1662122178634114048 -1662122178679115008 -1662122178724115968 -1662122178766116864 -1662122178814117888 -1662122178859118848 -1662122178910119936 -1662122178955120896 -1662122179003121920 -1662122179051122944 -1662122179096123904 -1662122179138124800 -1662122179180125696 -1662122179228126720 -1662122179267127552 -1662122179312128512 -1662122179363129600 -1662122179405130496 -1662122179450131456 -1662122179498132480 -1662122179540133376 -1662122179579134208 -1662122179624135168 -1662122179666136064 -1662122179711137024 -1662122179753137920 -1662122179798138880 -1662122179840139776 -1662122179885140736 -1662122179930141696 -1662122179972142592 -1662122180014143488 -1662122180056144384 -1662122180098145280 -1662122180137146112 -1662122180176146944 -1662122180227148032 -1662122180269148928 -1662122180314149888 -1662122180356150784 -1662122180395151616 -1662122180437152512 -1662122180479153408 -1662122180521154304 -1662122180566155264 -1662122180608156160 -1662122180653157120 -1662122180695158016 -1662122180734158848 -1662122180776159744 -1662122180821160704 -1662122180863161600 -1662122180908162560 -1662122180956163584 -1662122181001164544 -1662122181049165568 -1662122181091166464 -1662122181133167360 -1662122181172168192 -1662122181217169152 -1662122181262170112 -1662122181310171136 -1662122181355172096 -1662122181400173056 -1662122181442173952 -1662122181484174848 -1662122181526175744 -1662122181571176704 -1662122181613177600 -1662122181652178432 -1662122181694179328 -1662122181736180224 -1662122181772180992 -1662122181817181952 -1662122181862182912 -1662122181907183872 -1662122181949184768 -1662122181994185728 -1662122182042186752 -1662122182081187584 -1662122182117188352 -1662122182159189248 -1662122182198190080 -1662122182243191040 -1662122182285191936 -1662122182327192832 -1662122182369193728 -1662122182411194624 -1662122182456195584 -1662122182498196480 -1662122182540197376 -1662122182582198272 -1662122182624199168 -1662122182666200064 -1662122182708200960 -1662122182750201856 -1662122182795202816 -1662122182837203712 -1662122182882204672 -1662122182927205632 -1662122182969206528 -1662122183011207424 -1662122183059208448 -1662122183098209280 -1662122183137210112 -1662122183182211072 -1662122183224211968 -1662122183269212928 -1662122183308213760 -1662122183353214720 -1662122183395215616 -1662122183437216512 -1662122183476217344 -1662122183515218176 -1662122183557219072 -1662122183599219968 -1662122183641220864 -1662122183689221888 -1662122183731222784 -1662122183776223744 -1662122183821224704 -1662122183863225600 -1662122183908226560 -1662122183947227392 -1662122183989228288 -1662122184034229248 -1662122184076230144 -1662122184121231104 -1662122184163232000 -1662122184202232832 -1662122184247233792 -1662122184292234752 -1662122184334235648 -1662122184376236544 -1662122184421237504 -1662122184463238400 -1662122184508239360 -1662122184553240320 -1662122184595241216 -1662122184637242112 -1662122184679243008 -1662122184721243904 -1662122184763244800 -1662122184808245760 -1662122184850246656 -1662122184892247552 -1662122184934248448 -1662122184976249344 -1662122185015250176 -1662122185057251072 -1662122185099251968 -1662122185144252928 -1662122185192253952 -1662122185234254848 -1662122185276255744 -1662122185321256704 -1662122185366257664 -1662122185411258624 -1662122185450259456 -1662122185492260352 -1662122185531261184 -1662122185579262208 -1662122185627263232 -1662122185672264192 -1662122185717265152 -1662122185759266048 -1662122185807267072 -1662122185849267968 -1662122185888268800 -1662122185930269696 -1662122185966270464 -1662122186011271424 -1662122186053272320 -1662122186095273216 -1662122186137274112 -1662122186173274880 -1662122186218275840 -1662122186260276736 -1662122186299277568 -1662122186341278464 -1662122186383279360 -1662122186428280320 -1662122186473281280 -1662122186515282176 -1662122186563283200 -1662122186614284288 -1662122186656285184 -1662122186701286144 -1662122186746287104 -1662122186788288000 -1662122186833288960 -1662122186878289920 -1662122186917290752 -1662122186962291712 -1662122187004292608 -1662122187049293568 -1662122187088294400 -1662122187130295296 -1662122187175296256 -1662122187220297216 -1662122187262298112 -1662122187301298944 -1662122187343299840 -1662122187382300672 -1662122187424301568 -1662122187463302400 -1662122187505303296 -1662122187544304128 -1662122187586305024 -1662122187631305984 -1662122187673306880 -1662122187715307776 -1662122187757308672 -1662122187802309632 -1662122187844310528 -1662122187889311488 -1662122187934312448 -1662122187979313408 -1662122188024314368 -1662122188063315200 -1662122188111316224 -1662122188153317120 -1662122188201318144 -1662122188243319040 -1662122188294320128 -1662122188336321024 -1662122188378321920 -1662122188423322880 -1662122188465323776 -1662122188504324608 -1662122188549325568 -1662122188591326464 -1662122188636327424 -1662122188681328384 -1662122188723329280 -1662122188768330240 -1662122188813331200 -1662122188858332160 -1662122188906333184 -1662122188951334144 -1662122188996335104 -1662122189041336064 -1662122189086337024 -1662122189128337920 -1662122189173338880 -1662122189221339904 -1662122189263340800 -1662122189305341696 -1662122189350342656 -1662122189395343616 -1662122189431344384 -1662122189476345344 -1662122189518346240 -1662122189560347136 -1662122189605348096 -1662122189647348992 -1662122189692349952 -1662122189737350912 -1662122189782351872 -1662122189827352832 -1662122189872353792 -1662122189917354752 -1662122189962355712 -1662122190007356672 -1662122190052357632 -1662122190097358592 -1662122190139359488 -1662122190181360384 -1662122190220361216 -1662122190265362176 -1662122190307363072 -1662122190352364032 -1662122190397364992 -1662122190436365824 -1662122190475366656 -1662122190520367616 -1662122190565368576 -1662122190613369600 -1662122190661370624 -1662122190700371456 -1662122190742372352 -1662122190787373312 -1662122190829374208 -1662122190874375168 -1662122190916376064 -1662122190964377088 -1662122191006377984 -1662122191048378880 -1662122191099379968 -1662122191141380864 -1662122191186381824 -1662122191228382720 -1662122191276383744 -1662122191318384640 -1662122191360385536 -1662122191405386496 -1662122191444387328 -1662122191489388288 -1662122191531389184 -1662122191570390016 -1662122191609390848 -1662122191651391744 -1662122191690392576 -1662122191732393472 -1662122191774394368 -1662122191813395200 -1662122191855396096 -1662122191897396992 -1662122191936397824 -1662122191978398720 -1662122192020399616 -1662122192062400512 -1662122192101401344 -1662122192143402240 -1662122192185403136 -1662122192227404032 -1662122192269404928 -1662122192311405824 -1662122192350406656 -1662122192395407616 -1662122192437408512 -1662122192476409344 -1662122192518410240 -1662122192563411200 -1662122192608412160 -1662122192650413056 -1662122192695414016 -1662122192740414976 -1662122192782415872 -1662122192824416768 -1662122192869417728 -1662122192914418688 -1662122192956419584 -1662122193001420544 -1662122193040421376 -1662122193082422272 -1662122193127423232 -1662122193166424064 -1662122193208424960 -1662122193247425792 -1662122193289426688 -1662122193331427584 -1662122193370428416 -1662122193415429376 -1662122193454430208 -1662122193499431168 -1662122193541432064 -1662122193589433088 -1662122193631433984 -1662122193676434944 -1662122193721435904 -1662122193763436800 -1662122193808437760 -1662122193850438656 -1662122193889439488 -1662122193934440448 -1662122193976441344 -1662122194018442240 -1662122194057443072 -1662122194093443840 -1662122194135444736 -1662122194186445824 -1662122194231446784 -1662122194270447616 -1662122194309448448 -1662122194348449280 -1662122194390450176 -1662122194432451072 -1662122194471451904 -1662122194513452800 -1662122194558453760 -1662122194603454720 -1662122194645455616 -1662122194690456576 -1662122194729457408 -1662122194777458432 -1662122194819459328 -1662122194864460288 -1662122194906461184 -1662122194954462208 -1662122194999463168 -1662122195044464128 -1662122195089465088 -1662122195131465984 -1662122195179467008 -1662122195224467968 -1662122195266468864 -1662122195308469760 -1662122195353470720 -1662122195395471616 -1662122195443472640 -1662122195488473600 -1662122195533474560 -1662122195572475392 -1662122195614476288 -1662122195656477184 -1662122195698478080 -1662122195740478976 -1662122195782479872 -1662122195821480704 -1662122195866481664 -1662122195908482560 -1662122195953483520 -1662122195992484352 -1662122196037485312 -1662122196082486272 -1662122196127487232 -1662122196169488128 -1662122196211489024 -1662122196253489920 -1662122196292490752 -1662122196334491648 -1662122196373492480 -1662122196415493376 -1662122196454494208 -1662122196496495104 -1662122196538496000 -1662122196580496896 -1662122196622497792 -1662122196667498752 -1662122196709499648 -1662122196748500480 -1662122196793501440 -1662122196838502400 -1662122196880503296 -1662122196922504192 -1662122196967505152 -1662122197015506176 -1662122197057507072 -1662122197099507968 -1662122197138508800 -1662122197180509696 -1662122197222510592 -1662122197264511488 -1662122197309512448 -1662122197351513344 -1662122197393514240 -1662122197441515264 -1662122197483516160 -1662122197528517120 -1662122197570518016 -1662122197621519104 -1662122197663520000 -1662122197705520896 -1662122197747521792 -1662122197789522688 -1662122197834523648 -1662122197879524608 -1662122197921525504 -1662122197963526400 -1662122198005527296 -1662122198044528128 -1662122198086529024 -1662122198131529984 -1662122198176530944 -1662122198218531840 -1662122198263532800 -1662122198302533632 -1662122198347534592 -1662122198395535616 -1662122198434536448 -1662122198482537472 -1662122198521538304 -1662122198563539200 -1662122198605540096 -1662122198644540928 -1662122198680541696 -1662122198722542592 -1662122198767543552 -1662122198806544384 -1662122198851545344 -1662122198890546176 -1662122198938547200 -1662122198986548224 -1662122199025549056 -1662122199064549888 -1662122199103550720 -1662122199145551616 -1662122199193552640 -1662122199241553664 -1662122199283554560 -1662122199331555584 -1662122199376556544 -1662122199415557376 -1662122199463558400 -1662122199508559360 -1662122199553560320 -1662122199601561344 -1662122199640562176 -1662122199682563072 -1662122199727564032 -1662122199769564928 -1662122199814565888 -1662122199862566912 -1662122199904567808 -1662122199943568640 -1662122199994569728 -1662122200033570560 -1662122200078571520 -1662122200120572416 -1662122200159573248 -1662122200204574208 -1662122200240574976 -1662122200285575936 -1662122200330576896 -1662122200369577728 -1662122200420578816 -1662122200459579648 -1662122200498580480 -1662122200540581376 -1662122200582582272 -1662122200621583104 -1662122200666584064 -1662122200708584960 -1662122200753585920 -1662122200795586816 -1662122200834587648 -1662122200876588544 -1662122200918589440 From 8c00eeeaff68feccba1a26d7bf02391cedc47077 Mon Sep 17 00:00:00 2001 From: olayasturias Date: Tue, 28 Nov 2023 11:33:24 +0100 Subject: [PATCH 15/17] added subpipe and scripts for auto run --- CMakeLists.txt | 45 +++--- Examples/Monocular/mono_subpipe.cc | 168 +++++++++++++++++++ Examples/{REAMDME.md => README.md} | 0 Examples/aqualoc_mono.sh | 27 ++-- Examples/euroc_eval_examples.sh | 44 +++++ Examples/euroc_examples.sh | 190 ++++++++++++++++++++++ Examples/euroc_mono.sh | 54 +++++++ Examples/kitti_mono.sh | 69 ++++++++ Examples/mimir_mono.sh | 21 +++ Examples/tum_mono.sh | 43 +++++ Examples/tum_vi_eval_examples.sh | 19 +++ Examples/tum_vi_examples.sh | 249 +++++++++++++++++++++++++++++ README.md | 10 +- 13 files changed, 907 insertions(+), 32 deletions(-) create mode 100644 Examples/Monocular/mono_subpipe.cc rename Examples/{REAMDME.md => README.md} (100%) create mode 100755 Examples/euroc_eval_examples.sh create mode 100755 Examples/euroc_examples.sh create mode 100644 Examples/euroc_mono.sh create mode 100755 Examples/kitti_mono.sh create mode 100644 Examples/mimir_mono.sh create mode 100644 Examples/tum_mono.sh create mode 100755 Examples/tum_vi_eval_examples.sh create mode 100755 Examples/tum_vi_examples.sh diff --git a/CMakeLists.txt b/CMakeLists.txt index 1b85de7d19..e6aec15992 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -12,25 +12,30 @@ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3") set(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -march=native") set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -march=native") -# Check C++11 or C++0x support +# Check C++14 or C++0x support include(CheckCXXCompilerFlag) -CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) +CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX11) CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X) if(COMPILER_SUPPORTS_CXX11) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14") add_definitions(-DCOMPILEDWITHC11) - message(STATUS "Using flag -std=c++11.") + message(STATUS "Using flag -std=c++14.") elseif(COMPILER_SUPPORTS_CXX0X) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") add_definitions(-DCOMPILEDWITHC0X) message(STATUS "Using flag -std=c++0x.") +elseif(COMPILER_SUPPORTS_CXX14) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14") + add_definitions(-DCOMPILEDWITHC11) #code seems to have macros which need this + add_definitions(-DCOMPILEDWITHC14) + message(STATUS "Using flag -std=c++14.") else() - message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.") + message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++14 support. Please use a different C++ compiler.") endif() LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules) -find_package(OpenCV 3.2) +find_package(OpenCV) if(NOT OpenCV_FOUND) message(FATAL_ERROR "OpenCV > 4.4 not found.") endif() @@ -172,10 +177,6 @@ add_executable(stereo_euroc Examples/Stereo/stereo_euroc.cc) target_link_libraries(stereo_euroc ${PROJECT_NAME}) -add_executable(stereo_mimir - Examples/Stereo/stereo_mimir.cc) -target_link_libraries(stereo_mimir ${PROJECT_NAME}) - add_executable(stereo_tum_vi Examples/Stereo/stereo_tum_vi.cc) target_link_libraries(stereo_tum_vi ${PROJECT_NAME}) @@ -205,17 +206,21 @@ add_executable(mono_euroc Examples/Monocular/mono_euroc.cc) target_link_libraries(mono_euroc ${PROJECT_NAME}) -add_executable(mono_mimir - Examples/Monocular/mono_mimir.cc) -target_link_libraries(mono_mimir ${PROJECT_NAME}) +add_executable(mono_tum_vi + Examples/Monocular/mono_tum_vi.cc) +target_link_libraries(mono_tum_vi ${PROJECT_NAME}) add_executable(mono_aqualoc Examples/Monocular/mono_aqualoc.cc) target_link_libraries(mono_aqualoc ${PROJECT_NAME}) -add_executable(mono_tum_vi - Examples/Monocular/mono_tum_vi.cc) -target_link_libraries(mono_tum_vi ${PROJECT_NAME}) +add_executable(mono_mimir + Examples/Monocular/mono_mimir.cc) +target_link_libraries(mono_mimir ${PROJECT_NAME}) + +add_executable(mono_subpipe + Examples/Monocular/mono_subpipe.cc) +target_link_libraries(mono_subpipe ${PROJECT_NAME}) if(realsense2_FOUND) add_executable(mono_realsense_t265 @@ -234,10 +239,6 @@ add_executable(mono_inertial_euroc Examples/Monocular-Inertial/mono_inertial_euroc.cc) target_link_libraries(mono_inertial_euroc ${PROJECT_NAME}) -add_executable(mono_inertial_mimir - Examples/Monocular-Inertial/mono_inertial_mimir.cc) -target_link_libraries(mono_inertial_mimir ${PROJECT_NAME}) - add_executable(mono_inertial_tum_vi Examples/Monocular-Inertial/mono_inertial_tum_vi.cc) target_link_libraries(mono_inertial_tum_vi ${PROJECT_NAME}) @@ -259,6 +260,10 @@ add_executable(stereo_inertial_euroc Examples/Stereo-Inertial/stereo_inertial_euroc.cc) target_link_libraries(stereo_inertial_euroc ${PROJECT_NAME}) +add_executable(stereo_mimir + Examples/Stereo/stereo_mimir.cc) +target_link_libraries(stereo_mimir ${PROJECT_NAME}) + add_executable(stereo_inertial_tum_vi Examples/Stereo-Inertial/stereo_inertial_tum_vi.cc) target_link_libraries(stereo_inertial_tum_vi ${PROJECT_NAME}) diff --git a/Examples/Monocular/mono_subpipe.cc b/Examples/Monocular/mono_subpipe.cc new file mode 100644 index 0000000000..4f5ed094a6 --- /dev/null +++ b/Examples/Monocular/mono_subpipe.cc @@ -0,0 +1,168 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + + +#include +#include +#include +#include + +#include + +#include + +#include +#include + +using namespace std; + +void LoadImages(const string &strFile, vector &vstrImageFilenames, + vector &vTimestamps); + +int main(int argc, char **argv) +{ + if(argc != 4) + { + cerr << endl << "Usage: ./mono_subpipe path_to_vocabulary path_to_settings path_to_sequence" << endl; + return 1; + } + + // Retrieve paths to images + vector vstrImageFilenames; + vector vTimestamps; + string strFile = string(argv[3])+"/EstimatedState.csv"; + LoadImages(strFile, vstrImageFilenames, vTimestamps); + + + int nImages = vstrImageFilenames.size(); + cout << nImages << endl; + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR,true); + + // Vector for tracking time statistics + vector vTimesTrack; + vTimesTrack.resize(nImages); + + // Main loop + cv::Mat im; + for(int ni=0; ni >(t2 - t1).count(); + + vTimesTrack[ni]=ttrack; + + // Wait to load the next frame + double T=0; + if(ni0) + T = tframe-vTimestamps[ni-1]; + + if(ttrack &vstrImageFilenames, std::vector &vTimestamps) +{ + std::ifstream f; + f.open(strFile.c_str()); + + // Skip the first line containing column names + std::string columnNames; + getline(f, columnNames); + + while (!f.eof()) + { + std::string s1, s2; // Variables for the first and second columns + getline(f, s1, ','); // Read the first column + getline(f, s2, ','); // Read the second column + + if (!s1.empty() && !s2.empty()) + { + std::stringstream ss1(s1); + std::stringstream ss2(s2); + + double t; + std::string sRGB; + + ss1 >> sRGB; + ss2 >> t; + + // Extracting just the filename from the path using dirent.h + size_t lastSlashPos = sRGB.find_last_of('/'); + std::string fileName = (lastSlashPos != std::string::npos) ? sRGB.substr(lastSlashPos + 1) : sRGB; + + vTimestamps.push_back(t); + vstrImageFilenames.push_back(fileName); + } + + // Move to the next line + f.ignore(std::numeric_limits::max(), '\n'); + } +} diff --git a/Examples/REAMDME.md b/Examples/README.md similarity index 100% rename from Examples/REAMDME.md rename to Examples/README.md diff --git a/Examples/aqualoc_mono.sh b/Examples/aqualoc_mono.sh index 8aefb8ebc1..bb0f1a1b6e 100755 --- a/Examples/aqualoc_mono.sh +++ b/Examples/aqualoc_mono.sh @@ -1,12 +1,21 @@ #!/bin/bash -pathDatasetaqualoc='/home/olaya/Datasets/Aqualoc/Archaeological_site_sequences' #Example, it is necesary to change it by the dataset path -tracks='1 2 3 4 5 6' -for track in $tracks -do -echo "Launching $track with Monocular sensor" -./Monocular/mono_aqualoc ../Vocabulary/ORBvoc.txt Monocular/Aqualoc.yaml "$pathDatasetaqualoc"/archaeo_sequence_$track\_raw_data $track -mv KeyFrameTrajectory.txt kf_archaeo_sequence_$track\_raw_data.txt -done +# Check if both arguments are provided +if [ "$#" -ne 2 ]; then + echo "Usage: $0 " + echo "example: $0 $HOME/Datasets/Aqualoc/Archaeological_site_sequences '1 2 3 4 5 6'" + exit 1 +fi + +pathDatasetaqualoc="$1" +tracks="$2" -# ./Monocular/mono_aqualoc ../Vocabulary/ORBvoc.txt Monocular/Aqualoc.yaml /home/olaya/Datasets/Aqualoc/Archaeological_site_sequences/archaeo_sequence_1_raw_data 1 \ No newline at end of file +echo "Dataset Path: $pathDatasetaqualoc" +echo "Tracks: $tracks" + +for track in $tracks +do + echo "Launching $track with Monocular sensor" + ./Monocular/mono_aqualoc ../Vocabulary/ORBvoc.txt Monocular/Aqualoc.yaml "$pathDatasetaqualoc/archaeo_sequence_$track\_raw_data" $track + mv KeyFrameTrajectory.txt "kf_archaeo_sequence_$track\_raw_data.txt" +done \ No newline at end of file diff --git a/Examples/euroc_eval_examples.sh b/Examples/euroc_eval_examples.sh new file mode 100755 index 0000000000..f544cf0062 --- /dev/null +++ b/Examples/euroc_eval_examples.sh @@ -0,0 +1,44 @@ +#!/bin/bash + +# Check if all three arguments are provided +if [ "$#" -ne 1 ]; then + echo "Usage: $0 " + echo "example: $0 $HOME/Datasets/EuRoC" + exit 1 +fi + +pathDatasetEuroc="$1" + +# Single Session Example (Pure visual) +echo "Launching MH01 with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Stereo/EuRoC_TimeStamps/MH01.txt dataset-MH01_stereo +echo "------------------------------------" +echo "Evaluation of MH01 trajectory with Stereo sensor" +python ../evaluation/evaluate_ate_scale.py ../evaluation/Ground_truth/EuRoC_left_cam/MH01_GT.txt f_dataset-MH01_stereo.txt --plot MH01_stereo.pdf + + + +# MultiSession Example (Pure visual) +echo "Launching Machine Hall with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Stereo/EuRoC_TimeStamps/MH01.txt "$pathDatasetEuroc"/MH02 ./Stereo/EuRoC_TimeStamps/MH02.txt "$pathDatasetEuroc"/MH03 ./Stereo/EuRoC_TimeStamps/MH03.txt "$pathDatasetEuroc"/MH04 ./Stereo/EuRoC_TimeStamps/MH04.txt "$pathDatasetEuroc"/MH05 ./Stereo/EuRoC_TimeStamps/MH05.txt dataset-MH01_to_MH05_stereo +echo "------------------------------------" +echo "Evaluation of MAchine Hall trajectory with Stereo sensor" +python ../evaluation/evaluate_ate_scale.py ../evaluation/Ground_truth/EuRoC_left_cam/MH_GT.txt f_dataset-MH01_to_MH05_stereo.txt --plot MH01_to_MH05_stereo.pdf + + +# Single Session Example (Visual-Inertial) +echo "Launching V102 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V102 ./Monocular-Inertial/EuRoC_TimeStamps/V102.txt dataset-V102_monoi +echo "------------------------------------" +echo "Evaluation of V102 trajectory with Monocular-Inertial sensor" +python ../evaluation/evaluate_ate_scale.py "$pathDatasetEuroc"/V102/mav0/state_groundtruth_estimate0/data.csv f_dataset-V102_monoi.txt --plot V102_monoi.pdf + + +# MultiSession Monocular Examples + +echo "Launching Vicon Room 2 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Monocular-Inertial/EuRoC_TimeStamps/V201.txt "$pathDatasetEuroc"/V202 ./Monocular-Inertial/EuRoC_TimeStamps/V202.txt "$pathDatasetEuroc"/V203 ./Monocular-Inertial/EuRoC_TimeStamps/V203.txt dataset-V201_to_V203_monoi +echo "------------------------------------" +echo "Evaluation of Vicon Room 2 trajectory with Stereo sensor" +python ../evaluation/evaluate_ate_scale.py ../evaluation/Ground_truth/EuRoC_imu/V2_GT.txt f_dataset-V201_to_V203_monoi.txt --plot V201_to_V203_monoi.pdf + diff --git a/Examples/euroc_examples.sh b/Examples/euroc_examples.sh new file mode 100755 index 0000000000..480e2bb7d1 --- /dev/null +++ b/Examples/euroc_examples.sh @@ -0,0 +1,190 @@ +#!/bin/bash + +# Check if all three arguments are provided +if [ "$#" -ne 1 ]; then + echo "Usage: $0 " + echo "example: $0 $HOME/Datasets/EuRoC" + exit 1 +fi + +pathDatasetEuroc="$1" + +#------------------------------------ +# Monocular Examples +echo "Launching MH01 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Monocular/EuRoC_TimeStamps/MH01.txt dataset-MH01_mono + +echo "Launching MH02 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH02 ./Monocular/EuRoC_TimeStamps/MH02.txt dataset-MH02_mono + +echo "Launching MH03 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH03 ./Monocular/EuRoC_TimeStamps/MH03.txt dataset-MH03_mono + +echo "Launching MH04 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH04 ./Monocular/EuRoC_TimeStamps/MH04.txt dataset-MH04_mono + +echo "Launching MH05 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH05 ./Monocular/EuRoC_TimeStamps/MH05.txt dataset-MH05_mono + +echo "Launching V101 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Monocular/EuRoC_TimeStamps/V101.txt dataset-V101_mono + +echo "Launching V102 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V102 ./Monocular/EuRoC_TimeStamps/V102.txt dataset-V102_mono + +echo "Launching V103 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V103 ./Monocular/EuRoC_TimeStamps/V103.txt dataset-V103_mono + +echo "Launching V201 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Monocular/EuRoC_TimeStamps/V201.txt dataset-V201_mono + +echo "Launching V202 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V202 ./Monocular/EuRoC_TimeStamps/V202.txt dataset-V202_mono + +echo "Launching V203 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V203 ./Monocular/EuRoC_TimeStamps/V203.txt dataset-V203_mono + +# MultiSession Monocular Examples +echo "Launching Machine Hall with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Monocular/EuRoC_TimeStamps/MH01.txt "$pathDatasetEuroc"/MH02 ./Monocular/EuRoC_TimeStamps/MH02.txt "$pathDatasetEuroc"/MH03 ./Monocular/EuRoC_TimeStamps/MH03.txt "$pathDatasetEuroc"/MH04 ./Monocular/EuRoC_TimeStamps/MH04.txt "$pathDatasetEuroc"/MH05 ./Monocular/EuRoC_TimeStamps/MH05.txt dataset-MH01_to_MH05_mono + +echo "Launching Vicon Room 1 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Monocular/EuRoC_TimeStamps/V101.txt "$pathDatasetEuroc"/V102 ./Monocular/EuRoC_TimeStamps/V102.txt "$pathDatasetEuroc"/V103 ./Monocular/EuRoC_TimeStamps/V103.txt dataset-V101_to_V103_mono + +echo "Launching Vicon Room 2 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Monocular/EuRoC_TimeStamps/V201.txt "$pathDatasetEuroc"/V202 ./Monocular/EuRoC_TimeStamps/V202.txt "$pathDatasetEuroc"/V203 ./Monocular/EuRoC_TimeStamps/V203.txt dataset-V201_to_V203_mono + +#------------------------------------ +# Stereo Examples +echo "Launching MH01 with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Stereo/EuRoC_TimeStamps/MH01.txt dataset-MH01_stereo + +echo "Launching MH02 with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH02 ./Stereo/EuRoC_TimeStamps/MH02.txt dataset-MH02_stereo + +echo "Launching MH03 with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH03 ./Stereo/EuRoC_TimeStamps/MH03.txt dataset-MH03_stereo + +echo "Launching MH04 with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH04 ./Stereo/EuRoC_TimeStamps/MH04.txt dataset-MH04_stereo + +echo "Launching MH05 with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH05 ./Stereo/EuRoC_TimeStamps/MH05.txt dataset-MH05_stereo + +echo "Launching V101 with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Stereo/EuRoC_TimeStamps/V101.txt dataset-V101_stereo + +echo "Launching V102 with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/V102 ./Stereo/EuRoC_TimeStamps/V102.txt dataset-V102_stereo + +echo "Launching V103 with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/V103 ./Stereo/EuRoC_TimeStamps/V103.txt dataset-V103_stereo + +echo "Launching V201 with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Stereo/EuRoC_TimeStamps/V201.txt dataset-V201_stereo + +echo "Launching V202 with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/V202 ./Stereo/EuRoC_TimeStamps/V202.txt dataset-V202_stereo + +echo "Launching V203 with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/V203 ./Stereo/EuRoC_TimeStamps/V203.txt dataset-V203_stereo + +# MultiSession Stereo Examples +echo "Launching Machine Hall with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Stereo/EuRoC_TimeStamps/MH01.txt "$pathDatasetEuroc"/MH02 ./Stereo/EuRoC_TimeStamps/MH02.txt "$pathDatasetEuroc"/MH03 ./Stereo/EuRoC_TimeStamps/MH03.txt "$pathDatasetEuroc"/MH04 ./Stereo/EuRoC_TimeStamps/MH04.txt "$pathDatasetEuroc"/MH05 ./Stereo/EuRoC_TimeStamps/MH05.txt dataset-MH01_to_MH05_stereo + +echo "Launching Vicon Room 1 with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Stereo/EuRoC_TimeStamps/V101.txt "$pathDatasetEuroc"/V102 ./Stereo/EuRoC_TimeStamps/V102.txt "$pathDatasetEuroc"/V103 ./Stereo/EuRoC_TimeStamps/V103.txt dataset-V101_to_V103_stereo + +echo "Launching Vicon Room 2 with Stereo sensor" +./Stereo/stereo_euroc ../Vocabulary/ORBvoc.txt ./Stereo/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Stereo/EuRoC_TimeStamps/V201.txt "$pathDatasetEuroc"/V202 ./Stereo/EuRoC_TimeStamps/V202.txt "$pathDatasetEuroc"/V203 ./Stereo/EuRoC_TimeStamps/V203.txt dataset-V201_to_V203_stereo + +#------------------------------------ +# Monocular-Inertial Examples +echo "Launching MH01 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Monocular-Inertial/EuRoC_TimeStamps/MH01.txt dataset-MH01_monoi + +echo "Launching MH02 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH02 ./Monocular-Inertial/EuRoC_TimeStamps/MH02.txt dataset-MH02_monoi + +echo "Launching MH03 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH03 ./Monocular-Inertial/EuRoC_TimeStamps/MH03.txt dataset-MH03_monoi + +echo "Launching MH04 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH04 ./Monocular-Inertial/EuRoC_TimeStamps/MH04.txt dataset-MH04_monoi + +echo "Launching MH05 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH05 ./Monocular-Inertial/EuRoC_TimeStamps/MH05.txt dataset-MH05_monoi + +echo "Launching V101 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Monocular-Inertial/EuRoC_TimeStamps/V101.txt dataset-V101_monoi + +echo "Launching V102 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V102 ./Monocular-Inertial/EuRoC_TimeStamps/V102.txt dataset-V102_monoi + +echo "Launching V103 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V103 ./Monocular-Inertial/EuRoC_TimeStamps/V103.txt dataset-V103_monoi + +echo "Launching V201 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Monocular-Inertial/EuRoC_TimeStamps/V201.txt dataset-V201_monoi + +echo "Launching V202 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V202 ./Monocular-Inertial/EuRoC_TimeStamps/V202.txt dataset-V202_monoi + +echo "Launching V203 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V203 ./Monocular-Inertial/EuRoC_TimeStamps/V203.txt dataset-V203_monoi + +# MultiSession Monocular Examples +echo "Launching Machine Hall with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Monocular-Inertial/EuRoC_TimeStamps/MH01.txt "$pathDatasetEuroc"/MH02 ./Monocular-Inertial/EuRoC_TimeStamps/MH02.txt "$pathDatasetEuroc"/MH03 ./Monocular-Inertial/EuRoC_TimeStamps/MH03.txt "$pathDatasetEuroc"/MH04 ./Monocular-Inertial/EuRoC_TimeStamps/MH04.txt "$pathDatasetEuroc"/MH05 ./Monocular-Inertial/EuRoC_TimeStamps/MH05.txt dataset-MH01_to_MH05_monoi + +echo "Launching Vicon Room 1 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Monocular-Inertial/EuRoC_TimeStamps/V101.txt "$pathDatasetEuroc"/V102 ./Monocular-Inertial/EuRoC_TimeStamps/V102.txt "$pathDatasetEuroc"/V103 ./Monocular-Inertial/EuRoC_TimeStamps/V103.txt dataset-V101_to_V103_monoi + +echo "Launching Vicon Room 2 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_euroc ../Vocabulary/ORBvoc.txt ./Monocular-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Monocular-Inertial/EuRoC_TimeStamps/V201.txt "$pathDatasetEuroc"/V202 ./Monocular-Inertial/EuRoC_TimeStamps/V202.txt "$pathDatasetEuroc"/V203 ./Monocular-Inertial/EuRoC_TimeStamps/V203.txt dataset-V201_to_V203_monoi + +#------------------------------------ +# Stereo-Inertial Examples +echo "Launching MH01 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_euroc ../Vocabulary/ORBvoc.txt ./Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Stereo-Inertial/EuRoC_TimeStamps/MH01.txt dataset-MH01_stereoi + +echo "Launching MH02 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_euroc ../Vocabulary/ORBvoc.txt ./Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH02 ./Stereo-Inertial/EuRoC_TimeStamps/MH02.txt dataset-MH02_stereoi + +echo "Launching MH03 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_euroc ../Vocabulary/ORBvoc.txt ./Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH03 ./Stereo-Inertial/EuRoC_TimeStamps/MH03.txt dataset-MH03_stereoi + +echo "Launching MH04 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_euroc ../Vocabulary/ORBvoc.txt ./Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH04 ./Stereo-Inertial/EuRoC_TimeStamps/MH04.txt dataset-MH04_stereoi + +echo "Launching MH05 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_euroc ../Vocabulary/ORBvoc.txt ./Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH05 ./Stereo-Inertial/EuRoC_TimeStamps/MH05.txt dataset-MH05_stereoi + +echo "Launching V101 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_euroc ../Vocabulary/ORBvoc.txt ./Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Stereo-Inertial/EuRoC_TimeStamps/V101.txt dataset-V101_stereoi + +echo "Launching V102 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_euroc ../Vocabulary/ORBvoc.txt ./Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V102 ./Stereo-Inertial/EuRoC_TimeStamps/V102.txt dataset-V102_stereoi + +echo "Launching V103 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_euroc ../Vocabulary/ORBvoc.txt ./Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V103 ./Stereo-Inertial/EuRoC_TimeStamps/V103.txt dataset-V103_stereoi + +echo "Launching V201 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_euroc ../Vocabulary/ORBvoc.txt ./Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Stereo-Inertial/EuRoC_TimeStamps/V201.txt dataset-V201_stereoi + +echo "Launching V202 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_euroc ../Vocabulary/ORBvoc.txt ./Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V202 ./Stereo-Inertial/EuRoC_TimeStamps/V202.txt dataset-V202_stereoi + +echo "Launching V203 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_euroc ../Vocabulary/ORBvoc.txt ./Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V203 ./Stereo-Inertial/EuRoC_TimeStamps/V203.txt dataset-V203_stereoi + +# MultiSession Stereo-Inertial Examples +echo "Launching Machine Hall with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_euroc ../Vocabulary/ORBvoc.txt ./Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Stereo-Inertial/EuRoC_TimeStamps/MH01.txt "$pathDatasetEuroc"/MH02 ./Stereo-Inertial/EuRoC_TimeStamps/MH02.txt "$pathDatasetEuroc"/MH03 ./Stereo-Inertial/EuRoC_TimeStamps/MH03.txt "$pathDatasetEuroc"/MH04 ./Stereo-Inertial/EuRoC_TimeStamps/MH04.txt "$pathDatasetEuroc"/MH05 ./Stereo-Inertial/EuRoC_TimeStamps/MH05.txt dataset-MH01_to_MH05_stereoi + +echo "Launching Vicon Room 1 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_euroc ../Vocabulary/ORBvoc.txt ./Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Stereo-Inertial/EuRoC_TimeStamps/V101.txt "$pathDatasetEuroc"/V102 ./Stereo-Inertial/EuRoC_TimeStamps/V102.txt "$pathDatasetEuroc"/V103 ./Stereo-Inertial/EuRoC_TimeStamps/V103.txt dataset-V101_to_V103_stereoi + +echo "Launching Vicon Room 2 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_euroc ../Vocabulary/ORBvoc.txt ./Stereo-Inertial/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Stereo-Inertial/EuRoC_TimeStamps/V201.txt "$pathDatasetEuroc"/V202 ./Stereo-Inertial/EuRoC_TimeStamps/V202.txt "$pathDatasetEuroc"/V203 ./Stereo-Inertial/EuRoC_TimeStamps/V203.txt dataset-V201_to_V203_stereoi diff --git a/Examples/euroc_mono.sh b/Examples/euroc_mono.sh new file mode 100644 index 0000000000..fd968a6fb4 --- /dev/null +++ b/Examples/euroc_mono.sh @@ -0,0 +1,54 @@ +#!/bin/bash + +# Check if all three arguments are provided +if [ "$#" -ne 1 ]; then + echo "Usage: $0 " + echo "example: $0 $HOME/Datasets/EuRoC" + exit 1 +fi + +pathDatasetEuroc="$1" +#------------------------------------ +# Monocular Examples +echo "Launching MH01 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH_01_easy ./Monocular/EuRoC_TimeStamps/MH01.txt dataset-MH01_mono + +echo "Launching MH02 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH_02_easy ./Monocular/EuRoC_TimeStamps/MH02.txt dataset-MH02_mono + +echo "Launching MH03 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH_03_medium ./Monocular/EuRoC_TimeStamps/MH03.txt dataset-MH03_mono + +echo "Launching MH04 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH_04_difficult ./Monocular/EuRoC_TimeStamps/MH04.txt dataset-MH04_mono + +echo "Launching MH05 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH_05_difficult ./Monocular/EuRoC_TimeStamps/MH05.txt dataset-MH05_mono + +echo "Launching V101 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V1_01_easy ./Monocular/EuRoC_TimeStamps/V101.txt dataset-V101_mono + +echo "Launching V102 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V1_02_medium ./Monocular/EuRoC_TimeStamps/V102.txt dataset-V102_mono + +echo "Launching V103 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V1_03_difficult ./Monocular/EuRoC_TimeStamps/V103.txt dataset-V103_mono + +echo "Launching V201 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V2_01_easy ./Monocular/EuRoC_TimeStamps/V201.txt dataset-V201_mono + +echo "Launching V202 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V2_02_medium ./Monocular/EuRoC_TimeStamps/V202.txt dataset-V202_mono + +echo "Launching V203 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V2_03_difficult ./Monocular/EuRoC_TimeStamps/V203.txt dataset-V203_mono + +# MultiSession Monocular Examples +echo "Launching Machine Hall with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Monocular/EuRoC_TimeStamps/MH01.txt "$pathDatasetEuroc"/MH02 ./Monocular/EuRoC_TimeStamps/MH02.txt "$pathDatasetEuroc"/MH03 ./Monocular/EuRoC_TimeStamps/MH03.txt "$pathDatasetEuroc"/MH04 ./Monocular/EuRoC_TimeStamps/MH04.txt "$pathDatasetEuroc"/MH05 ./Monocular/EuRoC_TimeStamps/MH05.txt dataset-MH01_to_MH05_mono + +echo "Launching Vicon Room 1 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V101 ./Monocular/EuRoC_TimeStamps/V101.txt "$pathDatasetEuroc"/V102 ./Monocular/EuRoC_TimeStamps/V102.txt "$pathDatasetEuroc"/V103 ./Monocular/EuRoC_TimeStamps/V103.txt dataset-V101_to_V103_mono + +echo "Launching Vicon Room 2 with Monocular sensor" +./Monocular/mono_euroc ../Vocabulary/ORBvoc.txt ./Monocular/EuRoC.yaml "$pathDatasetEuroc"/V201 ./Monocular/EuRoC_TimeStamps/V201.txt "$pathDatasetEuroc"/V202 ./Monocular/EuRoC_TimeStamps/V202.txt "$pathDatasetEuroc"/V203 ./Monocular/EuRoC_TimeStamps/V203.txt dataset-V201_to_V203_mono diff --git a/Examples/kitti_mono.sh b/Examples/kitti_mono.sh new file mode 100755 index 0000000000..39863aeeb2 --- /dev/null +++ b/Examples/kitti_mono.sh @@ -0,0 +1,69 @@ +#!/bin/bash + +# Check if all three arguments are provided +if [ "$#" -ne 1 ]; then + echo "Usage: $0 " + echo "example: $0 $HOME/Datasets/KITTI" + exit 1 +fi + +pathDataset="$1" +pathDatasetKITTI=$pathDataset/data_odometry_gray/dataset/sequences #Example, it is necesary to change it by the dataset path +echo "Dataset Path: $pathDatasetKITTI" + +#------------------------------------ +# Monocular Examples +sequence="00" +echo "Launching $sequence with Monocular sensor" +./Monocular/mono_kitti ../Vocabulary/ORBvoc.txt Monocular/KITTI00-02.yaml $pathDatasetKITTI/$sequence +mv KeyFrameTrajectory.txt kf_KITTI_$sequence.txt + +sequence="01" +echo "Launching $sequence with Monocular sensor" +./Monocular/mono_kitti ../Vocabulary/ORBvoc.txt Monocular/KITTI00-02.yaml $pathDatasetKITTI/$sequence +mv KeyFrameTrajectory.txt kf_KITTI_$sequence.txt + +sequence="02" +echo "Launching $sequence with Monocular sensor" +./Monocular/mono_kitti ../Vocabulary/ORBvoc.txt Monocular/KITTI00-02.yaml $pathDatasetKITTI/$sequence +mv KeyFrameTrajectory.txt kf_KITTI_$sequence.txt + +sequence="03" +echo "Launching $sequence with Monocular sensor" +./Monocular/mono_kitti ../Vocabulary/ORBvoc.txt Monocular/KITTI03.yaml $pathDatasetKITTI/$sequence +mv KeyFrameTrajectory.txt kf_KITTI_$sequence.txt + +sequence="04" +echo "Launching $sequence with Monocular sensor" +./Monocular/mono_kitti ../Vocabulary/ORBvoc.txt Monocular/KITTI04-12.yaml $pathDatasetKITTI/$sequence +mv KeyFrameTrajectory.txt kf_KITTI_$sequence.txt + +sequence="05" +echo "Launching $sequence with Monocular sensor" +./Monocular/mono_kitti ../Vocabulary/ORBvoc.txt Monocular/KITTI04-12.yaml $pathDatasetKITTI/$sequence +mv KeyFrameTrajectory.txt kf_KITTI_$sequence.txt + +sequence="06" +echo "Launching $sequence with Monocular sensor" +./Monocular/mono_kitti ../Vocabulary/ORBvoc.txt Monocular/KITTI04-12.yaml $pathDatasetKITTI/$sequence +mv KeyFrameTrajectory.txt kf_KITTI_$sequence.txt + +sequence="07" +echo "Launching $sequence with Monocular sensor" +./Monocular/mono_kitti ../Vocabulary/ORBvoc.txt Monocular/KITTI04-12.yaml $pathDatasetKITTI/$sequence +mv KeyFrameTrajectory.txt kf_KITTI_$sequence.txt + +sequence="08" +echo "Launching $sequence with Monocular sensor" +./Monocular/mono_kitti ../Vocabulary/ORBvoc.txt Monocular/KITTI04-12.yaml $pathDatasetKITTI/$sequence +mv KeyFrameTrajectory.txt kf_KITTI_$sequence.txt + +sequence="09" +echo "Launching $sequence with Monocular sensor" +./Monocular/mono_kitti ../Vocabulary/ORBvoc.txt Monocular/KITTI04-12.yaml $pathDatasetKITTI/$sequence +mv KeyFrameTrajectory.txt kf_KITTI_$sequence.txt + +sequence="10" +echo "Launching $sequence with Monocular sensor" +./Monocular/mono_kitti ../Vocabulary/ORBvoc.txt Monocular/KITTI04-12.yaml $pathDatasetKITTI/$sequence +mv KeyFrameTrajectory.txt kf_KITTI_$sequence.txt diff --git a/Examples/mimir_mono.sh b/Examples/mimir_mono.sh new file mode 100644 index 0000000000..02c36660b4 --- /dev/null +++ b/Examples/mimir_mono.sh @@ -0,0 +1,21 @@ +#!/bin/bash + +# Check if all three arguments are provided +if [ "$#" -ne 3 ]; then + echo "Usage: $0 " + echo "example: $0 SeaFloor track0 cam0" + exit 1 +fi + +echo "Environment: $1" +echo "Track: $2" +echo "Camera: $3" + +data_path="$HOME/Datasets/MIMIR/$1/$2/auv0/rgb/$3/data" +timestamps_path="Examples/Monocular/MIMIR_TimeStamps/$1_$2.txt" + +echo $data_path +echo $timestamps_path + +# Add quotes around $1_$2_$3.txt to handle cases where the arguments contain spaces +./Examples/Monocular/mono_mimir Vocabulary/ORBvoc.txt Examples/Monocular/MIMIR.yaml "$data_path" "$timestamps_path" "$1_$2_$3.txt" diff --git a/Examples/tum_mono.sh b/Examples/tum_mono.sh new file mode 100644 index 0000000000..511572fad4 --- /dev/null +++ b/Examples/tum_mono.sh @@ -0,0 +1,43 @@ +#!/bin/bash + +# Check if all three arguments are provided +if [ "$#" -ne 1 ]; then + echo "Usage: $0 " + echo "example: $0 $HOME/Datasets/TUM" + exit 1 +fi + +pathDatasetTUM="$1" +echo "Dataset Path: $pathDatasetTUM" + +#------------------------------------ +# Monocular Examples +track="rgbd_dataset_freiburg1_360" +echo "Launching $track with Monocular sensor" +./Monocular/mono_tum ../Vocabulary/ORBvoc.txt Monocular/TUM1.yaml "$pathDatasetTUM"/Handheld/$track +mv KeyFrameTrajectory.txt kf_$track.txt + +track="rgbd_dataset_freiburg3_nostructure_texture_near_withloop" +echo "Launching $track with Monocular sensor" +./Monocular/mono_tum ../Vocabulary/ORBvoc.txt Monocular/TUM1.yaml "$pathDatasetTUM"/StructureTexture/$track +mv KeyFrameTrajectory.txt kf_$track.txt + +track="rgbd_dataset_freiburg3_nostructure_notexture_far" +echo "Launching $track with Monocular sensor"./Monocular/mono_tum ../Vocabulary/ORBvoc.txt Monocular/TUM3.yaml "$pathDatasetTUM"/StructureTexture/$track +mv KeyFrameTrajectory.txt kf_$track.txt + +track="rgbd_dataset_freiburg1_rpy" +echo "Launching $track with Monocular sensor" +./Monocular/mono_tum ../Vocabulary/ORBvoc.txt Monocular/TUM3.yaml "$pathDatasetTUM"/TestingDebugging/$track +mv KeyFrameTrajectory.txt kf_$track.txt + +############################################################################ +# echo "Launching Room 4 with Monocular sensor" +# ./Monocular/mono_tum ../Vocabulary/ORBvoc.txt Monocular/TUM1.yaml "$pathDatasetTUM"/dataset-room4_512_16/mav0/cam0/data Monocular/TUM_TimeStamps/dataset-room4_512.txt dataset-room4_512_mono + +# echo "Launching Room 5 with Monocular sensor" +# ./Monocular/mono_tum ../Vocabulary/ORBvoc.txt Monocular/TUM1.yaml "$pathDatasetTUM"/dataset-room5_512_16/mav0/cam0/data Monocular/TUM_TimeStamps/dataset-room5_512.txt dataset-room5_512_mono + +# echo "Launching Room 6 with Monocular sensor" +# ./Monocular/mono_tum ../Vocabulary/ORBvoc.txt Monocular/TUM1.yaml "$pathDatasetTUM"/dataset-room6_512_16/mav0/cam0/data Monocular/TUM_TimeStamps/dataset-room6_512.txt dataset-room6_512_mono + diff --git a/Examples/tum_vi_eval_examples.sh b/Examples/tum_vi_eval_examples.sh new file mode 100755 index 0000000000..0e6ddca734 --- /dev/null +++ b/Examples/tum_vi_eval_examples.sh @@ -0,0 +1,19 @@ +#!/bin/bash + +# Check if all three arguments are provided +if [ "$#" -ne 1 ]; then + echo "Usage: $0 " + echo "example: $0 $HOME/Datasets/TUM_VI" + exit 1 +fi + +pathDatasetTUM_VI="$1" +echo "Dataset Path: $pathDatasetTUM_VI" + +# Single Session Example + +echo "Launching Magistrale 1 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt ./Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam1/data ./Stereo-Inertial/TUM_TimeStamps/dataset-magistrale1_512.txt ./Stereo-Inertial/TUM_IMU/dataset-magistrale1_512.txt dataset-magistrale1_512_stereoi +echo "------------------------------------" +echo "Evaluation of Magistrale 1 trajectory with Stereo-Inertial sensor" +python ../evaluation/evaluate_ate_scale.py "$pathDatasetTUM_VI"/magistrale1_512_16/mav0/mocap0/data.csv f_dataset-magistrale1_512_stereoi.txt --plot magistrale1_512_stereoi.pdf diff --git a/Examples/tum_vi_examples.sh b/Examples/tum_vi_examples.sh new file mode 100755 index 0000000000..6e07d4d0fd --- /dev/null +++ b/Examples/tum_vi_examples.sh @@ -0,0 +1,249 @@ +#!/bin/bash + +# Check if all three arguments are provided +if [ "$#" -ne 1 ]; then + echo "Usage: $0 " + echo "example: $0 $HOME/Datasets/TUM_VI" + exit 1 +fi + +pathDatasetTUM_VI="$1" +echo "Dataset Path: $pathDatasetTUM_VI" + +#------------------------------------ +# Monocular Examples +echo "Launching Room 1 with Monocular sensor" +./Monocular/mono_tum_vi ../Vocabulary/ORBvoc.txt Monocular/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data Monocular/TUM_TimeStamps/dataset-room1_512.txt dataset-room1_512_mono + +echo "Launching Room 2 with Monocular sensor" +./Monocular/mono_tum_vi ../Vocabulary/ORBvoc.txt Monocular/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam0/data Monocular/TUM_TimeStamps/dataset-room2_512.txt dataset-room2_512_mono + +echo "Launching Room 3 with Monocular sensor" +./Monocular/mono_tum_vi ../Vocabulary/ORBvoc.txt Monocular/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam0/data Monocular/TUM_TimeStamps/dataset-room3_512.txt dataset-room3_512_mono + +echo "Launching Room 4 with Monocular sensor" +./Monocular/mono_tum_vi ../Vocabulary/ORBvoc.txt Monocular/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam0/data Monocular/TUM_TimeStamps/dataset-room4_512.txt dataset-room4_512_mono + +echo "Launching Room 5 with Monocular sensor" +./Monocular/mono_tum_vi ../Vocabulary/ORBvoc.txt Monocular/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam0/data Monocular/TUM_TimeStamps/dataset-room5_512.txt dataset-room5_512_mono + +echo "Launching Room 6 with Monocular sensor" +./Monocular/mono_tum_vi ../Vocabulary/ORBvoc.txt Monocular/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam0/data Monocular/TUM_TimeStamps/dataset-room6_512.txt dataset-room6_512_mono + + +#------------------------------------ +# Stereo Examples +echo "Launching Room 1 with Stereo sensor" +./Stereo/stereo_tum_vi ../Vocabulary/ORBvoc.txt Stereo/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam1/data Stereo/TUM_TimeStamps/dataset-room1_512.txt dataset-room1_512_stereo + +echo "Launching Room 2 with Stereo sensor" +./Stereo/stereo_tum_vi ../Vocabulary/ORBvoc.txt Stereo/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam1/data Stereo/TUM_TimeStamps/dataset-room2_512.txt dataset-room2_512_stereo + +echo "Launching Room 3 with Stereo sensor" +./Stereo/stereo_tum_vi ../Vocabulary/ORBvoc.txt Stereo/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam1/data Stereo/TUM_TimeStamps/dataset-room3_512.txt dataset-room3_512_stereo + +echo "Launching Room 4 with Stereo sensor" +./Stereo/stereo_tum_vi ../Vocabulary/ORBvoc.txt Stereo/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam1/data Stereo/TUM_TimeStamps/dataset-room4_512.txt dataset-room4_512_stereo + +echo "Launching Room 5 with Stereo sensor" +./Stereo/stereo_tum_vi ../Vocabulary/ORBvoc.txt Stereo/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam1/data Stereo/TUM_TimeStamps/dataset-room5_512.txt dataset-room5_512_stereo + +echo "Launching Room 6 with Stereo sensor" +./Stereo/stereo_tum_vi ../Vocabulary/ORBvoc.txt Stereo/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam1/data Stereo/TUM_TimeStamps/dataset-room6_512.txt dataset-room6_512_stereo + + +#------------------------------------ +# Monocular-Inertial Examples +echo "Launching Corridor 1 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor1_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-corridor1_512.txt Monocular-Inertial/TUM_IMU/dataset-corridor1_512.txt dataset-corridor1_512_monoi + +echo "Launching Corridor 2 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor2_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-corridor2_512.txt Monocular-Inertial/TUM_IMU/dataset-corridor2_512.txt dataset-corridor2_512_monoi + +echo "Launching Corridor 3 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor3_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-corridor3_512.txt Monocular-Inertial/TUM_IMU/dataset-corridor3_512.txt dataset-corridor3_512_monoi + +echo "Launching Corridor 4 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor4_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-corridor4_512.txt Monocular-Inertial/TUM_IMU/dataset-corridor4_512.txt dataset-corridor4_512_monoi + +echo "Launching Corridor 5 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor5_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-corridor5_512.txt Monocular-Inertial/TUM_IMU/dataset-corridor5_512.txt dataset-corridor5_512_monoi + + +echo "Launching Magistrale 1 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-magistrale1_512.txt Monocular-Inertial/TUM_IMU/dataset-magistrale1_512.txt dataset-magistrale1_512_monoi + +echo "Launching Magistrale 2 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale2_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-magistrale2_512.txt Monocular-Inertial/TUM_IMU/dataset-magistrale2_512.txt dataset-magistrale2_512 + +echo "Launching Magistrale 3 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale3_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-magistrale3_512.txt Monocular-Inertial/TUM_IMU/dataset-magistrale3_512.txt dataset-magistrale3_512_monoi + +echo "Launching Magistrale 4 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale4_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-magistrale4_512.txt Monocular-Inertial/TUM_IMU/dataset-magistrale4_512.txt dataset-magistrale4_512_monoi + +echo "Launching Magistrale 5 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale5_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-magistrale5_512.txt Monocular-Inertial/TUM_IMU/dataset-magistrale5_512.txt dataset-magistrale5_512_monoi + +echo "Launching Magistrale 6 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale6_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-magistrale6_512.txt Monocular-Inertial/TUM_IMU/dataset-magistrale6_512.txt dataset-magistrale6_512_monoi + + +echo "Launching Outdoor 1 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors1_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-outdoors1_512.txt Monocular-Inertial/TUM_IMU/dataset-outdoors1_512.txt dataset-outdoors1_512_monoi + +echo "Launching Outdoor 2 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors2_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-outdoors2_512.txt Monocular-Inertial/TUM_IMU/dataset-outdoors2_512.txt dataset-outdoors2_512_monoi + +echo "Launching Outdoor 3 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors3_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-outdoors3_512.txt Monocular-Inertial/TUM_IMU/dataset-outdoors3_512.txt dataset-outdoors3_512_monoi + +echo "Launching Outdoor 4 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors4_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-outdoors4_512.txt Monocular-Inertial/TUM_IMU/dataset-outdoors4_512.txt dataset-outdoors4_512_monoi + +echo "Launching Outdoor 5 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors5_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-outdoors5_512.txt Monocular-Inertial/TUM_IMU/dataset-outdoors5_512.txt dataset-outdoors5_512_monoi + +echo "Launching Outdoor 6 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors6_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-outdoors6_512.txt Monocular-Inertial/TUM_IMU/dataset-outdoors6_512.txt dataset-outdoors6_512_monoi + +echo "Launching Outdoor 7 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors7_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-outdoors7_512.txt Monocular-Inertial/TUM_IMU/dataset-outdoors7_512.txt dataset-outdoors7_512_monoi + +echo "Launching Outdoor 8 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512_far.yaml "$pathDatasetTUM_VI"/dataset-outdoors8_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-outdoors8_512.txt Monocular-Inertial/TUM_IMU/dataset-outdoors8_512.txt dataset-outdoors8_512_monoi + + +echo "Launching Room 1 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-room1_512.txt Monocular-Inertial/TUM_IMU/dataset-room1_512.txt dataset-room1_512_monoi + +echo "Launching Room 2 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-room2_512.txt Monocular-Inertial/TUM_IMU/dataset-room2_512.txt dataset-room2_512_monoi + +echo "Launching Room 3 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-room3_512.txt Monocular-Inertial/TUM_IMU/dataset-room3_512.txt dataset-room3_512_monoi + +echo "Launching Room 4 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-room4_512.txt Monocular-Inertial/TUM_IMU/dataset-room4_512.txt dataset-room4_512_monoi + +echo "Launching Room 5 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-room5_512.txt Monocular-Inertial/TUM_IMU/dataset-room5_512.txt dataset-room5_512_monoi + +echo "Launching Room 6 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-room6_512.txt Monocular-Inertial/TUM_IMU/dataset-room6_512.txt dataset-room6_512_monoi + + +echo "Launching Slides 1 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-slides1_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-slides1_512.txt Monocular-Inertial/TUM_IMU/dataset-slides1_512.txt dataset-slides1_512_monoi + +echo "Launching Slides 2 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-slides2_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-slides2_512.txt Monocular-Inertial/TUM_IMU/dataset-slides2_512.txt dataset-slides2_512_monoi + +echo "Launching Slides 3 with Monocular-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-slides3_512_16/mav0/cam0/data Monocular-Inertial/TUM_TimeStamps/dataset-slides3_512.txt Monocular-Inertial/TUM_IMU/dataset-slides3_512.txt dataset-slides3_512_monoi + + +# MultiSession Monocular Examples +echo "Launching Room 1, Magistrale 1, Magistrale 5 and Slides 1 in the same session with Stereo-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data Stereo-Inertial/TUM_TimeStamps/dataset-room1_512.txt Stereo-Inertial/TUM_IMU/dataset-room1_512.txt "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam0/data Stereo-Inertial/TUM_TimeStamps/dataset-magistrale1_512.txt Stereo-Inertial/TUM_IMU/dataset-magistrale1_512.txt "$pathDatasetTUM_VI"/dataset-magistrale5_512_16/mav0/cam0/data Stereo-Inertial/TUM_TimeStamps/dataset-magistrale5_512.txt Stereo-Inertial/TUM_IMU/dataset-magistrale5_512.txt "$pathDatasetTUM_VI"/dataset-slides1_512_16/mav0/cam0/data Stereo-Inertial/TUM_TimeStamps/dataset-slides1_512.txt Stereo-Inertial/TUM_IMU/dataset-slides1_512.txt dataset-room1_mag1_mag5_slides1_monoi + +echo "Launching all Rooms (1-6) in the same session with Stereo-Inertial sensor" +./Monocular-Inertial/mono_inertial_tum_vi ../Vocabulary/ORBvoc.txt Monocular-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data Stereo-Inertial/TUM_TimeStamps/dataset-room1_512.txt Stereo-Inertial/TUM_IMU/dataset-room1_512.txt "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam0/data Stereo-Inertial/TUM_TimeStamps/dataset-room2_512.txt Stereo-Inertial/TUM_IMU/dataset-room2_512.txt "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam0/data Stereo-Inertial/TUM_TimeStamps/dataset-room3_512.txt Stereo-Inertial/TUM_IMU/dataset-room3_512.txt "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam0/data Stereo-Inertial/TUM_TimeStamps/dataset-room4_512.txt Stereo-Inertial/TUM_IMU/dataset-room4_512.txt "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam0/data Stereo-Inertial/TUM_TimeStamps/dataset-room5_512.txt Stereo-Inertial/TUM_IMU/dataset-room5_512.txt "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam0/data Stereo-Inertial/TUM_TimeStamps/dataset-room6_512.txt Stereo-Inertial/TUM_IMU/dataset-room6_512.txt dataset-rooms123456_monoi + +#------------------------------------ +# Stereo-Inertial Examples +echo "Launching Corridor 1 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-corridor1_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-corridor1_512.txt Stereo-Inertial/TUM_IMU/dataset-corridor1_512.txt dataset-corridor1_512_stereoi + +echo "Launching Corridor 2 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor2_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-corridor2_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-corridor2_512.txt Stereo-Inertial/TUM_IMU/dataset-corridor2_512.txt dataset-corridor2_512_stereoi + +echo "Launching Corridor 3 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor3_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-corridor3_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-corridor3_512.txt Stereo-Inertial/TUM_IMU/dataset-corridor3_512.txt dataset-corridor3_512_stereoi + +echo "Launching Corridor 4 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor4_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-corridor4_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-corridor4_512.txt Stereo-Inertial/TUM_IMU/dataset-corridor4_512.txt dataset-corridor4_512_stereoi + +echo "Launching Corridor 5 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-corridor5_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-corridor5_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-corridor5_512.txt Stereo-Inertial/TUM_IMU/dataset-corridor5_512.txt dataset-corridor5_512_stereoi + + +echo "Launching Magistrale 1 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-magistrale1_512.txt Stereo-Inertial/TUM_IMU/dataset-magistrale1_512.txt dataset-magistrale1_512_stereoi + +echo "Launching Magistrale 2 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale2_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale2_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-magistrale2_512.txt Stereo-Inertial/TUM_IMU/dataset-magistrale2_512.txt dataset-magistrale2_512_stereoi + +echo "Launching Magistrale 3 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale3_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale3_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-magistrale3_512.txt Stereo-Inertial/TUM_IMU/dataset-magistrale3_512.txt dataset-magistrale3_512_stereoi + +echo "Launching Magistrale 4 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale4_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale4_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-magistrale4_512.txt Stereo-Inertial/TUM_IMU/dataset-magistrale4_512.txt dataset-magistrale4_512_stereoi + +echo "Launching Magistrale 5 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale5_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale5_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-magistrale5_512.txt Stereo-Inertial/TUM_IMU/dataset-magistrale5_512.txt dataset-magistrale5_512_stereoi + +echo "Launching Magistrale 6 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-magistrale6_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale6_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-magistrale6_512.txt Stereo-Inertial/TUM_IMU/dataset-magistrale6_512.txt dataset-magistrale6_512_stereoi + + +echo "Launching Outdoor 1 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors1_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-outdoors1_512.txt Stereo-Inertial/TUM_IMU/dataset-outdoors1_512.txt outdoors1_512_stereoi + +echo "Launching Outdoor 2 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors2_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors2_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-outdoors2_512.txt Stereo-Inertial/TUM_IMU/dataset-outdoors2_512.txt outdoors2_512_stereoi + +echo "Launching Outdoor 3 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors3_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors3_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-outdoors3_512.txt Stereo-Inertial/TUM_IMU/dataset-outdoors3_512.txt outdoors3_512 + +echo "Launching Outdoor 4 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors4_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors4_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-outdoors4_512.txt Stereo-Inertial/TUM_IMU/dataset-outdoors4_512.txt outdoors4_512 + +echo "Launching Outdoor 5 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors5_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors5_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-outdoors5_512.txt Stereo-Inertial/TUM_IMU/dataset-outdoors5_512.txt outdoors5_512_stereoi + +echo "Launching Outdoor 6 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors6_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors6_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-outdoors6_512.txt Stereo-Inertial/TUM_IMU/dataset-outdoors6_512.txt outdoors6_512_stereoi + +echo "Launching Outdoor 7 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors7_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors7_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-outdoors7_512.txt Stereo-Inertial/TUM_IMU/dataset-outdoors7_512.txt outdoors7_512_stereoi + +echo "Launching Outdoor 8 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512_outdoors.yaml "$pathDatasetTUM_VI"/dataset-outdoors8_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-outdoors8_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-outdoors8_512.txt Stereo-Inertial/TUM_IMU/dataset-outdoors8_512.txt outdoors8_512_stereoi + + +echo "Launching Room 1 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-room1_512.txt Stereo-Inertial/TUM_IMU/dataset-room1_512.txt dataset-room1_512_stereoi + +echo "Launching Room 2 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-room2_512.txt Stereo-Inertial/TUM_IMU/dataset-room2_512.txt dataset-room2_512_stereoi + +echo "Launching Room 3 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-room3_512.txt Stereo-Inertial/TUM_IMU/dataset-room3_512.txt dataset-room3_512_stereoi + +echo "Launching Room 4 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-room4_512.txt Stereo-Inertial/TUM_IMU/dataset-room4_512.txt dataset-room4_512_stereoi + +echo "Launching Room 5 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-room5_512.txt Stereo-Inertial/TUM_IMU/dataset-room5_512.txt dataset-room5_512_stereoi + +echo "Launching Room 6 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-room6_512.txt Stereo-Inertial/TUM_IMU/dataset-room6_512.txt dataset-room6_512_stereoi + + +echo "Launching Slides 1 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-slides1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-slides1_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-slides1_512.txt Stereo-Inertial/TUM_IMU/dataset-slides1_512.txt dataset-slides1_512_stereoi + +echo "Launching Slides 2 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-slides2_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-slides2_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-slides2_512.txt Stereo-Inertial/TUM_IMU/dataset-slides2_512.txt dataset-slides2_512_stereoi + +echo "Launching Slides 3 with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-slides3_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-slides3_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-slides3_512.txt Stereo-Inertial/TUM_IMU/dataset-slides3_512.txt dataset-slides3_512_stereoi + + +# MultiSession Stereo-Inertial Examples +echo "Launching Room 1, Magistrale 1, Magistrale 5 and Slides 1 in the same session with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-room1_512.txt Stereo-Inertial/TUM_IMU/dataset-room1_512.txt "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale1_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-magistrale1_512.txt Stereo-Inertial/TUM_IMU/dataset-magistrale1_512.txt "$pathDatasetTUM_VI"/dataset-magistrale5_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-magistrale5_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-magistrale5_512.txt Stereo-Inertial/TUM_IMU/dataset-magistrale5_512.txt "$pathDatasetTUM_VI"/dataset-slides1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-slides1_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-slides1_512.txt Stereo-Inertial/TUM_IMU/dataset-slides1_512.txt dataset-room1_mag1_mag5_slides1_stereoi + +echo "Launching all Rooms (1-6) in the same session with Stereo-Inertial sensor" +./Stereo-Inertial/stereo_inertial_tum_vi ../Vocabulary/ORBvoc.txt Stereo-Inertial/TUM_512.yaml "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room1_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-room1_512.txt Stereo-Inertial/TUM_IMU/dataset-room1_512.txt "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room2_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-room2_512.txt Stereo-Inertial/TUM_IMU/dataset-room2_512.txt "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room3_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-room3_512.txt Stereo-Inertial/TUM_IMU/dataset-room3_512.txt "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room4_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-room4_512.txt Stereo-Inertial/TUM_IMU/dataset-room4_512.txt "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room5_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-room5_512.txt Stereo-Inertial/TUM_IMU/dataset-room5_512.txt "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam0/data "$pathDatasetTUM_VI"/dataset-room6_512_16/mav0/cam1/data Stereo-Inertial/TUM_TimeStamps/dataset-room6_512.txt Stereo-Inertial/TUM_IMU/dataset-room6_512.txt dataset-rooms123456_stereoi diff --git a/README.md b/README.md index 9242f408c4..e40ebfa1f0 100644 --- a/README.md +++ b/README.md @@ -1,7 +1,8 @@ # ORB-SLAM3 ### V1.0, December 22th, 2021 -**Authors:** Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, [José M. M. Montiel](http://webdiis.unizar.es/~josemari/), [Juan D. Tardos](http://webdiis.unizar.es/~jdtardos/). +**Authors:** Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, [José M. M. Montiel](http://webdiis.unizar.es/~josemari/), [Juan D. Tardos](http://webdiis.unizar.es/~jdtardos/). Fork and modifications by [Olaya Álvarez-Tuñón](https://www.linkedin.com/in/olayatu/?locale=en_US) + The [Changelog](https://github.com/UZ-SLAMLab/ORB_SLAM3/blob/master/Changelog.md) describes the features of each version. @@ -11,6 +12,9 @@ We provide examples to run ORB-SLAM3 in the datasets: - [EuRoC](http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets) using stereo or monocular, with or without IMU. - [TUM-VI](https://vision.in.tum.de/data/datasets/visual-inertial-dataset) using fisheye stereo or monocular, with or without IMU. - [MIMIR-UW](https://github.com/remaro-network/MIMIR-UW) using stereo or monocular, without IMU. + - [SubPipe](https://github.com/remaro-network/SubPipe-dataset) using monocular, without IMU. + - Aqualoc + - KITTI Videos of some example executions can be found at [ORB-SLAM3 channel](https://www.youtube.com/channel/UCXVt-kXG6T95Z4tVaYlU80Q). @@ -59,8 +63,8 @@ If you use ORB-SLAM3 in an academic work, please cite: # 2. Prerequisites We have tested the library in **Ubuntu 16.04** and **18.04**, but it should be easy to compile in other platforms. A powerful computer (e.g. i7) will ensure real-time performance and provide more stable and accurate results. -## C++11 or C++0x Compiler -We use the new thread and chrono functionalities of C++11. +## C++14 +ORB-SLAM3 the thread and chrono functionalities of C++11, but the CMakeLists have been modified to work with C++14. ## Pangolin We use [Pangolin](https://github.com/stevenlovegrove/Pangolin) for visualization and user interface. Dowload and install instructions can be found at: https://github.com/stevenlovegrove/Pangolin. From e7db2089c4dc491953fe7ba040ec9a3288d4be9e Mon Sep 17 00:00:00 2001 From: olayasturias Date: Tue, 28 Nov 2023 11:38:15 +0100 Subject: [PATCH 16/17] script for subpipe --- Examples/Monocular/SubPipe.yaml | 80 +++++++++++++++++++++++++++++++++ Examples/subpipe_mono.sh | 14 ++++++ 2 files changed, 94 insertions(+) create mode 100644 Examples/Monocular/SubPipe.yaml create mode 100755 Examples/subpipe_mono.sh diff --git a/Examples/Monocular/SubPipe.yaml b/Examples/Monocular/SubPipe.yaml new file mode 100644 index 0000000000..e53019f50c --- /dev/null +++ b/Examples/Monocular/SubPipe.yaml @@ -0,0 +1,80 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# System config +#-------------------------------------------------------------------------------------------- + +# When the variables are commented, the system doesn't load a previous session or not store the current one + +# If the LoadFile doesn't exist, the system give a message and create a new Atlas from scratch +#System.LoadAtlasFromFile: "Session_MH01_MH02_MH03_Mono" + +# The store file is created from the current session, if a file with the same name exists it is deleted +#System.SaveAtlasToFile: "Session_MH01_MH02_MH03_Mono" + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- +File.version: "1.0" + +Camera.type: "PinHole" + +# Camera calibration and distortion parameters (OpenCV) +Camera1.fx: 1612.36 +Camera1.fy: 1622.56 +Camera1.cx: 1365.43 +Camera1.cy: 741.27 + +Camera1.k1: -0.247 +Camera1.k2: 0.0869 +Camera1.p1: -0.006 +Camera1.p2: 0.001 + +Camera.width: 2704 +Camera.height: 1520 + +Camera.newWidth: 640 +Camera.newHeight: 480 + +# Camera frames per second +Camera.fps: 30 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 10000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 3 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 10 +ORBextractor.minThFAST: 2 + +ORBextractor.iniThRatio: 0.5 +ORBextractor.minThRatio: 0.2 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#--------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1.0 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize: 2.0 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3.0 +Viewer.ViewpointX: 0.0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500.0 \ No newline at end of file diff --git a/Examples/subpipe_mono.sh b/Examples/subpipe_mono.sh new file mode 100755 index 0000000000..a226712a9c --- /dev/null +++ b/Examples/subpipe_mono.sh @@ -0,0 +1,14 @@ +#!/bin/bash + +# Check if both arguments are provided +if [ "$#" -ne 1 ]; then + echo "Usage: $0 " + echo "example: $0 $HOME/Datasets/SubPipe" + exit 1 +fi + +pathDataset="$1" + +echo "Dataset Path: $pathDataset" + +./Monocular/mono_subpipe ../Vocabulary/ORBvoc.txt Monocular/SubPipe.yaml $pathDataset/DATA/ From 74238a9fca8c1d5a33b7da0774f8772dc92d7e79 Mon Sep 17 00:00:00 2001 From: olayasturias Date: Mon, 5 Feb 2024 16:49:20 +0100 Subject: [PATCH 17/17] added code for subpipe mono and mono-inertial --- CMakeLists.txt | 4 + Examples/Monocular-Inertial/SubPipe.yaml | 97 +++++ .../mono_inertial_subpipe.cc | 332 ++++++++++++++++++ Examples/Monocular/mono_subpipe.cc | 2 +- 4 files changed, 434 insertions(+), 1 deletion(-) create mode 100644 Examples/Monocular-Inertial/SubPipe.yaml create mode 100644 Examples/Monocular-Inertial/mono_inertial_subpipe.cc diff --git a/CMakeLists.txt b/CMakeLists.txt index e6aec15992..5b4d44b4eb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -239,6 +239,10 @@ add_executable(mono_inertial_euroc Examples/Monocular-Inertial/mono_inertial_euroc.cc) target_link_libraries(mono_inertial_euroc ${PROJECT_NAME}) +add_executable(mono_inertial_subpipe + Examples/Monocular-Inertial/mono_inertial_subpipe.cc) +target_link_libraries(mono_inertial_subpipe ${PROJECT_NAME}) + add_executable(mono_inertial_tum_vi Examples/Monocular-Inertial/mono_inertial_tum_vi.cc) target_link_libraries(mono_inertial_tum_vi ${PROJECT_NAME}) diff --git a/Examples/Monocular-Inertial/SubPipe.yaml b/Examples/Monocular-Inertial/SubPipe.yaml new file mode 100644 index 0000000000..2fd7ad7c4b --- /dev/null +++ b/Examples/Monocular-Inertial/SubPipe.yaml @@ -0,0 +1,97 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# System config +#-------------------------------------------------------------------------------------------- + +# When the variables are commented, the system doesn't load a previous session or not store the current one + +# If the LoadFile doesn't exist, the system give a message and create a new Atlas from scratch +#System.LoadAtlasFromFile: "Session_MH01_MH02_MH03_Mono" + +# The store file is created from the current session, if a file with the same name exists it is deleted +#System.SaveAtlasToFile: "Session_MH01_MH02_MH03_Mono" + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- +File.version: "1.0" + +Camera.type: "PinHole" + +# Camera calibration and distortion parameters (OpenCV) +Camera1.fx: 1612.36 +Camera1.fy: 1622.56 +Camera1.cx: 1365.43 +Camera1.cy: 741.27 + +Camera1.k1: -0.247 +Camera1.k2: 0.0869 +Camera1.p1: -0.006 +Camera1.p2: 0.001 + +Camera.width: 2704 +Camera.height: 1520 + +Camera.newWidth: 640 +Camera.newHeight: 480 + +# Camera frames per second +Camera.fps: 30 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +# Transformation from camera to body-frame (imu) +IMU.T_b_c1: !!opencv-matrix + rows: 4 + cols: 4 + dt: f + data: [1., 0., 0., 0., + 0., 1., 0., 0., + 0., 0., 1., 0., + 0., 0., 0., 1.] + +# IMU noise +IMU.NoiseGyro: 1.7e-4 #1.6968e-04 +IMU.NoiseAcc: 2.0000e-3 #2.0e-3 +IMU.GyroWalk: 1.9393e-05 +IMU.AccWalk: 3.0000e-03 # 3e-03 +IMU.Frequency: 30.0 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 10000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 3 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 5 +ORBextractor.minThFAST: 1 + +ORBextractor.iniThRatio: 0.2 +ORBextractor.minThRatio: 0.1 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#--------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1.0 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize: 2.0 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3.0 +Viewer.ViewpointX: 0.0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500.0 \ No newline at end of file diff --git a/Examples/Monocular-Inertial/mono_inertial_subpipe.cc b/Examples/Monocular-Inertial/mono_inertial_subpipe.cc new file mode 100644 index 0000000000..a5309dd19b --- /dev/null +++ b/Examples/Monocular-Inertial/mono_inertial_subpipe.cc @@ -0,0 +1,332 @@ +/** +* This file is part of ORB-SLAM3 +* +* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. +* +* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public +* License as published by the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even +* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License along with ORB-SLAM3. +* If not, see . +*/ + + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include "ImuTypes.h" + +using namespace std; + +void LoadImages(const std::string &strAccPath, + std::vector &vImagePaths, std::vector &vTimeStamps); + +void LoadIMU(const std::string &strAccPath, const std::string &strGyroPath, std::vector &vTimeStamps, std::vector &vAcc, std::vector &vGyro); + +double ttrack_tot = 0; +int main(int argc, char *argv[]) +{ + + if(argc < 4) + { + cerr << endl << "Usage: ./mono_inertial_subpipe path_to_vocabulary path_to_settings path_to_sequence_folder_1 " << endl; + return 1; + } + + const int num_seq = argc-3; + cout << "num_seq = " << num_seq << endl; + bool bFileName= (((argc-3) % 2) == 1); + string file_name; + if (bFileName) + { + file_name = string(argv[argc-1]); + cout << "Path to files: " << file_name << endl; + } + + // Load all sequences: + int seq; + vector< vector > vstrImageFilenames; + vector< vector > vTimestampsCam; + vector< vector > vAcc, vGyro; + vector< vector > vTimestampsImu; + vector nImages; + vector nImu; + vector first_imu(num_seq,0); + vstrImageFilenames.resize(num_seq); + vTimestampsCam.resize(num_seq); + vAcc.resize(num_seq); + vGyro.resize(num_seq); + vTimestampsImu.resize(num_seq); + nImages.resize(num_seq); + nImu.resize(num_seq); + int tot_images = 0; + for (seq = 0; seq vTimesTrack; + vTimesTrack.resize(tot_images); + + cout.precision(17); + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_MONOCULAR, true); + float imageScale = SLAM.GetImageScale(); + + double t_resize = 0.f; + double t_track = 0.f; + + int proccIm=0; + for (seq = 0; seq vImuMeas; + proccIm = 0; + for(int ni=0; ni >(t_End_Resize - t_Start_Resize).count(); + SLAM.InsertResizeTime(t_resize); +#endif + } + + // Load imu measurements from previous frame + vImuMeas.clear(); + + if(ni>0) + { + // cout << "t_cam " << tframe << endl; + + while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][ni]) + { + vImuMeas.push_back(ORB_SLAM3::IMU::Point(vAcc[seq][first_imu[seq]].x,vAcc[seq][first_imu[seq]].y,vAcc[seq][first_imu[seq]].z, + vGyro[seq][first_imu[seq]].x,vGyro[seq][first_imu[seq]].y,vGyro[seq][first_imu[seq]].z, + vTimestampsImu[seq][first_imu[seq]])); + first_imu[seq]++; + } + } + + #ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); + #else + std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now(); + #endif + + // Pass the image to the SLAM system + // cout << "tframe = " << tframe << endl; + SLAM.TrackMonocular(im,tframe,vImuMeas); // TODO change to monocular_inertial + + #ifdef COMPILEDWITHC11 + std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); + #else + std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now(); + #endif + +#ifdef REGISTER_TIMES + t_track = t_resize + std::chrono::duration_cast >(t2 - t1).count(); + SLAM.InsertTrackTime(t_track); +#endif + + double ttrack= std::chrono::duration_cast >(t2 - t1).count(); + ttrack_tot += ttrack; + // std::cout << "ttrack: " << ttrack << std::endl; + + vTimesTrack[ni]=ttrack; + + // Wait to load the next frame + double T=0; + if(ni0) + T = tframe-vTimestampsCam[seq][ni-1]; + + if(ttrack &vImagePaths, std::vector &vTimeStamps) { + std::ifstream fAcc(strAccPath); + std::string line; + + // Skip the header + std::getline(fAcc, line); + + while (std::getline(fAcc, line)) { + std::istringstream ss(line); + + std::string imagePath; + double timestamp; + std::string dummy; // for skipping other data fields + + // Parse image path and timestamp + std::getline(ss, imagePath, ','); + std::getline(ss, dummy, ','); timestamp = std::stod(dummy); + + // Skip the rest of the data in the line + std::getline(ss, dummy); + + // Extracting just the filename from the path using dirent.h + size_t lastSlashPos = imagePath.find_last_of('/'); + std::string fileName = (lastSlashPos != std::string::npos) ? imagePath.substr(lastSlashPos + 1) : imagePath; + + vImagePaths.push_back(fileName); + vTimeStamps.push_back(timestamp); + } + + fAcc.close(); +} + +void LoadIMU(const std::string &strAccPath, const std::string &strGyroPath, std::vector &vTimeStamps, std::vector &vAcc, std::vector &vGyro) { + std::ifstream fAcc, fGyro; + fAcc.open(strAccPath); + fGyro.open(strGyroPath); + + std::string lineAcc, lineGyro; + + // Skip headers + std::getline(fAcc, lineAcc); + std::getline(fGyro, lineGyro); + + while (std::getline(fAcc, lineAcc) && std::getline(fGyro, lineGyro)) { + std::istringstream ssAcc(lineAcc), ssGyro(lineGyro); + + std::string sImageAcc, sImageGyro; + double timestampAcc, timestampGyro; + float accX, accY, accZ, gyroX, gyroY, gyroZ; + + std::string token; + + // Parse acceleration data + std::getline(ssAcc, sImageAcc, ','); // Skip image path + std::getline(ssAcc, token, ','); timestampAcc = std::stod(token); + std::getline(ssAcc, token, ','); accX = std::stof(token); + std::getline(ssAcc, token, ','); accY = std::stof(token); + std::getline(ssAcc, token, ','); accZ = std::stof(token); + + // Parse gyroscope data + std::getline(ssGyro, sImageGyro, ','); // Skip image path + std::getline(ssGyro, token, ','); timestampGyro = std::stod(token); + std::getline(ssGyro, token, ','); gyroX = std::stof(token); + std::getline(ssGyro, token, ','); gyroY = std::stof(token); + std::getline(ssGyro, token, ','); gyroZ = std::stof(token); + + // Check if timestamps match + if (timestampAcc != timestampGyro) { + std::cerr << "Warning: Mismatched timestamps found:" << std::endl; + std::cout << "Image Acc: " << sImageAcc << ", Timestamp Acc: " << timestampAcc << std::endl; + std::cout << "Image Gyro: " << sImageGyro << ", Timestamp Gyro: " << timestampGyro << std::endl; + continue; + } + + vTimeStamps.push_back(timestampAcc); + vAcc.emplace_back(accX, accY, accZ); + vGyro.emplace_back(gyroX, gyroY, gyroZ); + } + + fAcc.close(); + fGyro.close(); +} + diff --git a/Examples/Monocular/mono_subpipe.cc b/Examples/Monocular/mono_subpipe.cc index 4f5ed094a6..a361f6caca 100644 --- a/Examples/Monocular/mono_subpipe.cc +++ b/Examples/Monocular/mono_subpipe.cc @@ -66,7 +66,7 @@ int main(int argc, char **argv) { // Read image from file - im = cv::imread(string(argv[3])+"Cam0_images/"+vstrImageFilenames[ni],cv::IMREAD_UNCHANGED); + im = cv::imread(string(argv[3])+"/Cam0_images/"+vstrImageFilenames[ni],cv::IMREAD_UNCHANGED); double tframe = vTimestamps[ni];