initial commit

main
josch 12 years ago
commit 0281b65175

@ -0,0 +1,928 @@
@InProceedings{VMV2001,
author = "H. Surmann and K. Lingemann and A. N{\"u}chter and J. Hertzberg",
title = "{F}ast acquiring and analysis of three dimensional laser range data",
booktitle = "Proceedings of the of the 6th International Fall Workshop Vision, Modeling, and Visualization (VMV '01)",
month = "November",
year = "2001",
pages = "59 -- 66",
address = "Stuttgart, Germany"
}
@InProceedings{ISR2001,
author = "H. Surmann and K. Lingemann and A. N{\"u}chter and J. Hertzberg",
title = "A 3{D} laser range finder for autonomous mobile robots",
booktitle = "Proceedings of the of the 32nd International Symposium on Robotics (ISR '01)",
month = "April",
year = "2001",
pages = "153 -- 158",
address = "Seoul, Korea"
}
@Book{Report2001,
author = "H. Surmann and K. Lingemann and A. N{\"u}chter and J. Hertzberg",
title = "Aufbau eines 3D--Laserscanners f{\"u}r autonome mobile Roboter, GMD Report 126",
publisher = "GMD - Forschungszentrum Informationstechnik GmbH",
address = "Sankt Augustin",
month = "March",
year = "2001",
}
@InProceedings{IT2001,
author = "A. N{\"u}chter and K. Lingemann",
title = "Ein 3{D}-{L}aserscanner f{\"u}r autonome mobile {R}oboter",
booktitle = "Tagungsband zum 3. Fachwissenschaftlichen Informatikkongress - Informatiktage 2001",
month = "November",
year = "2001",
pages = "89 -- 92",
address = "Bad Schussenried, Germany"
}
@Article{Ariadne1998,
author= "H. Surmann",
title = "Diener mit unscharfer {L}ogik",
month = "March",
year = "1998",
journal = "GMD--Pointer, http://www.gmd.de/pointer/2-98/servicerob.html",
}
@misc{Karpinski2000,
author = "M. Karpinski",
title = "Approximative {A}lgorithmen f{\"u}r {NP}--harte {B}erechnungsprobleme (\textit{{APX} 00}), {U}niversit{"a}t {B}onn, {V}orlesungsmitschrift",
year = "2000",
}
@misc{Frehse1997,
author = "J. Frehse",
title = "Infinitisimalrechnung II, {U}niversit{"a}t {B}onn, {V}orlesungsmitschrift",
year = "1997",
}
@misc{Hudelson1998,
author = "M. Hudelson",
title = "Graph {T}heory (\textit{{M}ath 453}), {F}all {S}emester, {W}ashington {S}tate {U}niversity, {V}orlesungsmitschrift",
year = "1998",
}
@book{Russel,
author = "S. Russell and P. Norvig",
title = "Artificial Intelligence, A Modern Approach",
year = "1995",
publisher = "Prentice Hall, Inc.",
address = "Upper Sanddle River, NJ, USA",
}
@book{Arnold,
author = "V. Arnold",
title = "Gewöhnliche Differentialgleichungen",
year = "2001",
publisher = "Springer Verlag",
address = "Berlin Heidelberg",
}
@book{Heuser,
author = "H. Heuser",
title = "Gewöhnliche Differentialgleichungen : Einführung in Lehre und Gebrauch",
year = "1989",
publisher = "Teubner",
address = "Stuttgart",
}
@book{Orourke,
author = "J. O'Rourke",
title = "Art Gallery Theorems and Algorithms",
year = "1987",
publisher = "Oxford University Press",
}
@book{Cormen,
author = "Th. Cormen and Ch. Leiserson and R. Rivest",
title = "Introduction to Algorithms",
year = "1997",
publisher = "McGraw--Hill Book Company",
address = " ",
}
@book{Orear,
author = "J. Orear",
title = "Physik",
year = "1991",
publisher = "Weltbild Verlag GmbH",
address = "Augsburg"
}
@book{Fischer,
author = "G. Fischer",
title = "{L}ineare {A}lgebra",
year = "1995",
publisher = "Friedrich Vieweg \& Sohn Verglagsgesellschaft mbH",
address = "Braunschweig / Wiesbaden",
}
@book{Forster,
author = "O. Forster",
title = "{A}nalysis 1",
year = "1996",
publisher = "Friedrich Vieweg \& Sohn Verglagsgesellschaft mbH",
address = "Braunschweig / Wiesbaden",
}
@book{Deuflhard,
author = "P. Deuflhard and A. Hohmann",
title = "{N}umerische {M}athematik --- {E}ine algorithmisch orientierte {E}inführung",
year = "1993",
publisher = "Walter de Gruyter Co.",
address = "Berlin",
}
@article{Horn_1987,
author = "B. K. P. Horn",
title = "Closed--form solution of absolute orientation using unit quaternions",
journal = "Journal of the Optical Society of America A",
month = "April",
year = "1987",
volume = "4",
number = "4",
pages = "629 -- 642"
}
@article{Horn_1988,
author = "B. K. P. Horn and H. M. Hilden and Sh. Negahdaripour",
title = "Closed--form solution of absolute orientation using orthonormal matrices",
journal = "Journal of the Optical Society of America A",
month = "July",
year = "1988",
volume = "5",
number = "7",
pages = "1127 -- 1135"
}
@article{Besl_1992,
author = "P. Besl and N. McKay",
title = "A method for {R}egistration of 3--{D} {S}hapes",
journal = "IEEE Transactions on Pattern Analysis and Machine Intelligence",
month = "February",
year = "1992",
volume = "14",
number = "2",
pages = "239 -- 256"
}
@article{Shermer_1992,
author = "T. Shermer",
title = "{R}ecent {R}esults in {A}rt {G}alleries",
journal = "Proceedings of the IEEE",
month = "September",
year = "1992",
volume = "80",
number = "9",
pages = "1384 -- 1399"
}
@InProceedings{Chen_1991,
author = "Y. Chen and G. Medioni",
title = "{O}bject {M}odelling by {R}egistration of {M}ultiple {Range} {I}mages",
booktitle = "Proceedings of the IEEE Conference on Robotics and Automation (ICRA '91)",
month = "April",
year = "1991",
address = "Sacramento, CA, USA",
pages = "2724 -- 2729",
}
@InProceedings{Hebert_2001,
author = "M. Hebert and M. Deans and D. Huber and B. Nabbe and N. Vandapel",
title = "Progress in 3--{D} {M}apping and {L}ocalization",
booktitle = "Proceedings of the 9th International Symposium on Intelligent Robotic Systems, (SIRS '01)",
month = "July",
year = "2001",
address = "Toulouse, France"
}
@InProceedings{Sappa_2001,
author = "A. Sappa and A. Restrepo-Specht and M. Devy",
title = "Range {I}mage {R}egistration by using an {E}dge--based {R}epresentation",
booktitle = "Proceedings of th 9th International Symposium on Intelligent Robotic Systems, (SIRS '01)",
month = "July",
year = "2001",
address = "Toulouse, France"
}
@inproceedings{Simon_1994,
author = "D. Simon and M. Hebert and T. Kanade",
title = "Real--time 3--{D} pose estimation using a high--speed range sensor",
booktitle = "Proceedings of IEEE International Conference on Robotics and Automation (ICRA '94)",
month = "May",
year = "1994",
volume = "3",
pages = "2235 -- 2241",
address = "San Diego, CA, USA"
}
@inproceedings{Huber_2000,
author = "D. Huber and O. Carmichael and M. Hebert",
title = "3{D} map reconstruction from range data",
booktitle = "Proceedings of the IEEE International Conference on Robotics and Automation (ICRA '00)",
month = "April",
year = "2000",
volume = "1",
pages = "891 -- 897",
address = "San Francisco, CA, USA"
}
@article{Johnson_1999,
author = "A. E. Johnson and M. Hebert",
title = "Using spin images for efficient object recognition in cluttered 3{D} scenes",
journal = "IEEE Transactions on Pattern Analysis and Machine Intelligence",
month = "May",
year = "1999",
volume = "21",
number = "5",
pages = "433 -- 449"
}
@InProceedings{Johnson_1998,
author = {A. E. Johnson and M. Hebert},
title = {Efficient multiple model recognition in cluttered {3-D}scenes},
booktitle = {Proceedings of the IEEE International Conference on Computer Vision and Pattern Recognition (CVPR' 98)},
pages = {671 -- 677},
year = {1998},
address = {Santa Barbara, CA, U.S.A.},
month = {June}
}
@inproceedings{Huber_2001,
author = "D. Huber",
title = "Automatic 3{D} {M}odeling {U}sing {R}ange {I}mages {O}btained from {U}nknown {V}iewpoints",
booktitle = "Proceedings of the Third International Conference on 3D Digital Imaging and Modeling (3DIM '01)",
month = "May",
year = "2001",
pages = "153 -- 160",
address = "Quebec City, Canada",
}
@inproceedings{Huber_1999,
author = "D. Huber and M. Hebert",
title = "A {N}ew {A}pproach to 3--{D} {T}errain {M}apping",
booktitle = "Proceedings of the 1999 IEEE/RSJ International Conference on Intelligent Robotics and Systems (IROS '99)",
month = "October",
year = "1999",
pages = "1121 -- 1127",
publisher = "IEEE",
address = "Kyonjyu, Korea"
}
@techreport{Zhang_1992,
author = "Z. Zhang",
title = "Iterative point matching for registration of free--form curves",
number = "RR-1658",
year = "1992",
institution = "INRIA--Sophia Antipolis",
address = "Valbonne Cedex, France",
url = "citeseer.nj.nec.com/zhang92iterative.html"
}
@inproceedings{Schroeder_1998,
author="W. Schr{"o}der and E. Forgber and G. R{"o}h",
title = "{L}aser range camera applications",
booktitle = "Proceedings of the 5th ESA Workshop on Advanced Space Technologies for Robot Applications",
month = "December",
year = "1998",
address = "Noordwijk, The Netherlands"
}
@article{Lange_2001,
author="R. Lange and P. Seitz",
title = "{S}olid-state time-of-flight range camera",
journal = "IEEE Journal of Quantum Electronics",
month = "March",
year = "2001",
volume = "37",
number = "3",
}
@inproceedings{Banos_1998,
author="H. Gonzales-Banos and J. Latombe",
title = "Planning {R}obot {M}otions for {R}ange--{I}mage {A}cqusition and {A}utomatic 3{D} {M}odel {C}onstruction",
booktitle = "Proceedings of AAAI Fall Symposium",
month = "October",
year = "1998",
publisher = "AAAI Press",
address = "Menlo Park, CA, USA"
}
@inproceedings{Banos_2000,
author="H. Gonzalez-Banos and E. Mao and J.C. Latombe and T.M. Murali and A. Efrat",
title = "Planning {R}obot {M}otion {S}trategies for {E}fficient {M}odel {C}onstruction",
booktitle = "Robotics Research -- The 9th International Symposium (ISRR'99)",
year = "2000",
publisher = "Springer",
pages = "345 -- 352",
editor = "J. Hollerbach and D. Koditschek"
}
@inproceedings{Banta_1995,
author="J. Banta and Y. Zhieng and X. Wang and G. Zhang and M. Smith and M. Abidi",
title = "A ``{B}est--{N}ext--{V}iew'' {A}lgorithm for {T}hree--{D}imensional {S}cene {R}econstruction {U}sing {R}ange {I}mages",
booktitle = "Proceedings SPIE (Intelligent Robots and Computer Vision XIV: Algorithms), vol 2588",
year = "1995",
editor = "D. Casasent",
pages = "418 -- 429"
}
@inproceedings{Thrun_2000,
author="S. Thrun and D. Fox and W. Burgard",
title = "A real-time algorithm for mobile robot mapping with application to multi robot and 3{D} mapping",
booktitle = "Proceedings of the IEEE International Conference on Robotics and Automation (ICRA '00)",
month = "April",
year = "2000",
address = "San Francisco, CA, USA",
}
@article{Thrun_2001,
author="S. Thrun and D. Fox and W. Burgard and F. Dellaert",
title = "{R}obust {M}onte {C}arlo {L}ocalization for {M}obile {R}obots",
journal = "Artificial Intelligence",
year = "2001",
month = "Summer",
}
@inproceedings{Haehnel_2001,
author="D. H{\"a}hnel and W. Burgard and S. Thrun",
title = "Learning {C}ompact 3{D} {M}odels of {I}ndoor and {O}utdoor {E}nvironments with a {M}obile {R}obot",
booktitle = "Proceedings of the fourth European workshop on advanced mobile robots (EUROBOT '01)",
month = "September",
year = "2001",
address = "Lund, Sweden",
}
@inproceedings{Haehnel_2002,
author="D. H{"a}hnel and W. Burgard",
title = "{P}robabilistic {M}atching for {3D} {S}can {R}egistration",
booktitle = "Proceedings of the second German conference on robotics (ROBOTIK '02)",
month = "June",
year = "2002",
address = "Ludwigsburg, Germany",
}
@inproceedings{Rusi_2001,
author="S. Rusinkiewicz and M. Levoy",
title = "Efficient variants of the {ICP} algorithm",
booktitle = "Proceedings of the Third International Conference on 3D Digital Imaging and Modellling (3DIM '01)",
month = "May",
year = "2001",
address = "Quebec City, Canada",
pages = "145 -- 152",
}
@inproceedings{Lorusso_1995,
author = "A. Lorusso and D. Eggert and R. Fisher",
title = "A {C}omparison of {F}our {A}lgorithms for {E}stimating 3-{D} {R}igid {T}ransformations",
Booktitle = "Proceedings of the 4th British Machine Vision Conference (BMVC '95)",
pages = "237 -- 246",
address = "Birmingham, England",
month = "September",
year = "1995",
url = "citeseer.nj.nec.com/lorusso95comparison.html"
}
@article{Curless_1996,
author = "B. Curless and M. Levoy",
title = "A {V}olumetric {M}ethod for {B}uilding {C}omplex {M}odels from {R}ange {I}mages",
journal = "Computer Graphics",
volume = "30",
number = "{Annual Conference Series}",
pages = "303 -- 312",
year = "1996",
url = "citeseer.nj.nec.com/curless96volumetric.html"
}
@inproceedings{Banos_2001,
author = "H. Gonzalez-Banos and J. Latombe",
title = "A {R}andomized {A}rt-{G}allery {A}lgorithm for {S}ensor {P}lacement",
booktitle = "Proceedings of ACM Symposium on Computational Geometry (SoCG'01)",
month = "June",
year = "2001",
address = "Medford, MA, USA"
}
@inproceedings{Latombe_2000,
author = "H. Gonzalez-Banos and J. Latombe",
title = "Robot {N}avigation for {A}utomatic {M}odel {C}onstruction {U}sing {S}afe {R}egions",
booktitle = "Lecture Notes in Control and Information Sciences, 271, (Proceedings of International Symposium on Experimental Robotics (ISER '00))",
month = "December",
year = "2000",
address = "Waikiki, HI, USA",
editor = "D. Russ and S. Singh",
pages = "405 -- 415",
publisher = "Springer",
}
@phdthesis{Verbeek_2001,
author = "Chr. Verbeek",
title = "Reaktive {S}teuerung autonomer mobiler {R}oboter",
school = "Technische Fakult{\"a}t der {U}niversit{\"a}t Bielefeld",
month = "January",
year = "2001",
}
@inproceedings{Pulli_1997,
author = "K. Pulli and T. Duchamp and H. Hoppe and J. McDonald and L. Shapiro and W. Stuetzle",
title = "Robust meshes from multiple range maps",
booktitle = "Proceedings IEEE International Conference on Recent Advances in 3D Digital Imaging and Modeling (3DIM '97)",
address = "Ottawa, Canada",
month = "May",
year = "1997",
url = "citeseer.nj.nec.com/pulli97robust.html"
}
@inproceedings{Benjemaa_1997,
author = "R. Benjemaa and F. Schmitt",
title = "{F}ast {G}lobal {R}egistration of {3D} {S}ampled {S}urfaces {U}sing a {M}ulti-{Z}-{B}uffer {T}echnique",
booktitle = "Proceedings IEEE International Conference on Recent Advances in 3D Digital Imaging and Modeling (3DIM '97)",
address = "Ottawa, Canada",
month = "May",
year = "1997",
}
@article{Hoppe_1992,
author = "H. Hoppe and T. DeRose and T. Duchamp and J. McDonald and W. Stuetzle",
title = "Surface reconstruction from unorganized points",
journal = "Computer Graphics",
volume = "26",
number = "2",
pages = "71 -- 78",
year = "1992",
url = "citeseer.nj.nec.com/hoppe92surface.html"
}
@misc{City_2001,
author = "City Project Page",
title = "\texttt{http://graphics.lcs.mit.edu/city/city.html}",
year = "2001"
}
@misc{Bahnplanung_2001,
author = "R. Klein and Chr. Icking and E. Langetepe",
title = "Entwicklung, {A}nalyse und experimentelle {E}rprobung von kompetitiven {A}lgorithmen f{\"u}r die {B}ahnplanung autonomer {S}ysteme, \texttt{http://web.informatik.uni-bonn.de/I/research/dfg-bahnplanung/}",
year = "2001"
}
@article{Hoffmann_2002,
author ="F. Hoffmann and Chr. Icking and R. Klein and K. Kriegel",
title = "The Polygon Exploration Problem",
journal = "SIAM Journal on Computing",
volume = "31",
number = "2",
pages = "577--600",
year = "2002",
url = "citeseer.nj.nec.com/493716.html"
}
@inproceedings{Stamos_2000,
author = "I. Stamos and P. Allen",
title = "3-{D} {M}odel {C}onstruction {U}sing {R}ange and {I}mage {D}ata",
booktitle = "Proceedings of the Conference on Computer Vision and Pattern Recognition (CVPR '00)",
month = "June",
year = "2000",
address = "USA"
}
@inproceedings{Allen_2001,
author = "P. Allen and I. Stamos and A. Gueorguiev and E. Gold and P. Blaer",
title = "{AVENUE:} {A}utomated {S}ite {M}odelling in {U}rban {E}nvironments",
booktitle = "Proceedings of the Third International Conference on 3D Digital Imaging and Modeling (3DIM '01)",
month = "May",
year = "2001",
address = "Quebec City, Canada",
}
@inproceedings{Gueorguiev_2000,
author = "A. Gueorguiev and P. Allen and E. Gold and P. Blaer",
title = "{D}esign, {A}rcitecture and {C}ontrol of a {M}obile Site-{M}odelling {R}obot",
booktitle = "Proceedings of the IEEE International Conference on Robotics and Automation (ICRA '00)",
month = "April",
year = "2000",
address = "San Francisco, CA, USA"
}
@inproceedings{Allen_1998,
author = "P. Allen and M. Reed and I. Stamos",
title = "View {P}lanning for {S}ite {M}odeling",
booktitle = "Proceedings of the DARPA Image Understanding Workshop",
address = "Monterey",
month = "November",
year = "1998"
}
@inproceedings{Reed_1997,
author = "M. Reed and P. Allen and I. Stamos",
title = "Automated {M}odel {A}cquisition from {R}ange {I}mages with {V}iew {P}lanning",
booktitle = "Proceedings of the Conference on Computer Vision and Pattern Recognition (CVPR '97)",
address = "Puerto Rico",
year = " 1997",
}
@article{Reed_1999,
author ="M. Reed and P. Allen",
title = "3-{D} {M}odeling from {R}ange {I}magery: {A}n {I}ncremental {M}ethod with a {P}lanning {C}omponent",
journal = "{I}mage and {V}ision {C}omputing",
volume = "17",
pages = "99 -- 111",
year = "1999"
}
@inproceedings{Yang_1998,
author = "P. Allen and R. Yang",
title = "Registering, {I}ntegrating, and {B}uilding {CAD} {M}odels from {R}ange {D}ata",
booktitle = "Proceedings of the IEEE International Conference on Robotics and Automation (ICRA '98)",
month = "May",
year = "1998",
address = "Leuven, Belgium",
}
@misc{matrixfaq,
author = "Matrix FAQ",
title = "Version 2, \texttt{http://skal.planet-d.net/demo/matrixfaq.htm}",
year = "1997"
}
@techreport{Dam_1998,
author = "E. Dam and M. Koch and M. Lillholm",
title = "{Q}uaternion, {I}nterpolation and {A}nimation",
number = "DIKU-TR-98/5",
year = "1998",
institution = "Department of Computer Science University of Copenhagen",
address = "Copenhagen, Denmark",
}
@article{Hart_1994,
author ="J. Hart and G. Francis and L. Kauffmann",
title = "{V}isualizing {Q}uaternion {Rotation}",
journal = "{ACM} {T}ransactions on {G}raphics",
volume = "13",
pages = "256 -- 276",
year = "1994",
month = "July",
}
@inproceedings{Pervin_1983,
author = "E. Pervin and J. Webb",
title = "{Q}uaternions for computer vision and robotics",
booktitle = "Proceedings of the Conference on Computer Vision and Pattern Recognition (CVPR '83)",
address = "Washington, D.C., USA",
year = " 1983",
}
@misc{Hamilton,
author = "Sir William Rowan Hamilton (1805-1865)",
title = "\texttt{http://www.maths.tcd.ie/pub/{H}istMath/ {P}eople/{H}amilton/}",
year = "2000"
}
@inproceedings{Hamilton_1843,
author = "W. Hamilton",
title = "{O}n a new {S}pecies of {I}maginary {Q}uantities connected with a theory of {Q}uaternions",
booktitle = "Proceedings of the Royal Irish Academy",
month = "November",
address = "Dublin, Ireland",
year = " 1843",
}
@article{Eggert_1998,
author ="D. Eggert and A. Fitzgibbon and R. Fisher",
title = "{S}imultaneous {R}egistration of {M}ultiple {R}ange {V}iews {S}atisfying {G}lobal {C}onsistency {C}onstraints For {U}se {I}n {R}everse {E}ngineering",
journal = "{C}omputer {V}ision and {I}mage {U}nderstanding",
volume = "69",
pages = "253 -- 272",
year = "1998",
month = "March",
}
@inproceedings{Michelangelo_2000,
author = "M. Levoy and K. Pulli and B. Curless and S. Rusinkiewicz and D. Koller and L. Pereira and M. Ginzton and S. Anerson and J. Davis and J. Ginsberg and J. Shade and D. Fulk",
title = "{T}he {D}igital {M}ichelangelo {P}roject: {3D} {S}canning of {L}arge {S}tatues",
booktitle = "Proceedings of the ACM SIGGRAPH",
year = "2000",
address = "New Orleans, USA",
month = "July",
}
@inproceedings{Pulli_1999,
author = "K. Pulli",
title = "{M}ultiview {R}egistration for {L}arge {D}ata {S}ets",
booktitle = "Proceedings of the 2nd International Conference on 3D Digital Imaging and Modeling (3DIM '99)",
address = "Ottawa, Canada",
year = "1999",
month = "October",
pages = "160 -- 168",
}
@inproceedings{Stoddart_1996,
author = "A. Stoddart and A. Hilton",
title = "{R}egistration of multiple point sets",
booktitle = "Proceedings of the 13th IAPR International Conference on Pattern Recognition",
year = "1996",
pages = "40--44",
address = "Vienna, Austria",
month = "August",
}
@inproceedings{Cunnington_1999,
author = "S. Cunnington and A. Stoddart",
title = "{N}-{V}iew {P}oint {S}et {R}egistration: {A} {C}omparison",
Booktitle = "Proceedings of the 10th British Machine Vision Conference (BMVC '99)",
year = "1999",
address = "Nottingham, UK.",
url = "citeseer.nj.nec.com/319525.html"
}
@article{Blais_1995,
author ="G. Blais and D. Levine",
title = "{R}egistration {M}ultiview {R}ange {D}ata to {C}reate 3{D} {C}omputer {O}bjects",
journal = "{P}attern {A}nalysis and {M}achine {I}ntelligence",
volume = "17",
number ="8",
pages = "820 -- 824",
year = "1995",
month = "August",
}
@article{Benjemaa_1998,
author ="R. Benjemaas and F. Schmitt",
title = "{A} {S}olution {F}or {T}he {R}egistration {O}f {M}ultiple 3{D} {P}oint {S}ets {U}sing {U}nit {Q}uaternions",
journal = "{C}omputer {V}ision -- ECCV '98",
volume = "2",
pages = "34 -- 50",
year = "1998",
publisher = "Springer Verlag",
}
@inproceedings{Frueh_2001_1,
author = "C. Fr{\"u}h and A. Zakhor",
title = "3{D} {M}odel {G}eneration for {C}ities {U}sing {A}erial {P}hotographs and {G}round {L}evel {L}aser {S}cans",
Booktitle = "Proceedings of the Computer Vision and Pattern Recognition Conference (CVPR '01)",
year = "2001",
month = "December",
address = "Kauai, Hawaii, USA",
}
@inproceedings{Frueh_2001_2,
author = "C. Fr{\"u}h and A. Zakhor",
title = "{F}ast 3{D} {M}odel {G}eneration in {U}rban {E}nvironments",
Booktitle = "Proceedings of the 4th International Conference on Multisensor Fusion and Integration for Intelligent Systems (MFI '01)",
year = "2001",
month = "August",
address = "Baden Baden, Germany",
}
@inproceedings{Sequeira_1999,
author = "V. Sequeira and K. Ng and E. Wolfart and J. Goncalves and D. Hogg",
title = "{A}utomated {3D} reconstruction of interiors with multiple scan--views",
booktitle = "Proceedings of SPIE, Electronic Imaging '99, The Society for Imaging Science and Technology /SPIE's 11th Annual Symposium",
year = "1999",
address = "San Jose, CA, USA",
month = "January",
}
@Article{Sequeira_1995,
author= "V. Sequeira and J. Goncalves and M. Ribeiro",
title = "{3D} environment modelling using laser range sensing",
year = "1995",
journal = "Robotics and Automation",
pages = "81 -- 91",
volume = "16",
publisher = "Elsevier",
}
@inproceedings{Sappa_2000,
author = "A. Sappa and M. Devy and M. Garcia",
title = "{M}odelling {B}uilt {E}nvironments from {L}arge {R}ange {I}mages using {A}daptive {T}riangular {M}eshes",
booktitle = "Proceedings of the 8th International Symposium on Intelligent Robotic Systems, (SIRS '00)",
year = "2000",
address = "Reading, United Kingdom",
month = "July",
pages = "23 -- 29"
}
@inproceedings{Garcia_2000,
author = "A. Sappa and M. Garcia",
title = "{I}ncremental {M}ultiview {I}ntegration of {R}ange {I}mages",
booktitle = "Proceedings of the 15th IAPR International Conference on Pattern Recognition",
year = "2000",
pages = "546 -- 549",
address = "Barcelona, Spain",
month = "September",
}
@inproceedings{Garcia_1998,
author = "M. Garcia and S. Velazquez and A. Sappa",
title = "{A} {T}wo--{S}tage {A}lgorithm for {P}lanning the {N}ext {V}iew {F}rom {R}ange {I}mages",
Booktitle = "Proceedings of the 9th British Machine Vision Conference (BMVC '98)",
pages = "720 -- 729",
address = "Southampton, United Kingdom",
year = "1998",
}
@inproceedings{Huber_2001_1,
author = "Daniel F. Huber and Martial Hebert",
title = "Fully Automatic Registration of Multiple 3D Data Sets",
booktitle = "IEEE Computer Society Workshop on Computer Vision Beyond the Visible Spectrum (CVBVS '01)",
month = "December",
year = "2001"
}
@inproceedings{Turk_1994,
author = "G. Turk and M. Levoy",
title = "{Z}ippered polygon meshes from range images",
booktitle = "Proceedings of the ACM SIGGRAPH '94",
year = "1994",
address = "Orlando, FL, USA",
month = "July",
pages = "311 -- 318",
}
@inproceedings{Zhao_2001,
author = "H. Zhao and R. Shibasaki",
title = "{R}econstructing {T}extured {CAD} {M}odel of {U}rban {E}nvironment {U}sing {V}ehicle-{B}orne {L}aser {R}ange {S}canners and {L}ine {C}ameras",
booktitle = "Second International Workshop on Computer Vision System (ICVS '01)",
year = "2001",
address = "Vancouver, Canada",
month = "July",
pages = "284 -- 295",
}
@article{Zhao_2000,
author = "H. Zhao and R. Shibasaki",
title = "{R}econstruction of {T}extured Urban {3D} {M}odel by {G}round-{B}ased {L}aser {R}ange and {CCD} {I}mages",
journal = "IEICE Transactions on Information and Systems",
volume = "E38-D",
number ="7",
pages = ".1429 -- 1440",
year = "2000",
}
@inproceedings{Indiveri_1999,
author = "G. Indiveri",
title = "{K}inematic {T}ime-invariant {C}ontrol of a {2D} {N}onholonomic {V}ehicle",
booktitle = "Proceedings of the 38th Conference on Decision and Control, (CDC '99)",
address = "Phoenix, USA",
month = "December",
year = "1999",
}
@article{Carlsson_1999,
author ="S. Carlsson and B. Nilsson",
title = "{C}omputing {V}ision {P}oints in {P}olygons",
journal = "{A}lgorithmica",
volume = "24",
number ="1",
pages = "50 -- 75",
year = "1999",
}
@article{Vatti_1992,
author ="B. Vatti",
title = "{A} {G}eneric {S}olution to {P}olygon {C}lipping",
journal = "{C}ommunications of the {ACM}",
volume = "35",
number ="7",
pages = "56 -- 63",
year = "1992",
}
@article{Amenta_2001,
author ="N. Amenta and S. Choi and R. Kolluri",
title = "{T}he {P}ower {C}rust",
journal = "{C}ommunications of the {ACM}",
volume = "35",
number ="7",
pages = "56 -- 63",
year = "2001",
}
@article{Prytherch_2002,
author ="D. Prytherch and M. McLundie",
title = "{S}o what is haptics anyway?",
journal = "{R}esearch issues in {A}rt {D}esign and {M}edia",
publisher = "{T}he {R}esearch {T}raining {I}nitiative",
volume = "Spring",
number ="2",
pages = "1 -- 16",
year = "2002",
}
@book{Streri_2002,
author = "A. Streri",
title = "Seeing, Reaching, and touching (cited through \cite{Gonz_1998}) ",
publisher = "The MIT Press",
address = "Cambridge, MA, USA",
year = "1993",
}
@inproceedings{Gonz_1998,
author = "L. Goncalves and R. Grupen and A. Oliveira",
title = "{A} {C}ontrol {A}rchitecture for {M}ulti-modal {S}ensory {I}ntegration",
booktitle = "Proceedings of the 9th IEEE International Conference on Computer Graphics and Image Processing (SIBGRAPH '98)",
year = "1998",
month = "October",
address = "Rio de Janeiro, RJ, Brazil",
}
@incollection{Bern_2000,
author = "M. Bern and P. Plassmann",
title = "Mesh Generation",
booktitle = "Handbook of Computational Geometry",
publisher = "Elsevier Science",
editor = "J. Sack and J. Urrutia",
year = "2000",
url = "citeseer.nj.nec.com/bern00mesh.html"
}
@misc{WDR,
author = "WDR",
title = "{L}eonardo {S}chwerpunkt {H}aptik \texttt{http://capehorn.gmd.de:8080/download/haptik/\linebreak haptik.mp3}"
}
@misc{CAMERA,
author = "CAMERA: CAd Modelling of Built Environments from Range Analysis",
title = "\texttt{http://www.dai.ed.ac.uk/homes/rbf/{CAMERA}/camera.htm}",
year = "2000"
}
@misc{RESOLV,
author = "{The ACTS RESOLV (REconstruction using Scanned Laser and Video) Project}",
title = "\texttt{http://www.comp.leeds.ac.uk/resolv/}",
year = "1999"
}
@misc{RIEGLold,
author = "RIEGL Laser Measurement Systems GmbH",
title = "\texttt{http://www.riegl.co.at/}",
year = "2001"
}
@misc{AVENUE,
author = "{AVENUE (Autonomous Vehicle for Exploration and Navigation in Urban Environments) Project}",
title = "\texttt{http://www.cs.columbia.edu/} \texttt{robotics/projects/avenue/}",
year = "2001"
}
@misc{3DMAP,
author = "3D Terrain Mapping Using Range Sensors",
title = "\texttt{http://www-2.cs.cmu.edu/$\sim$dhuber/ mapping/}",
year = "1999"
}
@misc{URLTHRUN,
author = "CMU's 3D Robot Mapping Project",
title = "\texttt{http://www-2.cs.cmu.edu/$\sim$thrun/3D/index.html}",
year = "2000"
}
@misc{3DFAX,
author = "Project to build a 3D fax machine",
title = "\texttt{http://graphics.stanford.edu/projects/faxing/}",
year = "2001"
}
@misc{LYAPUNOV,
author = "The Lyapunov Function, Wolfram Research{,}",
title = "\texttt{http://mathworld.wolfram.com/Lyapunov\linebreak Function.html}",
year = "2002"
}
@misc{CLAY,
author = "Clay Mathematics Institute",
title = "\texttt{http://www.claymath.org/prizeproblems/index.htm}",
month = "May",
year = "2000"
}
@misc{POWERCRUST,
author = "The Power Crust",
title = "\texttt{http://www.cs.utexas.edu/users/amenta/powercrust/}",
year = "2002"
}
@misc{INTRO,
author = "MIT's Bouncing Baby Robot?",
title = "\texttt{http://www.controleng.com/archives/2000/ctl0101.00\linebreak /000101w1.htm}",
year = "2000"
}
@misc{SIEMENS3D,
author = "Siemens 3D-Sensor",
title = "http://w4.siemens.de/FuI/de/archiv/newworld/heft2\_01/artikel03/",
year = "2001",
}

@ -0,0 +1,199 @@
//----------------------------------------------------------------------
// File: ANN.cpp
// Programmer: Sunil Arya and David Mount
// Description: Methods for ANN.h and ANNx.h
// Last modified: 01/04/05 (Version 1.0)
//----------------------------------------------------------------------
// Copyright (c) 1997-2005 University of Maryland and Sunil Arya and
// David Mount. All Rights Reserved.
//
// This software and related documentation is part of the Approximate
// Nearest Neighbor Library (ANN). This software is provided under
// the provisions of the Lesser GNU Public License (LGPL). See the
// file ../ReadMe.txt for further information.
//
// The University of Maryland (U.M.) and the authors make no
// representations about the suitability or fitness of this software for
// any purpose. It is provided "as is" without express or implied
// warranty.
//----------------------------------------------------------------------
// History:
// Revision 0.1 03/04/98
// Initial release
// Revision 1.0 04/01/05
// Added performance counting to annDist()
//----------------------------------------------------------------------
#include <stdlib.h>
#include <ANN/ANNx.h> // all ANN includes
#include <ANN/ANNperf.h> // ANN performance
using namespace std; // make std:: accessible
//----------------------------------------------------------------------
// Point methods
//----------------------------------------------------------------------
//----------------------------------------------------------------------
// Distance utility.
// (Note: In the nearest neighbor search, most distances are
// computed using partial distance calculations, not this
// procedure.)
//----------------------------------------------------------------------
ANNdist annDist( // interpoint squared distance
int dim,
ANNpoint p,
ANNpoint q)
{
register int d;
register ANNcoord diff;
register ANNcoord dist;
dist = 0;
for (d = 0; d < dim; d++) {
diff = p[d] - q[d];
dist = ANN_SUM(dist, ANN_POW(diff));
}
ANN_FLOP(3*dim) // performance counts
ANN_PTS(1)
ANN_COORD(dim)
return dist;
}
//----------------------------------------------------------------------
// annPrintPoint() prints a point to a given output stream.
//----------------------------------------------------------------------
void annPrintPt( // print a point
ANNpoint pt, // the point
int dim, // the dimension
std::ostream &out) // output stream
{
for (int j = 0; j < dim; j++) {
out << pt[j];
if (j < dim-1) out << " ";
}
}
//----------------------------------------------------------------------
// Point allocation/deallocation:
//
// Because points (somewhat like strings in C) are stored
// as pointers. Consequently, creating and destroying
// copies of points may require storage allocation. These
// procedures do this.
//
// annAllocPt() and annDeallocPt() allocate a deallocate
// storage for a single point, and return a pointer to it.
//
// annAllocPts() allocates an array of points as well a place
// to store their coordinates, and initializes the points to
// point to their respective coordinates. It allocates point
// storage in a contiguous block large enough to store all the
// points. It performs no initialization.
//
// annDeallocPts() should only be used on point arrays allocated
// by annAllocPts since it assumes that points are allocated in
// a block.
//
// annCopyPt() copies a point taking care to allocate storage
// for the new point.
//
// annAssignRect() assigns the coordinates of one rectangle to
// another. The two rectangles must have the same dimension
// (and it is not possible to test this here).
//----------------------------------------------------------------------
ANNpoint annAllocPt(int dim, ANNcoord c) // allocate 1 point
{
ANNpoint p = new ANNcoord[dim];
for (int i = 0; i < dim; i++) p[i] = c;
return p;
}
ANNpointArray annAllocPts(int n, int dim) // allocate n pts in dim
{
ANNpointArray pa = new ANNpoint[n]; // allocate points
ANNpoint p = new ANNcoord[n*dim]; // allocate space for coords
for (int i = 0; i < n; i++) {
pa[i] = &(p[i*dim]);
}
return pa;
}
void annDeallocPt(ANNpoint &p) // deallocate 1 point
{
delete [] p;
p = NULL;
}
void annDeallocPts(ANNpointArray &pa) // deallocate points
{
delete [] pa[0]; // dealloc coordinate storage
delete [] pa; // dealloc points
pa = NULL;
}
ANNpoint annCopyPt(int dim, ANNpoint source) // copy point
{
ANNpoint p = new ANNcoord[dim];
for (int i = 0; i < dim; i++) p[i] = source[i];
return p;
}
// assign one rect to another
void annAssignRect(int dim, ANNorthRect &dest, const ANNorthRect &source)
{
for (int i = 0; i < dim; i++) {
dest.lo[i] = source.lo[i];
dest.hi[i] = source.hi[i];
}
}
// is point inside rectangle?
ANNbool ANNorthRect::inside(int dim, ANNpoint p)
{
for (int i = 0; i < dim; i++) {
if (p[i] < lo[i] || p[i] > hi[i]) return ANNfalse;
}
return ANNtrue;
}
//----------------------------------------------------------------------
// Error handler
//----------------------------------------------------------------------
void annError(char *msg, ANNerr level)
{
if (level == ANNabort) {
cerr << "ANN: ERROR------->" << msg << "<-------------ERROR\n";
exit(1);
}
else {
cerr << "ANN: WARNING----->" << msg << "<-------------WARNING\n";
}
}
//----------------------------------------------------------------------
// Limit on number of points visited
// We have an option for terminating the search early if the
// number of points visited exceeds some threshold. If the
// threshold is 0 (its default) this means there is no limit
// and the algorithm applies its normal termination condition.
// This is for applications where there are real time constraints
// on the running time of the algorithm.
//----------------------------------------------------------------------
int ANNmaxPtsVisited = 0; // maximum number of pts visited
int ANNptsVisited; // number of pts visited in search
//----------------------------------------------------------------------
// Global function declarations
//----------------------------------------------------------------------
void annMaxPtsVisit( // set limit on max. pts to visit in search
int maxPts) // the limit
{
ANNmaxPtsVisited = maxPts;
}

@ -0,0 +1,96 @@
/**
* @file
* @brief
*
* @author Thomas Escher
*/
#ifndef MULTI_ARRAY_H
#define MULTI_ARRAY_H
#include <iostream>
using std::cout;
using std::cerr;
using std::endl;
#include "scanserver/cache/cacheDataAccess.h"
/**
* @brief Point-Array imitation for xyz[i][0..2] calls
*/
template<typename return_type>
class TripleArray : public CacheDataAccess {
public:
//! Take ownership of a cache data
TripleArray(CacheDataAccess&& cd) : CacheDataAccess(cd) {}
//! Move constructor of this type like CacheData, transfer lock
TripleArray(TripleArray&& other) : CacheDataAccess(other) {}
//! Represent the CacheData as an array of T[3]'s
inline return_type* operator[](unsigned int i) const
{
return reinterpret_cast<return_type*>(getData()) + (i*3);
}
//! Count of T[3] objects in this CacheData
inline unsigned int size() const { return CacheDataAccess::getSize() / (3*sizeof(return_type)); }
};
/**
* @brief Point-Array imitation for value[i] calls
*/
template<typename return_type>
class SingleArray : public CacheDataAccess {
public:
//! Take ownership of a cache data
SingleArray(CacheDataAccess&& cd) : CacheDataAccess(cd) {}
//! Move constructor of this type like CacheData, transfer lock
SingleArray(SingleArray&& other) : CacheDataAccess(other) {}
//! Represent the CacheData as an array of T's
inline return_type& operator[](unsigned int i) const
{
return *(reinterpret_cast<return_type*>(getData()) + i);
}
//! Count of T objects in this CacheData
inline unsigned int size() const { return CacheDataAccess::getSize() / sizeof(return_type); }
};
typedef TripleArray<double> DataXYZ;
typedef TripleArray<unsigned char> DataRGB;
typedef SingleArray<float> DataReflectance;
typedef SingleArray<float> DataAmplitude;
typedef SingleArray<int> DataType;
typedef SingleArray<float> DataDeviation;
/**
* To simplify T** access patterns for an array of T[3] (points), this RAII type class helps creating and managing this pointer array on the stack.
*/
template<typename T>
class Array {
public:
//! Create a temporary array and fill it sequentially with pointers to each point
Array(const TripleArray<T>& data) {
unsigned int size = data.size();
m_array = new T*[size];
for(unsigned int i = 0; i < size; ++i)
m_array[i] = data[i];
}
//! Removes the temporary array on destruction (RAII)
~Array() {
delete[] m_array;
}
//! Conversion operator to interface the MultiArray to a T** array
inline T* const* get() const { return m_array; }
private:
T** m_array;
};
#endif //MULTI_ARRAY_H

@ -0,0 +1,56 @@
int glui_img_leftarrow[] = { 16, 16, /* width, height */
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 192,192,192, 128,128,128, 128,128,128, 128,128,128,
128,128,128, 128,128,128, 128,128,128, 128,128,128, 128,128,128,
128,128,128, 128,128,128, 128,128,128, 128,128,128, 128,128,128,
128,128,128, 0, 0, 0, 192,192,192, 255,255,255, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 128,128,128, 0, 0, 0, 192,192,192, 255,255,255,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 128,128,128, 0, 0, 0, 192,192,192,
255,255,255, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 128,128,128, 0, 0, 0,
192,192,192, 255,255,255, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 0, 0, 0, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 128,128,128,
0, 0, 0, 192,192,192, 255,255,255, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 0, 0, 0, 0, 0, 0,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
128,128,128, 0, 0, 0, 192,192,192, 255,255,255, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 0, 0, 0, 0, 0, 0,
0, 0, 0, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 128,128,128, 0, 0, 0, 192,192,192, 255,255,255,
192,192,192, 192,192,192, 192,192,192, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 128,128,128, 0, 0, 0, 192,192,192,
255,255,255, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
0, 0, 0, 0, 0, 0, 0, 0, 0, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 128,128,128, 0, 0, 0,
192,192,192, 255,255,255, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 0, 0, 0, 0, 0, 0, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 128,128,128,
0, 0, 0, 192,192,192, 255,255,255, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 0, 0, 0,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
128,128,128, 0, 0, 0, 192,192,192, 255,255,255, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 128,128,128, 0, 0, 0, 192,192,192, 255,255,255,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 128,128,128, 0, 0, 0, 192,192,192,
255,255,255, 255,255,255, 255,255,255, 255,255,255, 255,255,255,
255,255,255, 255,255,255, 255,255,255, 255,255,255, 255,255,255,
255,255,255, 255,255,255, 255,255,255, 128,128,128, 0, 0, 0,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
192,192,192, 192,192,192, 192,192,192, 192,192,192, 192,192,192,
0, 0, 0,
};

@ -0,0 +1,188 @@
/*
* cacheManager implementation
*
* Copyright (C) Thomas Escher, Kai Lingemann
*
* Released under the GPL version 3.
*
*/
#include "scanserver/cache/cacheManager.h"
#include <stdexcept>
#include <string>
#include <boost/interprocess/exceptions.hpp>
using namespace boost::interprocess;
using std::runtime_error;
using std::vector;
using std::string;
#include <iostream>
using std::cout;
using std::cerr;
using std::endl;
#ifdef _MSC_VER
#include <windows.h>
#else
#include <sys/mman.h> // mlock for avoiding swaps
#endif
CacheManager::CacheManager(SegmentManager* sm, const char* shm_name, std::size_t cache_size) :
m_segment_manager(sm),
m_shm_name(shm_name)
{
// remove any existing shared memory that wasn't cleaned up
shared_memory_object::remove(m_shm_name.c_str());
try {
m_msm = new managed_shared_memory(create_only, m_shm_name.c_str(), cache_size);
#ifndef WIN32
cout << " Locking cache memory... " << std::flush;
int ret = mlock(m_msm->get_address(), m_msm->get_size());
if(ret == 0)
cout << "success.";
else if(ret == -EPERM)
cout << "unsuccessful, no permissions.";
else if(ret == -ENOMEM)
cout << "unsuccessful, RLIMIT_MEMLOCK too small.";
else
cout << "unsuccessful, error=" << ret << ".";
cout << endl;
#endif
} catch(interprocess_exception& e) {
throw std::runtime_error(std::string("Could not create shared memory: ") + e.what());
}
}
CacheManager::~CacheManager()
{
// clean up objects
for(vector<CacheObject*>::iterator it = m_objects.begin(); it != m_objects.end(); ++it)
m_segment_manager->destroy_ptr(*it);
// remove cache data shared memory
delete m_msm;
shared_memory_object::remove(m_shm_name.c_str());
}
CacheObject* CacheManager::createCacheObject()
{
CacheObject* obj = m_segment_manager->construct<CacheObject>(anonymous_instance)();
m_objects.push_back(obj);
return obj;
}
bool CacheManager::loadCacheObject(CacheObject* obj)
{
if(obj->m_handler) {
return obj->m_handler->load();
} else {
throw runtime_error("No CacheHandler set for loading");
}
}
unsigned char* CacheManager::allocateCacheObject(CacheObject* obj, unsigned int size)
{
// remove old data if this isn't a cache miss call but a direct allocate call
if(obj->m_handle != 0) {
if(size == obj->m_size) {
// INFO
//cout << "CacheManager::allocateCacheObject reusing space" << endl;
// space fits? leave it be
return reinterpret_cast<unsigned char*>(m_msm->get_address_from_handle(obj->m_handle));
} else {
// reset CO
m_msm->destroy_ptr(m_msm->get_address_from_handle(obj->m_handle));
obj->m_size = 0;
obj->m_handle = 0;
}
}
// try to allocate it initially
try {
return load(obj, size);
} catch(bad_alloc& e) {
// flush behaviour below
}
// create a list of COs to remove from memory
// TODO: create the list from the heuristic
vector<CacheObject*> loaded = m_loaded;
// try to exclusively lock COs to remove them from memory
for(vector<CacheObject*>::iterator it = loaded.begin(); it != loaded.end(); ++it) {
CacheObject* target = *it;
scoped_lock<interprocess_upgradable_mutex> lock(target->m_mutex_in_use, try_to_lock);
if(lock) {
unload(target);
// try to allocate it
try {
return load(obj, size);
} catch(bad_alloc& e) {
// continue flushing
}
}
}
// when flushing didn't work, there's nothing to do anymore
throw runtime_error("CacheManager could not allocate enough memory for CacheObject. All available memory is locked for used CacheObjects and you need to increase the cache memory size");
}
void CacheManager::invalidateCacheObject(CacheObject* obj)
{
// remove its data
if(obj->m_handle != 0) {
// reset CO
m_msm->destroy_ptr(m_msm->get_address_from_handle(obj->m_handle));
obj->m_size = 0;
obj->m_handle = 0;
}
// invalidate the handler too
obj->m_handler->invalidate();
}
unsigned char* CacheManager::load(CacheObject* obj, unsigned int size)
{
// INFO
//cout << " CM::load (" << size << ")" << endl;
// allocate
unsigned char* data = m_msm->construct<unsigned char>(anonymous_instance)[size]();
obj->m_size = size;
obj->m_handle = m_msm->get_handle_from_address(data);
// mark it as loaded
m_loaded.push_back(obj);
return data;
}
void CacheManager::unload(CacheObject* obj)
{
if(obj->m_handle == 0) return;
// INFO
//cout << " CM::unload" << endl;
// save the CO by its handler
unsigned char* data = reinterpret_cast<unsigned char*>(m_msm->get_address_from_handle(obj->m_handle));
obj->m_handler->save(data, obj->m_size);
// TODO: exceptions?
// reset CO
m_msm->destroy_ptr(data);
obj->m_size = 0;
obj->m_handle = 0;
// mark it as unloaded
for(vector<CacheObject*>::iterator it = m_loaded.begin(); it != m_loaded.end(); ++it) {
if(obj == *it) {
m_loaded.erase(it);
break;
}
}
}

@ -0,0 +1,483 @@
//#define WANT_STREAM
#define WANT_MATH
#include "include.h"
#include "newmatap.h"
//#include "newmatio.h"
#include "tmt.h"
#ifdef use_namespace
using namespace NEWMAT;
#endif
// check D is sorted
void CheckIsSorted(const DiagonalMatrix& D, bool ascending = false)
{
DiagonalMatrix D1 = D;
if (ascending) SortAscending(D1); else SortDescending(D1);
D1 -= D; Print(D1);
}
void trymate()
{
Tracer et("Fourteenth test of Matrix package");
Tracer::PrintTrace();
{
Tracer et1("Stage 1");
Matrix A(8,5);
{
#ifndef ATandT
Real a[] = { 22, 10, 2, 3, 7,
14, 7, 10, 0, 8,
-1, 13, -1,-11, 3,
-3, -2, 13, -2, 4,
9, 8, 1, -2, 4,
9, 1, -7, 5, -1,
2, -6, 6, 5, 1,
4, 5, 0, -2, 2 };
#else
Real a[40];
a[ 0]=22; a[ 1]=10; a[ 2]= 2; a[ 3]= 3; a[ 4]= 7;
a[ 5]=14; a[ 6]= 7; a[ 7]=10; a[ 8]= 0; a[ 9]= 8;
a[10]=-1; a[11]=13; a[12]=-1; a[13]=-11;a[14]= 3;
a[15]=-3; a[16]=-2; a[17]=13; a[18]=-2; a[19]= 4;
a[20]= 9; a[21]= 8; a[22]= 1; a[23]=-2; a[24]= 4;
a[25]= 9; a[26]= 1; a[27]=-7; a[28]= 5; a[29]=-1;
a[30]= 2; a[31]=-6; a[32]= 6; a[33]= 5; a[34]= 1;
a[35]= 4; a[36]= 5; a[37]= 0; a[38]=-2; a[39]= 2;
#endif
A << a;
}
DiagonalMatrix D; Matrix U; Matrix V;
int anc = A.Ncols(); IdentityMatrix I(anc);
SymmetricMatrix S1; S1 << A.t() * A;
SymmetricMatrix S2; S2 << A * A.t();
Real zero = 0.0; SVD(A+zero,D,U,V); CheckIsSorted(D);
DiagonalMatrix D1; SVD(A,D1); CheckIsSorted(D1);
D1 -= D; Clean(D1,0.000000001);Print(D1);
Matrix W;
SVD(A, D1, W, W, true, false); D1 -= D; W -= U;
Clean(W,0.000000001); Print(W); Clean(D1,0.000000001); Print(D1);
Matrix WX;
SVD(A, D1, WX, W, false, true); D1 -= D; W -= V;
Clean(W,0.000000001); Print(W); Clean(D1,0.000000001); Print(D1);
Matrix SU = U.t() * U - I; Clean(SU,0.000000001); Print(SU);
Matrix SV = V.t() * V - I; Clean(SV,0.000000001); Print(SV);
Matrix B = U * D * V.t() - A; Clean(B,0.000000001); Print(B);
D1=0.0; SVD(A,D1,A); CheckIsSorted(D1);
A -= U; Clean(A,0.000000001); Print(A);
D(1) -= sqrt(1248.0); D(2) -= 20; D(3) -= sqrt(384.0);
Clean(D,0.000000001); Print(D);
Jacobi(S1, D, V); CheckIsSorted(D, true);
V = S1 - V * D * V.t(); Clean(V,0.000000001); Print(V);
D = D.Reverse(); D(1)-=1248; D(2)-=400; D(3)-=384;
Clean(D,0.000000001); Print(D);
Jacobi(S1, D); CheckIsSorted(D, true);
D = D.Reverse(); D(1)-=1248; D(2)-=400; D(3)-=384;
Clean(D,0.000000001); Print(D);
SymmetricMatrix JW(5);
Jacobi(S1, D, JW); CheckIsSorted(D, true);
D = D.Reverse(); D(1)-=1248; D(2)-=400; D(3)-=384;
Clean(D,0.000000001); Print(D);
Jacobi(S2, D, V); CheckIsSorted(D, true);
V = S2 - V * D * V.t(); Clean(V,0.000000001); Print(V);
D = D.Reverse(); D(1)-=1248; D(2)-=400; D(3)-=384;
Clean(D,0.000000001); Print(D);
EigenValues(S1, D, V); CheckIsSorted(D, true);
V = S1 - V * D * V.t(); Clean(V,0.000000001); Print(V);
D(5)-=1248; D(4)-=400; D(3)-=384;
Clean(D,0.000000001); Print(D);
EigenValues(S2, D, V); CheckIsSorted(D, true);
V = S2 - V * D * V.t(); Clean(V,0.000000001); Print(V);
D(8)-=1248; D(7)-=400; D(6)-=384;
Clean(D,0.000000001); Print(D);
EigenValues(S1, D); CheckIsSorted(D, true);
D(5)-=1248; D(4)-=400; D(3)-=384;
Clean(D,0.000000001); Print(D);
SymmetricMatrix EW(S2);
EigenValues(S2, D, EW); CheckIsSorted(D, true);
D(8)-=1248; D(7)-=400; D(6)-=384;
Clean(D,0.000000001); Print(D);
}
{
Tracer et1("Stage 2");
Matrix A(20,21);
int i,j;
for (i=1; i<=20; i++) for (j=1; j<=21; j++)
{ if (i>j) A(i,j) = 0; else if (i==j) A(i,j) = 21-i; else A(i,j) = -1; }
A = A.t();
SymmetricMatrix S1; S1 << A.t() * A;
SymmetricMatrix S2; S2 << A * A.t();
DiagonalMatrix D; Matrix U; Matrix V;
#ifdef ATandT
int anc = A.Ncols(); DiagonalMatrix I(anc); // AT&T 2.1 bug
#else
DiagonalMatrix I(A.Ncols());
#endif
I=1.0;
SVD(A,D,U,V); CheckIsSorted(D);
Matrix SU = U.t() * U - I; Clean(SU,0.000000001); Print(SU);
Matrix SV = V.t() * V - I; Clean(SV,0.000000001); Print(SV);
Matrix B = U * D * V.t() - A; Clean(B,0.000000001); Print(B);
for (i=1; i<=20; i++) D(i) -= sqrt((22.0-i)*(21.0-i));
Clean(D,0.000000001); Print(D);
Jacobi(S1, D, V); CheckIsSorted(D, true);
V = S1 - V * D * V.t(); Clean(V,0.000000001); Print(V);
D = D.Reverse();
for (i=1; i<=20; i++) D(i) -= (22-i)*(21-i);
Clean(D,0.000000001); Print(D);
Jacobi(S2, D, V); CheckIsSorted(D, true);
V = S2 - V * D * V.t(); Clean(V,0.000000001); Print(V);
D = D.Reverse();
for (i=1; i<=20; i++) D(i) -= (22-i)*(21-i);
Clean(D,0.000000001); Print(D);
EigenValues(S1, D, V); CheckIsSorted(D, true);
V = S1 - V * D * V.t(); Clean(V,0.000000001); Print(V);
for (i=1; i<=20; i++) D(i) -= (i+1)*i;
Clean(D,0.000000001); Print(D);
EigenValues(S2, D, V); CheckIsSorted(D, true);
V = S2 - V * D * V.t(); Clean(V,0.000000001); Print(V);
for (i=2; i<=21; i++) D(i) -= (i-1)*i;
Clean(D,0.000000001); Print(D);
EigenValues(S1, D); CheckIsSorted(D, true);
for (i=1; i<=20; i++) D(i) -= (i+1)*i;
Clean(D,0.000000001); Print(D);
EigenValues(S2, D); CheckIsSorted(D, true);
for (i=2; i<=21; i++) D(i) -= (i-1)*i;
Clean(D,0.000000001); Print(D);
}
{
Tracer et1("Stage 3");
Matrix A(30,30);
int i,j;
for (i=1; i<=30; i++) for (j=1; j<=30; j++)
{ if (i>j) A(i,j) = 0; else if (i==j) A(i,j) = 1; else A(i,j) = -1; }
Real d1 = A.LogDeterminant().Value();
DiagonalMatrix D; Matrix U; Matrix V;
#ifdef ATandT
int anc = A.Ncols(); DiagonalMatrix I(anc); // AT&T 2.1 bug
#else
DiagonalMatrix I(A.Ncols());
#endif
I=1.0;
SVD(A,D,U,V); CheckIsSorted(D);
Matrix SU = U.t() * U - I; Clean(SU,0.000000001); Print(SU);
Matrix SV = V.t() * V - I; Clean(SV,0.000000001); Print(SV);
Real d2 = D.LogDeterminant().Value();
Matrix B = U * D * V.t() - A; Clean(B,0.000000001); Print(B);
Real d3 = D.LogDeterminant().Value();
ColumnVector Test(3);
Test(1) = d1 - 1; Test(2) = d2 - 1; Test(3) = d3 - 1;
Clean(Test,0.00000001); Print(Test); // only 8 decimal figures
A.ReSize(2,2);
Real a = 1.5; Real b = 2; Real c = 2 * (a*a + b*b);
A << a << b << a << b;
I.ReSize(2); I=1;
SVD(A,D,U,V); CheckIsSorted(D);
SU = U.t() * U - I; Clean(SU,0.000000001); Print(SU);
SV = V.t() * V - I; Clean(SV,0.000000001); Print(SV);
B = U * D * V.t() - A; Clean(B,0.000000001); Print(B);
D = D*D; SortDescending(D);
DiagonalMatrix D50(2); D50 << c << 0; D = D - D50;
Clean(D,0.000000001);
Print(D);
A << a << a << b << b;
SVD(A,D,U,V); CheckIsSorted(D);
SU = U.t() * U - I; Clean(SU,0.000000001); Print(SU);
SV = V.t() * V - I; Clean(SV,0.000000001); Print(SV);
B = U * D * V.t() - A; Clean(B,0.000000001); Print(B);
D = D*D; SortDescending(D);
D = D - D50;
Clean(D,0.000000001);
Print(D);
}
{
Tracer et1("Stage 4");
// test for bug found by Olof Runborg,
// Department of Numerical Analysis and Computer Science (NADA),
// KTH, Stockholm
Matrix A(22,20);
A = 0;
int a=1;
A(a+0,a+2) = 1; A(a+0,a+18) = -1;
A(a+1,a+9) = 1; A(a+1,a+12) = -1;
A(a+2,a+11) = 1; A(a+2,a+12) = -1;
A(a+3,a+10) = 1; A(a+3,a+19) = -1;
A(a+4,a+16) = 1; A(a+4,a+19) = -1;
A(a+5,a+17) = 1; A(a+5,a+18) = -1;
A(a+6,a+10) = 1; A(a+6,a+4) = -1;
A(a+7,a+3) = 1; A(a+7,a+2) = -1;
A(a+8,a+14) = 1; A(a+8,a+15) = -1;
A(a+9,a+13) = 1; A(a+9,a+16) = -1;
A(a+10,a+8) = 1; A(a+10,a+9) = -1;
A(a+11,a+1) = 1; A(a+11,a+15) = -1;
A(a+12,a+16) = 1; A(a+12,a+4) = -1;
A(a+13,a+6) = 1; A(a+13,a+9) = -1;
A(a+14,a+5) = 1; A(a+14,a+4) = -1;
A(a+15,a+0) = 1; A(a+15,a+1) = -1;
A(a+16,a+14) = 1; A(a+16,a+0) = -1;
A(a+17,a+7) = 1; A(a+17,a+6) = -1;
A(a+18,a+13) = 1; A(a+18,a+5) = -1;
A(a+19,a+7) = 1; A(a+19,a+8) = -1;
A(a+20,a+17) = 1; A(a+20,a+3) = -1;
A(a+21,a+6) = 1; A(a+21,a+11) = -1;
Matrix U, V; DiagonalMatrix S;
SVD(A, S, U, V, true, true); CheckIsSorted(S);
DiagonalMatrix D(20); D = 1;
Matrix tmp = U.t() * U - D;
Clean(tmp,0.000000001); Print(tmp);
tmp = V.t() * V - D;
Clean(tmp,0.000000001); Print(tmp);
tmp = U * S * V.t() - A ;
Clean(tmp,0.000000001); Print(tmp);
}
{
Tracer et1("Stage 5");
Matrix A(10,10);
A.Row(1) << 1.00 << 0.07 << 0.05 << 0.00 << 0.06
<< 0.09 << 0.03 << 0.02 << 0.02 << -0.03;
A.Row(2) << 0.07 << 1.00 << 0.05 << 0.05 << -0.03
<< 0.07 << 0.00 << 0.07 << 0.00 << 0.02;
A.Row(3) << 0.05 << 0.05 << 1.00 << 0.05 << 0.02
<< 0.01 << -0.05 << 0.04 << 0.05 << -0.03;
A.Row(4) << 0.00 << 0.05 << 0.05 << 1.00 << -0.05
<< 0.04 << 0.01 << 0.02 << -0.05 << 0.00;
A.Row(5) << 0.06 << -0.03 << 0.02 << -0.05 << 1.00
<< -0.03 << 0.02 << -0.02 << 0.04 << 0.00;
A.Row(6) << 0.09 << 0.07 << 0.01 << 0.04 << -0.03
<< 1.00 << -0.06 << 0.08 << -0.02 << -0.10;
A.Row(7) << 0.03 << 0.00 << -0.05 << 0.01 << 0.02
<< -0.06 << 1.00 << 0.09 << 0.12 << -0.03;
A.Row(8) << 0.02 << 0.07 << 0.04 << 0.02 << -0.02
<< 0.08 << 0.09 << 1.00 << 0.00 << -0.02;
A.Row(9) << 0.02 << 0.00 << 0.05 << -0.05 << 0.04
<< -0.02 << 0.12 << 0.00 << 1.00 << 0.02;
A.Row(10) << -0.03 << 0.02 << -0.03 << 0.00 << 0.00
<< -0.10 << -0.03 << -0.02 << 0.02 << 1.00;
SymmetricMatrix AS; AS << A;
Matrix V; DiagonalMatrix D, D1;
ColumnVector Check(6);
EigenValues(AS,D,V); CheckIsSorted(D, true);
Check(1) = MaximumAbsoluteValue(A - V * D * V.t());
DiagonalMatrix I(10); I = 1;
Check(2) = MaximumAbsoluteValue(V * V.t() - I);
Check(3) = MaximumAbsoluteValue(V.t() * V - I);
EigenValues(AS, D1); CheckIsSorted(D1, true);
D -= D1;
Clean(D,0.000000001); Print(D);
Jacobi(AS,D,V);
Check(4) = MaximumAbsoluteValue(A - V * D * V.t());
Check(5) = MaximumAbsoluteValue(V * V.t() - I);
Check(6) = MaximumAbsoluteValue(V.t() * V - I);
SortAscending(D);
D -= D1;
Clean(D,0.000000001); Print(D);
Clean(Check,0.000000001); Print(Check);
// Check loading rows
SymmetricMatrix B(10);
B.Row(1) << 1.00;
B.Row(2) << 0.07 << 1.00;
B.Row(3) << 0.05 << 0.05 << 1.00;
B.Row(4) << 0.00 << 0.05 << 0.05 << 1.00;
B.Row(5) << 0.06 << -0.03 << 0.02 << -0.05 << 1.00;
B.Row(6) << 0.09 << 0.07 << 0.01 << 0.04 << -0.03
<< 1.00;
B.Row(7) << 0.03 << 0.00 << -0.05 << 0.01 << 0.02
<< -0.06 << 1.00;
B.Row(8) << 0.02 << 0.07 << 0.04 << 0.02 << -0.02
<< 0.08 << 0.09 << 1.00;
B.Row(9) << 0.02 << 0.00 << 0.05 << -0.05 << 0.04
<< -0.02 << 0.12 << 0.00 << 1.00;
B.Row(10) << -0.03 << 0.02 << -0.03 << 0.00 << 0.00
<< -0.10 << -0.03 << -0.02 << 0.02 << 1.00;
B -= AS; Print(B);
}
{
Tracer et1("Stage 6");
// badly scaled matrix
Matrix A(9,9);
A.Row(1) << 1.13324e+012 << 3.68788e+011 << 3.35163e+009
<< 3.50193e+011 << 1.25335e+011 << 1.02212e+009
<< 3.16602e+009 << 1.02418e+009 << 9.42959e+006;
A.Row(2) << 3.68788e+011 << 1.67128e+011 << 1.27449e+009
<< 1.25335e+011 << 6.05413e+010 << 4.34573e+008
<< 1.02418e+009 << 4.69192e+008 << 3.61098e+006;
A.Row(3) << 3.35163e+009 << 1.27449e+009 << 1.25571e+007
<< 1.02212e+009 << 4.34573e+008 << 3.69769e+006
<< 9.42959e+006 << 3.61098e+006 << 3.59450e+004;
A.Row(4) << 3.50193e+011 << 1.25335e+011 << 1.02212e+009
<< 1.43514e+011 << 5.42310e+010 << 4.15822e+008
<< 1.23068e+009 << 4.31545e+008 << 3.58714e+006;
A.Row(5) << 1.25335e+011 << 6.05413e+010 << 4.34573e+008
<< 5.42310e+010 << 2.76601e+010 << 1.89102e+008
<< 4.31545e+008 << 2.09778e+008 << 1.51083e+006;
A.Row(6) << 1.02212e+009 << 4.34573e+008 << 3.69769e+006
<< 4.15822e+008 << 1.89102e+008 << 1.47143e+006
<< 3.58714e+006 << 1.51083e+006 << 1.30165e+004;
A.Row(7) << 3.16602e+009 << 1.02418e+009 << 9.42959e+006
<< 1.23068e+009 << 4.31545e+008 << 3.58714e+006
<< 1.12335e+007 << 3.54778e+006 << 3.34311e+004;
A.Row(8) << 1.02418e+009 << 4.69192e+008 << 3.61098e+006
<< 4.31545e+008 << 2.09778e+008 << 1.51083e+006
<< 3.54778e+006 << 1.62552e+006 << 1.25885e+004;
A.Row(9) << 9.42959e+006 << 3.61098e+006 << 3.59450e+004
<< 3.58714e+006 << 1.51083e+006 << 1.30165e+004
<< 3.34311e+004 << 1.25885e+004 << 1.28000e+002;
SymmetricMatrix AS; AS << A;
Matrix V; DiagonalMatrix D, D1;
ColumnVector Check(6);
EigenValues(AS,D,V); CheckIsSorted(D, true);
Check(1) = MaximumAbsoluteValue(A - V * D * V.t()) / 100000;
DiagonalMatrix I(9); I = 1;
Check(2) = MaximumAbsoluteValue(V * V.t() - I);
Check(3) = MaximumAbsoluteValue(V.t() * V - I);
EigenValues(AS, D1);
D -= D1;
Clean(D,0.001); Print(D);
Jacobi(AS,D,V);
Check(4) = MaximumAbsoluteValue(A - V * D * V.t()) / 100000;
Check(5) = MaximumAbsoluteValue(V * V.t() - I);
Check(6) = MaximumAbsoluteValue(V.t() * V - I);
SortAscending(D);
D -= D1;
Clean(D,0.001); Print(D);
Clean(Check,0.0000001); Print(Check);
}
{
Tracer et1("Stage 7");
// matrix with all singular values close to 1
Matrix A(8,8);
A.Row(1)<<-0.4343<<-0.0445<<-0.4582<<-0.1612<<-0.3191<<-0.6784<<0.1068<<0;
A.Row(2)<<0.5791<<0.5517<<0.2575<<-0.1055<<-0.0437<<-0.5282<<0.0442<<0;
A.Row(3)<<0.5709<<-0.5179<<-0.3275<<0.2598<<-0.196<<-0.1451<<-0.4143<<0;
A.Row(4)<<0.2785<<-0.5258<<0.1251<<-0.4382<<0.0514<<-0.0446<<0.6586<<0;
A.Row(5)<<0.2654<<0.3736<<-0.7436<<-0.0122<<0.0376<<0.3465<<0.3397<<0;
A.Row(6)<<0.0173<<-0.0056<<-0.1903<<-0.7027<<0.4863<<-0.0199<<-0.4825<<0;
A.Row(7)<<0.0434<<0.0966<<0.1083<<-0.4576<<-0.7857<<0.3425<<-0.1818<<0;
A.Row(8)<<0.0<<0.0<<0.0<<0.0<<0.0<<0.0<<0.0<<-1.0;
Matrix U,V; DiagonalMatrix D;
SVD(A,D,U,V); CheckIsSorted(D);
Matrix B = U * D * V.t() - A; Clean(B,0.000000001); Print(B);
DiagonalMatrix I(8); I = 1; D -= I; Clean(D,0.0001); Print(D);
U *= U.t(); U -= I; Clean(U,0.000000001); Print(U);
V *= V.t(); V -= I; Clean(V,0.000000001); Print(V);
}
{
Tracer et1("Stage 8");
// check SortSV functions
Matrix A(15, 10);
int i, j;
for (i = 1; i <= 15; ++i) for (j = 1; j <= 10; ++j)
A(i, j) = i + j / 1000.0;
DiagonalMatrix D(10);
D << 0.2 << 0.5 << 0.1 << 0.7 << 0.8 << 0.3 << 0.4 << 0.7 << 0.9 << 0.6;
Matrix U = A; Matrix V = 10 - 2 * A;
Matrix Prod = U * D * V.t();
DiagonalMatrix D2 = D; SortDescending(D2);
DiagonalMatrix D1 = D; SortSV(D1, U, V); Matrix X = D1 - D2; Print(X);
X = Prod - U * D1 * V.t(); Clean(X,0.000000001); Print(X);
U = A; V = 10 - 2 * A;
D1 = D; SortSV(D1, U); X = D1 - D2; Print(X);
D1 = D; SortSV(D1, V); X = D1 - D2; Print(X);
X = Prod - U * D1 * V.t(); Clean(X,0.000000001); Print(X);
D2 = D; SortAscending(D2);
U = A; V = 10 - 2 * A;
D1 = D; SortSV(D1, U, V, true); X = D1 - D2; Print(X);
X = Prod - U * D1 * V.t(); Clean(X,0.000000001); Print(X);
U = A; V = 10 - 2 * A;
D1 = D; SortSV(D1, U, true); X = D1 - D2; Print(X);
D1 = D; SortSV(D1, V, true); X = D1 - D2; Print(X);
X = Prod - U * D1 * V.t(); Clean(X,0.000000001); Print(X);
}
{
Tracer et1("Stage 9");
// Tom William's example
Matrix A(10,10);
Matrix U;
Matrix V;
DiagonalMatrix Sigma;
Real myVals[] =
{
1, 1, 1, 1, 1, 1, 1, 1, 1, 1,
1, 1, 1, 1, 1, 1, 1, 1, 1, 1,
1, 1, 1, 1, 1, 1, 1, 1, 1, 1,
1, 1, 1, 1, 1, 1, 1, 1, 1, 1,
1, 1, 1, 1, 1, 1, 1, 1, 1, 1,
1, 1, 1, 1, 1, 1, 1, 1, 1, 0,
1, 1, 1, 1, 1, 1, 1, 1, 1, 0,
1, 1, 1, 1, 1, 1, 1, 1, 0, 0,
1, 1, 1, 1, 1, 1, 1, 0, 0, 0,
1, 1, 1, 1, 1, 0, 0, 0, 0, 0,
};
A << myVals;
SVD(A, Sigma, U, V); CheckIsSorted(Sigma);
A -= U * Sigma * V.t();
Clean(A, 0.000000001); Print(A);
}
}

@ -0,0 +1,90 @@
/**
* @file
* @brief IO of a 3D scan
* @author Kai Lingemann. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Andreas Nuechter. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Thomas Escher
*/
#ifndef __SCAN_IO_H__
#define __SCAN_IO_H__
#include "slam6d/io_types.h"
#include "slam6d/pointfilter.h"
#include <string>
#include <list>
#include <map>
#include <vector>
/**
* @brief IO of a 3D scan
*
* This class needs to be instantiated by a class loading
* 3D scans from different file formats.
*/
class ScanIO {
public:
/**
* Read a directory and return all possible scans in the [start,end] interval.
*
* @param dir_path The directory from which to read the scans
* @param start Starting index
* @param end Last index
* @return List of IO-specific identifiers of scans, matching the search
*/
virtual std::list<std::string> readDirectory(const char* dir_path, unsigned int start, unsigned int end) = 0;
/**
* Reads the pose from a dedicated pose file or from the scan file.
*
* @param dir_path The directory the scan is contained in
* @param scan_identifier IO-specific identifier for the particular scan
* @param pose Pointer to an existing double[6] array where the pose is saved in
*/
virtual void readPose(const char* dir_path, const char* identifier, double* pose) = 0;
/**
* Given a scan identifier, load the contents of this particular scan.
*
* @param dir_path The directory the scan is contained in
* @param identifier IO-specific identifier for the particular scan
* @param filter Filter object which each point is tested on by its position
*/
virtual void readScan(const char* dir_path, const char* identifier, PointFilter& filter, std::vector<double>* xyz = 0, std::vector<unsigned char>* rgb = 0, std::vector<float>* reflectance = 0, std::vector<float>* amplitude = 0, std::vector<int>* type = 0, std::vector<float>* deviation = 0) = 0;
/**
* Returns whether this ScanIO can load the requested data from a scan.
*
* @param type data channel request
* @return whether it's supported or not
*/
virtual bool supports(IODataType type) = 0;
/**
* @brief Global mapping of io_types to single instances of ScanIOs.
*
* If the ScanIO doesn't exist, it will be created and saved in a map.
* Otherwise, the matching ScanIO will be returned.
*
* @param type Key identifying the ScanIO
* @return The newly created or found ScanIO
*/
static ScanIO* getScanIO(IOType iotype);
//! Delete all ScanIO instances and (lazy) try to unload the libraries.
static void clearScanIOs();
private:
static std::map<IOType, ScanIO *> m_scanIOs;
};
// Since the shared object files are loaded on the fly, we
// need class factories
// the types of the class factories
typedef ScanIO* create_sio();
typedef void destroy_sio(ScanIO*);
#endif

@ -0,0 +1,219 @@
/*
* icp6Dlumquat implementation
*
* Copyright (C) Andreas Nuechter, Alexandru-Eugen Ichim
*
* Released under the GPL version 3.
*
*/
/** @file
* @brief Implementation of the ICP error function minimization via
* via linearization with quaternions
*
* @author Andreas Nuechter. Jacobs University Bremen gGmbH, Germany
* @author Alexandru-Eugen Ichim. Jacobs University Bremen gGmbH, Germany
*
*/
#include "slam6d/icp6Dlumquat.h"
#include "slam6d/globals.icc"
#include <iomanip>
using std::ios;
using std::resetiosflags;
using std::setiosflags;
#include "newmat/newmat.h"
#include "newmat/newmatap.h"
using namespace NEWMAT;
/**
* computes the rotation matrix consisting
* of a rotation and translation that
* minimizes the root-mean-square error of the
* point pairs using linearization with quarernions
* @param pairs Vector of point pairs (pairs of corresponding points)
* @param *alignfx The resulting transformation matrix
* @return Error estimation of the matching (rms)
*/
double icp6D_LUMQUAT::Point_Point_Align(const vector<PtPair>& pairs, double *alignfx,
const double centroid_m[3], const double centroid_d[3])
{
// alignfx is filled with the current pose, t is the translation, quat is the quaternion
double t[3], quat[4];
Matrix4ToQuat(alignfx, quat, t);
double error = 0;
double sum = 0.0;
for(unsigned int i = 0; i < pairs.size(); i++){
sum += sqr(pairs[i].p1.x - pairs[i].p2.x)
+ sqr(pairs[i].p1.y - pairs[i].p2.y)
+ sqr(pairs[i].p1.z - pairs[i].p2.z) ;
}
error = sqrt(sum / (double)pairs.size());
if (!quiet) {
cout.setf(ios::basefield);
cout << "LUMQUAT RMS point-to-point error = "
<< resetiosflags(ios::adjustfield) << setiosflags(ios::internal)
<< resetiosflags(ios::floatfield) << setiosflags(ios::fixed)
<< std::setw(10) << std::setprecision(7)
<< error
<< " using " << std::setw(6) << (int)pairs.size() << " points" << endl;
}
/////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////
/// MZ = M^T * Z
ColumnVector MZ(7); MZ = 0.0;
/// MM = M^T * M
Matrix MM(7, 7); MM = 0.0;
double x = 0.0, y = 0.0, z = 0.0, dx = 0.0, dy = 0.0, dz = 0.0, sx = 0.0, sy = 0.0, sz = 0.0, xpy = 0.0, xpz = 0.0, ypz = 0.0, xpypz = 0.0, xy = 0.0, yz = 0.0, xz = 0.0;
for(unsigned int i = 0; i < pairs.size(); ++i) {
/// temporary values that we shall use multiple times in the subsequent computations
x = (pairs[i].p1.x + pairs[i].p1.x) / 2.0;
y = (pairs[i].p1.y + pairs[i].p2.y) / 2.0;
z = (pairs[i].p1.z + pairs[i].p2.z) / 2.0;
dx = pairs[i].p1.x - pairs[i].p2.x;
dy = pairs[i].p1.y - pairs[i].p2.y;
dz = pairs[i].p1.z - pairs[i].p2.z;
/// sums of each coordinate
sx += x;
sy += y;
sz += z;
/// sums of squares of coordinates
xpy += x*x + y*y;
xpz += x*x + z*z;
ypz += y*y + z*z;
xpypz += x*x + y*y + z*z;
/// sums of products of pairs of coordinates
xy += x*y;
xz += x*z;
yz += y*z;
/// incrementally construct matrix M^T * Z
MZ(1) += dx;
MZ(2) += dy;
MZ(3) += dz;
MZ(4) += x*dx + y*dy + z*dz;
MZ(5) += z*dy - y*dz;
MZ(6) += x*dz - z*dx;
MZ(7) += y*dx - x*dy;
}
/// construct M^ * M
MM(1,1) = MM(2,2) = MM(3,3) = pairs.size();
MM(4,4) = xpypz;
MM(5,5) = ypz;
MM(6,6) = xpz;
MM(7,7) = xpy;
MM(1,4) = MM(4,1) = sx;
MM(1,6) = MM(6,1) = -sz;
MM(1,7) = MM(7,1) = sy;
MM(2,4) = MM(4,2) = sy;
MM(2,5) = MM(5,2) = sz;
MM(2,7) = MM(7,2) = -sx;
MM(3,4) = MM(4,3) = sz;
MM(3,5) = MM(5,3) = -sy;
MM(3,6) = MM(6,3) = sx;
MM(5,6) = MM(6,5) = -xy;
MM(5,7) = MM(7,5) = -xz;
MM(6,7) = MM(7,6) = -yz;
ColumnVector Ehat = MM.i() * MZ ;
/// construct the auxiliary matrices U and T needed to build up H
double p = quat[0], q = quat[1], r = quat[2], s = quat[3];
x = t[0], y = t[1], z = t[2];
Matrix U(4, 4);
U << p << q << r << s
<< q <<-p << s <<-r
<< r <<-s <<-p << q
<< s << r <<-q <<-p;
Matrix T(3, 4);
T << p*x + s*y - r*z << q*x + r*y + s*z << r*x - q*y + p*z << s*x - p*y - q*z
<<-s*x + p*y + q*z <<-r*x + q*y - p*z << q*x + r*y + s*z << p*x + s*y - r*z
<< r*x - q*y + p*z <<-s*x + p*y + q*z <<-p*x - s*y + r*z << q*x + r*y - s*z;
/// now actually compose matrix H
Matrix H(7, 7); H = 0.0;
H.SubMatrix(1, 3, 1, 3) = IdentityMatrix(3);
H.SubMatrix(1, 3, 4, 7) = T *(-2);
H.SubMatrix(4, 7, 4, 7) = U * 2;
/// Xhat is the pose estimate for the second scan - use the pose of the first scan
ColumnVector Xhat(7); Xhat << x << y << z << p << q << r << s;
/// create a transformation matrix for the first scan with the given values
Matrix T1(4, 4); T1 = 0.0;
Matrix Cq(3, 3);
ColumnVector qvec(3); qvec << q << r << s;
Cq << 0 << -qvec(3) << qvec(2) << qvec(3) << 0 << -qvec(1) << -qvec(2) << qvec(1) << 0;
ColumnVector qtq(1); qtq = qvec.t() *qvec * (-1);
T1.SubMatrix(1, 3, 1, 3) = IdentityMatrix(3) * (p*p + qtq(1)) + qvec*qvec.t()*2 + Cq *2*p;
T1(1, 4) = x;
T1(2, 4) = y;
T1(3, 4) = z;
T1(4, 4) = 1;
/// the translation and quaternion for the second scan are computed
ColumnVector X = Xhat - H.i() * Ehat;
/// create the transformation matrix for the second scan
x = X(1), y = X(2), z = X(3);
p = X(4); q = X(5); r = X(6); s = X(7);
Matrix T2(4, 4); T2 = 0.0;
qvec = 0.0; qvec << q << r << s;
Cq = 0.0; Cq << 0 << -qvec(3) << qvec(2) << qvec(3) << 0 << -qvec(1) << -qvec(2) << qvec(1) << 0;
qtq = qvec.t() *qvec * (-1);
T2.SubMatrix(1, 3, 1, 3) = IdentityMatrix(3) * (p*p + qtq(1)) + qvec*qvec.t()*2 + Cq *2*p;
T2(1, 4) = x;
T2(2, 4) = y;
T2(3, 4) = z;
T2(4, 4) = 1;
/// the incremental transform calculated from the absolute poses of the two scans
Matrix T_inc = T1 * T2.i();
/// convert our 4x4 transform to column-wise opengl form
alignfx[0] = T_inc(1, 1);
alignfx[1] = T_inc(2, 1);
alignfx[2] = T_inc(3, 1);
alignfx[3] = 0.0;
alignfx[4] = T_inc(1, 2);
alignfx[5] = T_inc(2, 2);
alignfx[6] = T_inc(3, 2);
alignfx[7] = 0.0;
alignfx[8] = T_inc(1, 3);
alignfx[9] = T_inc(2, 3);
alignfx[10]= T_inc(3, 3);
alignfx[11]= 0.0;
alignfx[12]= T_inc(1, 4);
alignfx[13]= T_inc(2, 4);
alignfx[14]= T_inc(3, 4);
alignfx[15]= 1.0;
/////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////
return error;
}

@ -0,0 +1,75 @@
/**
* @file panorama.h
* @brife create panorama images from 3D scans.
* This class is a panorama image container with different projections.
* It creats panoramic images with specified resolutions.
* @author HamidReza Houshiar. Jacobs University Bremen gGmbH, Germany.
* @date Date: 2012/05/23 2:00
*/
#ifndef PANORAMA_H_
#define PANORAMA_H_
#include "fbr_global.h"
using namespace std;
namespace fbr{
/**
* @class panorama : create panorama images with different projection methods from input scan files(Mat from scan_cv class) in opencv Mat format
* @param iReflectance panorama image from reflectance data
* @param iRange panorama image from range data
* @param iMap panorama map of 3D cartesian coordinate of input scan(same points as iRange and iReflectance)
* @param extendedIMap 3D vector as panorama map with all the points
* @param iWidth width of the panorama image (cols in opencv)
* @param iHeight height of panorama image (rows in opencv)
* @param pMethod projection method for panorama creation
* @param nImage number of images per scan specially for Rectilinear, Pannini and Stereographic projections
* @param pParam special d parameter of Pannini projection (Master Thesis for more info) or special R parameter of Stereographic projection (Master Thesis for more info)
*/
class panorama{
cv::Mat iReflectance;
cv::Mat iMap;
cv::Mat iRange;
vector<vector<vector<cv::Vec3f> > > extendedIMap;
unsigned int iWidth;
unsigned int iHeight;
projection_method pMethod;
unsigned int nImages;
double pParam;
panorama_map_method mapMethod;
void init(unsigned int width, unsigned int height, projection_method method, unsigned int numberOfImages, double param, panorama_map_method mapMethod);
void map(int x, int y, cv::MatIterator_<cv::Vec4f> it, double range);
public:
/**
* constructor of class panorama
* @param width the width of the panorama image
* @param height the height of the panorama image
* @param method the projection method
* @param images number of subsets to crate panorama image
* @param param special parameter for pannini or stereographic projections
* @param mapMethod mapping method for panorama image and 3D points
*/
panorama (unsigned int width, unsigned int height, projection_method method);
panorama (unsigned int width, unsigned int height, projection_method method, unsigned int numberOfImages);
panorama (unsigned int width, unsigned int height, projection_method method, unsigned int numberOfImages, double param);
panorama (unsigned int width, unsigned int height, projection_method method, unsigned int numberOfImages, double param, panorama_map_method mapMethod);
/**
* @brief creates the panorama reflectance image and map.
*/
void createPanorama(cv::Mat scan);
unsigned int getImageWidth();
unsigned int getImageHeight();
projection_method getProjectionMethod();
unsigned int getNumberOfImages();
double getProjectionParam();
cv::Mat getReflectanceImage();
cv::Mat getMap();
cv::Mat getRangeImage();
vector<vector<vector<cv::Vec3f> > > getExtendedMap();
panorama_map_method getMapMethod();
void getDescription();
};
}
#endif /* PANORAMA_H_ */

@ -0,0 +1,97 @@
/**************************************************************************
quaternion.h
A quaternion class
---------------------------------------------------------------------
Feb 1998, Paul Rademacher (rademach@cs.unc.edu)
**************************************************************************/
#ifndef _QUATERNION_H_
#define _QUATERNION_H_
#include "algebra3.h"
#include <stdio.h>
#include <stdlib.h>
/* this line defines a new type: pointer to a function which returns a */
/* float and takes as argument a float */
typedef float (*V_FCT_PTR)(float);
/****************************************************************
* Quaternion *
****************************************************************/
class quat
{
/*protected: */
public:
vec3 v; /* vector component */
float s; /* scalar component */
/*public: */
/* Constructors */
quat(void);
quat(const float x, const float y, const float z, const float w);
quat( vec3 v, float s );
quat( float s, vec3 v );
quat(const float *d ); /* copy from four-element float array */
quat(const double *f ); /* copy from four-element double array */
quat(const quat &q ); /* copy from other quat */
/* Assignment operators */
quat &operator = ( const quat &v ); /* assignment of a quat */
quat &operator += ( const quat &v ); /* incrementation by a quat */
quat &operator -= ( const quat &v ); /* decrementation by a quat */
quat &operator *= ( const float d ); /* multiplication by a constant */
quat &operator /= ( const float d ); /* division by a constant */
float &operator [] ( int i); /* indexing */
/* special functions */
float length(void); /* length of a quat */
float length2(void); /* squared length of a quat */
quat &normalize(void); /* normalize a quat */
quat &apply(V_FCT_PTR fct); /* apply a func. to each component */
void set( float x, float y, float z ); /* set quat */
void set( vec3 v, float s ); /* set quat */
void print( FILE *file, char *name ); /* print quat to a file */
vec3 xform( const vec3 &v ); /* q*v*q-1 */
mat4 to_mat4( void );
void set_angle( float f ); /* set rot angle (degrees) */
void scale_angle( float f ); /* scale rot angle (degrees) */
float get_angle( void ); /* set rot angle (degrees) */
vec3 get_axis( void ); /* get axis */
/* friends */
friend quat operator - (const quat &v); /* -q1 */
friend quat operator + (const quat &a, const quat &b); /* q1 + q2 */
friend quat operator - (const quat &a, const quat &b); /* q1 - q2 */
friend quat operator * (const quat &a, const float d); /* q1 * 3.0 */
friend quat operator * (const float d, const quat &a); /* 3.0 * q1 */
friend quat operator * (const quat &a, const quat &b); /* q1 * q2 */
friend quat operator / (const quat &a, const float d); /* q1 / 3.0 */
friend int operator == (const quat &a, const quat &b); /* q1 == q2 ? */
friend int operator != (const quat &a, const quat &b); /* q1 != q2 ? */
friend void swap(quat &a, quat &b); /* swap q1 &q2 */
/*friend quat min(const quat &a, const quat &b); -- min(q1, q2) */
/*friend quat max(const quat &a, const quat &b); -- max(q1, q2) */
friend quat prod(const quat &a, const quat &b); /* term by term mult */
};
/* Utility functions */
quat quat_identity( void ); /* Returns quaternion identity element */
quat quat_slerp( quat from, quat to, float t );
#endif

@ -0,0 +1,158 @@
/**
* @file
* @brief Implementation of reading 3D scans
* @author Kai Lingemann. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Andreas Nuechter. Institute of Computer Science, University of Osnabrueck, Germany.
*/
#include "slam6d/scan_io_xyzr.h"
#include "slam6d/globals.icc"
#include <fstream>
using std::ifstream;
#include <iostream>
using std::cout;
using std::cerr;
using std::endl;
#ifdef _MSC_VER
#include <windows.h>
#endif
/**
* Reads specified scans from given directory.
*
* Scan poses will NOT be initialized after a call
* to this function.
*
* This function actually implements loading of 3D scans
* in UOS + reflectance file format and will be compiled as shared lib.
*
* @param start Starts to read with this scan
* @param end Stops with this scan
* @param dir The directory from which to read
* @param maxDist Reads only Points up to this Distance
* @param minDist Reads only Points from this Distance
* @param euler Initital pose estimates (will not be applied to the points
* @param ptss Vector containing the read points
*/
int ScanIO_xyzr::readScans(int start, int end, string &dir, int maxDist, int minDist,
double *euler, vector<Point> &ptss)
{
static int fileCounter = start;
string scanFileName;
string poseFileName;
ifstream scan_in, pose_in;
double maxDist2 = sqr(maxDist);
double minDist2 = sqr(minDist);
int my_fileNr = fileCounter;
if (end > -1 && fileCounter > end) return -1; // 'nuf read
/*
scanFileName = dir + "scan" + to_string(fileCounter,3) + ".3d";
poseFileName = dir + "scan" + to_string(fileCounter,3) + ".pose";
scan_in.open(scanFileName.c_str());
pose_in.open(poseFileName.c_str());
*/
scanFileName = dir + "konv_bremenc_" + to_string(fileCounter,3) + ".txt";
scan_in.open(scanFileName.c_str());
poseFileName = dir + "scan" + to_string(fileCounter,3) + ".pose";
pose_in.open(poseFileName.c_str());
// read 3D scan
// if (!pose_in.good() && !scan_in.good()) return -1; // no more files in the directory
if (!scan_in.good()) return -1; // no more files in the directory
cout << "Processing Scan " << scanFileName;
if (pose_in.good()) {
for (unsigned int i = 0; i < 6; pose_in >> euler[i++]);
// convert angles from deg to rad
for (unsigned int i = 3; i <= 5; i++) euler[i] = rad(euler[i]);
} else {
cout << endl << "No pose estimate given." << endl;
for (unsigned int i = 0; i < 6; euler[i++] = 0.0);
}
cout << " @ pose (" << euler[0] << "," << euler[1] << "," << euler[2]
<< "," << deg(euler[3]) << "," << deg(euler[4]) << "," << deg(euler[5]) << ")" << endl;
// convert angles from deg to rad
for (unsigned int i = 3; i <= 5; i++) euler[i] = rad(euler[i]);
// overread the first line
char dummy[255];
scan_in.getline(dummy, 255);
double tmp;
while (scan_in.good()) {
Point p;
try {
scan_in >> p;
p.x -= 485531.0;
p.y -= 5882078.400;
p.z -= 52;
tmp = p.z;
p.z = p.y;
p.y = tmp;
scan_in >> p.reflectance;
} catch (...) {
break;
}
// load points up to a certain distance only
// maxDist2 = -1 indicates no limitation
if ((maxDist == -1 || sqr(p.x) + sqr(p.y) + sqr(p.z) < maxDist2) && (minDist == -1 || sqr(p.x) + sqr(p.y) + sqr(p.z) > minDist2))
ptss.push_back(p);
}
scan_in.close();
scan_in.clear();
pose_in.close();
pose_in.clear();
fileCounter++;
return my_fileNr;
}
/**
* class factory for object construction
*
* @return Pointer to new object
*/
#ifdef _MSC_VER
extern "C" __declspec(dllexport) ScanIO* create()
#else
extern "C" ScanIO* create()
#endif
{
return new ScanIO_xyzr;
}
/**
* class factory for object construction
*
* @return Pointer to new object
*/
#ifdef _MSC_VER
extern "C" __declspec(dllexport) void destroy(ScanIO *sio)
#else
extern "C" void destroy(ScanIO *sio)
#endif
{
delete sio;
}
#ifdef _MSC_VER
BOOL APIENTRY DllMain(HANDLE hModule, DWORD dwReason, LPVOID lpReserved)
{
return TRUE;
}
#endif

@ -0,0 +1,925 @@
/**
* @file
* @brief Implementation of reading a 3D CAD model and creating a 3D
* surface sampling of it. This sampling is then used as an artificial
* 3D scan in regular scan matching
* @author Sven Albrecht. Institute of Computer Science, University of Osnabrueck, Germany.
*/
#include "slam6d/scan_io_cad.h"
#include "slam6d/globals.icc"
#include <fstream>
using std::ifstream;
#include <iostream>
using std::cout;
using std::cerr;
using std::endl;
#include <cmath>
#include <limits>
// TODO: make eventually compatible to windoze
#include <stdint.h> // can be changed to cstdint if -std=c++0x compiler flag is used
#ifdef _MSC_VER
#include <windows.h>
#endif
#define BOOST_NEW_FS_API 104600
ScanIO_CAD::ScanIO_CAD (void) : _op_descr ("CAD Config Options")
{
setUpOptionDescription ();
}
/**
* Reads specified 'scans' from CAD models in a given directory.
*
* Scan poses will NOT be initialized after a call
* to this function.
*
* Each CAD model will be represented by a sampling of 3D points on the
* the surface of the CAD model. Currently the implementation is able to
* handle CAD models in the .stl file format (binary or ASCII is fine).
* In constrast to other ScanIOs only one 3D scan will be read (specified
* by parameter start). Other data is generated from the (arbitrary) named
* .stl files in the directory specified by argument dir. Parameter end is
* soley kept to satisfy the general interface.
*
* !!!!!!
* Config parameters are read from an (optional) config.txt in the scan directory.
* A config.txt with content "help = 1" will print out all possible parameters.
* !!!!!!
*
* @param start Starts to read with this scan
* @param end Stops with this scan
* @param dir The directory from which to read
* @param maxDist Reads only Points up to this Distance
* @param minDist Reads only Points from this Distance
* @param euler Initital pose estimates (will not be applied to the points
* @param ptss Vector containing the read points
*/
int ScanIO_CAD::readScans(int start, int end, string &dir, int maxDist, int minDist,
double *euler, vector<Point> &ptss)
{
/*
* we need to read 1 normal scan (the first one) and afterwards
* create point samplings of the CAD models
*/
static int fileCounter = start; // this is a really ugly hack...
// check before the first scan is read for a config file
if (fileCounter == start)
{
// is there a config file ?
std::string config_file_name = dir + "config.txt";
std::ifstream config;
config.open (config_file_name.c_str ());
if (config.good ())
{
// parse the config to eventually overload default parameters
parseConfig (config);
}
// else use the default parameters
// retrieve all stl files
parseDirForAllSTL (dir);
}
string scanFileName;
string poseFileName;
ifstream scan_in, pose_in;
// clear the point vector (to make sure no old garbage is contained)
ptss.clear ();
int my_fileNr = fileCounter;
if (end > -1 && fileCounter > end) return -1; // 'nuf read
fs::path stl_file;
// the first scan file name should be a .3d file
if (fileCounter == start)
{
scanFileName = dir + "scan" + to_string(fileCounter, 3) + ".3d";
poseFileName = dir + "scan" + to_string(fileCounter, 3) + ".pose";
}
// otherwise it should be a .stl file
else
{
// get the next stl file if the directory contains one more
if (getNextSTLFromDir (stl_file))
{
fs::path pose_file (stl_file);
// retrieve the the filenames according to the installed boost version
#if BOOST_VERSION < BOOST_NEW_FS_API
// change extension
pose_file.replace_extension (".pose");
scanFileName = stl_file.directory_string ();
poseFileName = pose_file.directory_string ();
#else
// change extension
pose_file.replace_extension (fs::path (".pose"));
scanFileName = stl_file.string ();
poseFileName = pose_file.string ();
#endif
}
else
{
// aparently no stl file available anymore
return -1;
}
}
scan_in.open(scanFileName.c_str());
pose_in.open(poseFileName.c_str());
// read pose information independent from file type
// read 3D scan
if (!pose_in.good() && !scan_in.good()) return -1; // no more files in the directory
if (!pose_in.good()) { cerr << "ERROR: Missing file " << poseFileName << endl; exit(1); }
if (!scan_in.good()) { cerr << "ERROR: Missing file " << scanFileName << endl; exit(1); }
cout << "Processing Scan " << scanFileName;
// read a 'normal' Slam6D Pose
for (unsigned int i = 0; i < 6; pose_in >> euler[i++]);
cout << " @ pose (" << euler[0] << "," << euler[1] << "," << euler[2]
<< "," << euler[3] << "," << euler[4] << "," << euler[5] << ")" << endl;
// convert angles from deg to rad
for (unsigned int i = 3; i <= 5; i++) euler[i] = rad(euler[i]);
if (fileCounter == start)
{
read3DScan (scan_in, maxDist, minDist, ptss);
}
else
{
bool success = createSamplingFromSTL (scan_in, ptss);
if (!success)
{
// terminate similar to missing file
exit (1);
}
if (store_cad)
{
std::string stem;
// get the string of the file-stem according to installed boost API
#if BOOST_VERSION < BOOST_NEW_FS_API
stem = stl_file.stem ();
#else
stem = stl_file.stem ().string ();
#endif
fs::path sample_file (stl_file);
// is filename scanXXX.3d ?
if (stem.substr (0, 4).compare ("scan") == 0 &&
std::atoi (stem.substr (4).c_str ()) == fileCounter)
{
// replace the extension according to the installed boost API
#if BOOST_VERSION < BOOST_NEW_FS_API
sample_file.replace_extension (".3d");
#else
sample_file.replace_extension (fs::path (".3d"));
#endif
// the appropriate .pose file already exists
}
else
{
// generate appropriate filename
std::string filename = "scan" + to_string (fileCounter, 3) + ".3d";
sample_file.remove_filename ();
sample_file /= filename;
// copy .pose file
fs::path orig_pose (stl_file);
fs::path copied_pose (sample_file);
#if BOOST_VERSION < BOOST_NEW_FS_API
orig_pose.replace_extension (".pose");
copied_pose.replace_extension (".pose");
#else
orig_pose.replace_extension (fs::path (".pose"));
copied_pose.replace_extension (fs::path (".pose"));
#endif
fs::copy_file (orig_pose, copied_pose, fs::copy_option::overwrite_if_exists);
}
// retrieve the filename according to the installed boost API
#if BOOST_VERSION < BOOST_NEW_FS_API
storeSamplingTo3D (sample_file.directory_string (), ptss);
#else
storeSamplingTo3D (sample_file.string (), ptss);
#endif
}
}
// close the filestreams
scan_in.close();
scan_in.clear();
pose_in.close();
pose_in.clear();
fileCounter++;
return my_fileNr;
}
/**
* Helper function to read a regular UOS scan
*/
void
ScanIO_CAD::read3DScan (std::ifstream &scan_in, int maxDist, int minDist,
vector<Point> &points)
{
// reading regular uos scan (copy & paste from scan_io_uos.cc)
// overread the first line
char dummy[255];
scan_in.getline(dummy, 255);
double maxDist2 = sqr (maxDist);
double minDist2 = sqr (minDist);
while (scan_in.good()) {
Point p;
try {
scan_in >> p;
} catch (...) {
break;
}
// load points up to a certain distance only
// maxDist2 = -1 indicates no limitation
if (maxDist == -1 || sqr(p.x) + sqr(p.y) + sqr(p.z) < maxDist2)
{
if (minDist == -1 || sqr(p.x) + sqr(p.y) + sqr(p.z) > minDist2)
{
points.push_back(p);
}
}
}
}
/**
* Helper function to create a 3D point sampling for a given .stl file
*/
bool
ScanIO_CAD::createSamplingFromSTL (std::ifstream &scan_in,
vector<Point> &points)
{
bool success;
if (hasASCIIHeader (scan_in))
{
std::cout << "detected ASCII header, parsing file" << std::endl;
success = parseASCII (scan_in, points);
}
else
{
std::cout << "couldn't detect ASCII header, trying to parse binary"
<< std::endl;
success = parseBinary (scan_in, points);
}
return success;
}
bool
ScanIO_CAD::hasASCIIHeader (std::ifstream &scan_in)
{
// store current get pointer position
std::streampos current_pos = scan_in. tellg ();
bool is_ascii = true;
/* idea: check for the keywords with have to occur at the beginning
* and the end of an ASCII .stl files
* (see http://www.ennex.com/~fabbers/StL.asp for further specs)
*/
std::string solid ("solid");
std::string last_line;
std::string name;
std::string last_read_string;
// go to the beginning of the ifstream
scan_in.seekg (0, std::ios::beg);
// read the first string
scan_in >> last_read_string;
if (solid.compare (last_read_string) != 0)
{
is_ascii = false;
}
if (is_ascii)
{
// read the next string (i.e. name of the stl)
scan_in >> name;
// generate expected last line
last_line = "endsolid " + name;
// set the get pointer to the correct position
scan_in.seekg (-last_line.length () - 2, std::ios::end);
scan_in >> last_read_string;
if (last_read_string.compare ("endsolid") != 0)
{
is_ascii = false;
}
if (is_ascii)
{
scan_in >> last_read_string;
if (last_read_string.compare (name) != 0)
{
is_ascii = false;
}
}
}
// reset the position of the get pointer to its original position
scan_in.seekg (current_pos, std::ios::beg);
return is_ascii;
}
bool
ScanIO_CAD::parseASCII (std::ifstream &scan_in, vector<Point> &points)
{
float vertex1[3];
float vertex2[3];
float vertex3[3];
float raw_data[3];
unsigned int line_nr = 0;
unsigned int face_counter = 0;
float* vertices[3];
vertices[0] = vertex1;
vertices[1] = vertex2;
vertices[2] = vertex3;
bool success = true;
bool reached_end = false;
// retrieve current pos of get pointer
std::ios::streampos current_pos = scan_in.tellg ();
// set get pointer to beginning of file
scan_in.seekg (0, std::ios::beg);
std::string read_key;
std::string tmp;
// ignore first line, since in hasASCIIHeader ()
std::getline (scan_in, read_key);
line_nr++;
while (scan_in.good ())
{
// read first string at current position
scan_in >> read_key;
// determine if end of file reached
if (read_key.compare ("endsolid") == 0)
{
reached_end = true;
break;
}
// otherwise check if a new face begins
if (read_key.compare ("facet") != 0 ||
!scan_in.good ())
{
// no new face -> misformated .stl
std::cout << "expected 'facet', contains '" << read_key.substr (0,5)
<< "'" << std::endl;
success = false;
break;
}
// read the rest of the line (containing the normal)
getline (scan_in, read_key);
line_nr++;
// get the next 2 strings
scan_in >> read_key;
scan_in >> tmp;
read_key += " " + tmp;
if (read_key.compare ("outer loop") != 0 ||
!scan_in.good ())
{
std::cout << "expected 'outer loop', read '" << read_key
<< "' instead" << std::endl;
success = false;
break;
}
// read the rest of the line
getline (scan_in, read_key);
line_nr++;
// read the 3 vertices
for (unsigned int i = 0; i < 3; ++i)
{
scan_in >> read_key;
line_nr++;
if (read_key.compare ("vertex") == 0)
{
// read x, y and z coordinate in this order
scan_in >> raw_data[0] >> raw_data[1] >> raw_data[2];
// scale and order according to the specified settings
copyRawData2Vertex (raw_data, vertices[i]);
if (!scan_in.good ())
{
success = false;
break;
}
}
else
{
success = false;
break;
}
}
// retrieve the closing tag for the vertices
scan_in >> read_key;
if (read_key.compare ("endloop") != 0 ||
!scan_in.good ())
{
success = false;
break;
}
// retrieve the rest of the current line
getline (scan_in, read_key);
line_nr++;
// retrieve the closing tag for the face
scan_in >> read_key;
if (read_key.compare ("endfacet") != 0 ||
!scan_in.good ())
{
std::cout << "Expected 'endfacet', read '" << read_key
<< "' instead" << std::endl;
success = false;
break;
}
// retrieve the rest of the line
getline (scan_in, read_key);
line_nr++;
// increment nr of read faces
face_counter++;
// create the sampling for the face
createSampingForFace (vertex1, vertex2, vertex3, points);
}
if (!reached_end)
{
success = false;
}
// reset position of get pointer
scan_in.seekg (current_pos, std::ios::beg);
if (!success)
{
std::cerr << "Misformated ASCII .stl file. Parsing error in line "
<< line_nr << std::endl;
}
else
{
std::cout << "Created " << points.size () << " sample points for "
<< face_counter << " faces." << std::endl;
}
return success;
}
bool
ScanIO_CAD::parseBinary (std::ifstream &scan_in, vector<Point> &points)
{
// TODO: make eventually compatible to windoze
uint32_t nr_faces;
uint32_t face_counter = 0;
uint16_t attribute;
float normal[3];
float vertex1[3];
float vertex2[3];
float vertex3[3];
float raw_data[3];
bool success;
size_t header_size = 80; // defined in the binary .stl standard
char* header = new char[header_size];
// retrieve the current get pointer position
std::streampos current_pos = scan_in.tellg ();
// jump to begin of file
scan_in.seekg (0, std::ios::beg);
if (scan_in.is_open ())
{
// read the header (unimportant for the sampling)
scan_in.read (header, header_size);
// read nr of faces contained in stl file
scan_in.read ((char*) &nr_faces, 4);
// try to read all faces
for (face_counter = 0; face_counter < nr_faces; ++face_counter)
{
if (!scan_in.good ())
{
break;
}
// read face normal (which we don't need)
scan_in.read ((char*) &normal, 12);
// read the first vertex
scan_in.read ((char*) &raw_data, 12);
copyRawData2Vertex (raw_data, vertex1);
// read the second vertex
scan_in.read ((char*) &raw_data, 12);
copyRawData2Vertex (raw_data, vertex2);
// read the first vertex
scan_in.read ((char*) &raw_data, 12);
copyRawData2Vertex (raw_data, vertex3);
// read the attribute (which we don't need)
scan_in.read ((char*) &attribute, 2);
// create the sampling for the current face
createSampingForFace (vertex1, vertex2, vertex3, points);
}
}
// check if indeed the specified number of faces could be read
if (face_counter == nr_faces)
{
success = true;
std::cout << "Created " << points.size () << " sample points for "
<< nr_faces << " faces." << std::endl;
}
else
{
std::cerr << "Error parsing binary .stl file. Expected " << nr_faces
<< " faces but could read only " << face_counter << std::endl;
success = false;
}
// reset the get pointer position;
scan_in.seekg (current_pos, std::ios::beg);
delete [] header;
return success;
}
void
ScanIO_CAD::createSampingForFace (float* vertex1, float* vertex2,
float* vertex3, vector<Point> &points)
{
/*
* Random sampling approach to sample a triangle:
* First compute the area of the triangle and decide how many sample
* points are needed; afterwards randomly create a number of points
* inside the triangle
*/
// get the area of the triangle
float vector12[3];
float vector13[3];
float vector23[3];
for (unsigned int i = 0; i < 3; ++i)
{
vector12[i] = vertex2[i] - vertex1[i];
vector13[i] = vertex3[i] - vertex1[i];
vector23[i] = vertex3[i] - vertex2[i];
}
float a, b, c;
a = b = c = 0.0f;
a = dotProd (vector12, vector12);
b = dotProd (vector13, vector13);
c = dotProd (vector23, vector23);
a = sqrt (a);
b = sqrt (b);
c = sqrt (c);
float s = a + b + c;
s /= 2.0f;
float area = sqrt (s * (s - a) * (s - b) * (s - c));
unsigned int nr_sample_points, nr_added_points;
nr_sample_points = area / (sample_point_dist * sample_point_dist);
nr_added_points = 0;
if (nr_sample_points > 3)
{
points.reserve (points.size () + nr_sample_points);
float u, v;
float point_in_triangle[3];
while (nr_added_points < nr_sample_points)
{
// randomly generate scalar u and v in [0,1]
u = (float) std::rand () / (float) RAND_MAX;
v = (float) std::rand () / (float) RAND_MAX;
// check if u and v are smaller than 1.0 (i.e. point is in triangle)
if (u + v <= 1.0f)
{
for (unsigned int i = 0; i < 3; ++i)
{
point_in_triangle[i] = vertex1[i] + u * vector12[i] + v * vector13[i];
}
points.push_back (Point (point_in_triangle[0],
point_in_triangle[1], point_in_triangle[2]));
nr_added_points++;
}
}
}
// for a small face just add the corners to the sample points
else
{
points.reserve (points.size () + 3);
points.push_back (Point (vertex1[0], vertex1[1], vertex1[2]));
points.push_back (Point (vertex2[0], vertex2[1], vertex2[2]));
points.push_back (Point (vertex3[0], vertex3[1], vertex3[2]));
}
}
void
ScanIO_CAD::storeSamplingTo3D (std::string filename, vector<Point> &points)
{
std::ofstream sample_file (filename.c_str ());
// write header
sample_file << "# artificial scan from cad model '" << filename
<< "', containing " << points.size () << " sample points" << std::endl;
// write all points
vector<Point>::const_iterator it = points.begin ();
while (it != points.end ())
{
sample_file << *it++ << std::endl;
}
sample_file.flush ();
sample_file.close ();
}
float
ScanIO_CAD::dotProd (const float* vec1, const float* vec2)
{
return vec1[0] * vec2[0] + vec1[1] * vec2[1] + vec1[2] * vec2[2];
}
void
ScanIO_CAD::parseConfig (std::ifstream &config)
{
try
{
po::store (po::parse_config_file (config, _op_descr), _vmap);
}
catch (std::exception &e)
{
std::cout << "illegal parameter in config file:" << std::endl
<< e.what () << std::endl << std::endl;
std::cout << "The following options are available:" << std::endl;
std::cout << _op_descr << std::endl;
config.close ();
exit (-1);
}
catch (...)
{
std::cerr << "this line shouldn't have been reached ever" << std::endl;
config.close ();
exit (-2);
}
po::notify (_vmap);
if (_vmap.count ("help"))
{
std::cout << _op_descr << std::endl;
// when help is enabled we'll just exit
exit (1);
}
std::cout << "'store_cad' ";
if (store_cad)
std::cout << "was set to true";
else
std::cout << "was set to false";
std::cout << endl;
if (x_index == y_index)
{
std::cout << "Warning: x_index = y_index = " << x_index << std::endl;
}
if (x_index == z_index)
{
std::cout << "Warning: x_index = z_index = " << x_index << std::endl;
}
if (y_index == z_index)
{
std::cout << "Warning: y_index = z_index = " << y_index << std::endl;
}
if (fabs (x_scale - STD_X_SCALE) > std::numeric_limits<float>::epsilon () ||
fabs (y_scale - STD_Y_SCALE) > std::numeric_limits<float>::epsilon () ||
fabs (z_scale - STD_Z_SCALE) > std::numeric_limits<float>::epsilon ())
{
this->individual_scale = true;
}
else
{
this->individual_scale = false;
}
config.close ();
}
void
ScanIO_CAD::copyRawData2Vertex (float *raw_data, float *vertex)
{
// copy the raw data to the desired positions
vertex[0] = raw_data[x_index];
vertex[1] = raw_data[y_index];
vertex[2] = raw_data[z_index];
// any axis to be inverted in the data converted to scan coords?
if (invert_x)
vertex[0] *= -1.0f;
if (invert_y)
vertex[1] *= -1.0f;
if (invert_z)
vertex[2] *= -1.0f;
// scale with individual scale_factor
if (individual_scale)
{
vertex[0] *= x_scale;
vertex[1] *= y_scale;
vertex[2] *= z_scale;
// scale additionally with general scale factor
if (combine_scales)
{
vertex[0] *= scale_factor;
vertex[1] *= scale_factor;
vertex[2] *= scale_factor;
}
}
// scale with the general scale factor
else
{
vertex[0] *= scale_factor;
vertex[1] *= scale_factor;
vertex[2] *= scale_factor;
}
}
void
ScanIO_CAD::setUpOptionDescription (void)
{
// just something for a little nicer output formating
std::stringstream x_ss;
x_ss << STD_X_SCALE;
std::stringstream y_ss;
y_ss << STD_Y_SCALE;
std::stringstream z_ss;
z_ss << STD_Z_SCALE;
std::stringstream scale_ss;
scale_ss << STD_SCALE_FACTOR;
// set up the options descriptions
_op_descr.add_options ()
("help", "produce this help message")
("store_cad",
po::value<bool> (&store_cad)->default_value (STD_STORE_CAD),
"determine storage of sampled cad")
("sample_dist",
po::value<float> (&sample_point_dist)->default_value (STD_SAMPLE_DIST),
"approximate distance of sample points")
("random_sampling",
po::value<bool> (&random_sampling)->default_value (STD_RND_SAMP),
"enables/diables random surface sampling")
("x_index",
po::value<unsigned int> (&x_index)->default_value (STD_X_INDEX),
"array index for the x coordinate (default should work for UOS scans)")
("y_index",
po::value<unsigned int> (&y_index)->default_value (STD_Y_INDEX),
"array index for the y coordinate (default should work for UOS scans)")
("z_index",
po::value<unsigned int> (&z_index)->default_value (STD_Z_INDEX),
"array index for the z coordinate (default should work for UOS scans)")
("scale_factor",
po::value<float> (&scale_factor)->default_value (STD_SCALE_FACTOR,
scale_ss.str ()),
"set general scale factor for x-, y- and z-axis")
("x_scale",
po::value<float> (&x_scale)->default_value (STD_X_SCALE, x_ss.str ()),
"scale factor to convert the x coordinate of the CAD models to scan scale")
("y_scale",
po::value<float> (&y_scale)->default_value (STD_Y_SCALE, y_ss.str ()),
"scale factor to convert the y coordinate of the CAD models to scan scale")
("z_scale",
po::value<float> (&z_scale)->default_value (STD_Z_SCALE, z_ss.str ()),
"scale factor to convert the z coordinate of the CAD models to scan scale")
("combine_scales",
po::value<bool> (&combine_scales)->default_value (STD_COMBINE_SCALES),
"enables combining of general scale factor and individual scale factors")
("invert_x",
po::value<bool> (&invert_x)->default_value (STD_INVERT_AXIS),
"inverts the direction of the CAD models x-axis")
("invert_y",
po::value<bool> (&invert_y)->default_value (STD_INVERT_AXIS),
"inverts the direction of the CAD models y-axis")
("invert_z",
po::value<bool> (&invert_z)->default_value (STD_INVERT_AXIS),
"inverts the direction of the CAD models z-axis")
;
}
void
ScanIO_CAD::parseDirForAllSTL (std::string &directory_name)
{
// make sure nothing is stored in the stl file vector
_stl_files.clear ();
// get a directory iterator to mark the end of the directory
fs::path dir (directory_name);
fs::directory_iterator end;
// iterate over the complete directory
for (fs::directory_iterator pos (dir); pos != end; ++pos)
{
if (fs::is_regular_file (*pos))
{
std::string extension;
// retrieve the extension string according to the installed boost API
#if BOOST_VERSION < BOOST_NEW_FS_API
extension = pos->path ().extension ();
#else
extension = pos->path ().extension ().string ();
#endif
std::for_each (extension.begin (), extension.end (), ::tolower);
// add all stl files into the vector
if (extension.compare (".stl") == 0)
{
_stl_files.push_back ((*pos));
}
}
}
_stl_files_pos = 0;
}
bool
ScanIO_CAD::getNextSTLFromDir (fs::path &stl_file)
{
if (_stl_files_pos < _stl_files.size ())
{
stl_file = _stl_files[_stl_files_pos++];
return true;
}
// return an empty path
stl_file = fs::path ();
return false;
}
/**
* class factory for object construction
*
* @return Pointer to new object
*/
#ifdef _MSC_VER
extern "C" __declspec(dllexport) ScanIO* create()
#else
extern "C" ScanIO* create()
#endif
{
return new ScanIO_CAD;
}
/**
* class factory for object construction
*
* @return Pointer to new object
*/
#ifdef _MSC_VER
extern "C" __declspec(dllexport) void destroy(ScanIO *sio)
#else
extern "C" void destroy(ScanIO *sio)
#endif
{
delete sio;
}
#ifdef _MSC_VER
BOOL APIENTRY DllMain(HANDLE hModule, DWORD dwReason, LPVOID lpReserved)
{
return TRUE;
}
#endif

@ -0,0 +1,148 @@
/*
* calibrate implementation
*
* Copyright (C) Stanislav Serebryakov
*
* Released under the GPL version 3.
*
*/
#include <stdio.h>
#include <cv.h>
#include <highgui.h>
void usage(char *progName) {
printf("%s <board-size-x> <board-size-y> <square-size> <images-list>\n", progName);
printf("\twhere board-size-x and y is count of *inner* corners of the booard");
printf("i.e.: %s 6 4 0.04 image*\n", progName);
printf("Use more then ten images.\nPress space bar to proceed.\n");
}
void calibrate( CvMat *intrinsic, CvMat *distortion, CvSize imgSz, CvSize boardSz
, double boardSide, CvPoint2D32f **corners, int boardsCnt) {
int totalPoints = boardSz.width * boardSz.height;
// object points (model)
CvMat *objPts = cvCreateMat(totalPoints * boardsCnt, 3, CV_32FC1);
// found points
CvMat *imgPts = cvCreateMat(totalPoints * boardsCnt, 2, CV_32FC1);
// points count
CvMat *ptsCnt = cvCreateMat(boardsCnt, 1, CV_32SC1);
// copy corners to matrix and fill model matrix
for(int i = 0; i < boardsCnt; i++) {
for(int j = 0; j < totalPoints; j++) {
int s = i * totalPoints;
CV_MAT_ELEM(*imgPts, float, s+j, 0) = corners[i][j].x;
CV_MAT_ELEM(*imgPts, float, s+j, 1) = corners[i][j].y;
CV_MAT_ELEM(*objPts, float, s+j, 0) = boardSide * (j / boardSz.width);
CV_MAT_ELEM(*objPts, float, s+j, 1) = boardSide * (j % boardSz.width);
CV_MAT_ELEM(*objPts, float, s+j, 2) = 0.0f;
}
CV_MAT_ELEM(*ptsCnt, int, i, 0) = totalPoints;
}
// initial guess
CV_MAT_ELEM(*intrinsic, float, 0, 0) = 1.0f;
CV_MAT_ELEM(*intrinsic, float, 1, 1) = 1.0f;
cvCalibrateCamera2( objPts, imgPts, ptsCnt, imgSz
, intrinsic, distortion
, NULL, NULL, 0 );
return;
}
int main(int argc, char **argv)
{
if(argc < 5) {
usage(argv[0]);
exit(1);
}
int patx = atoi(argv[1]);
int paty = atoi(argv[2]);
CvSize boardSz = cvSize(patx, paty);
int loadImageCnt = argc - 4;
int cornersTotal = boardSz.width * boardSz.height;
float boardSide = atof(argv[3]);;
char **images = &argv[4];
// intrinsic matrices and ditortion params
CvMat *intrinsic = cvCreateMat(3, 3, CV_32F);
CvMat *distortion = cvCreateMat(1, 4, CV_32F);
IplImage *img = cvLoadImage(images[0], CV_LOAD_IMAGE_GRAYSCALE);
IplImage *imgColor = cvCreateImage(cvGetSize(img), 8, 3);
int subpixel;
if(cvGetSize(img).width < 300) {
subpixel = 4;
}
else {
subpixel = 11;
}
int imagesWithBoard = 0;
CvPoint2D32f **corners = (CvPoint2D32f**)calloc(100, sizeof(CvPoint2D32f*));
corners[0] = (CvPoint2D32f*) malloc(cornersTotal * sizeof(CvPoint2D32f));
cvNamedWindow("Cam", 0);
for(int imagesLoaded = 0; imagesLoaded < loadImageCnt; imagesLoaded++) {
img = cvLoadImage(images[imagesLoaded], CV_LOAD_IMAGE_GRAYSCALE);
cvCvtColor(img, imgColor, CV_GRAY2BGR);
int cornersCount;
int found = cvFindChessboardCorners(img, boardSz, corners[imagesWithBoard],
&cornersCount, CV_CALIB_CB_ADAPTIVE_THRESH | CV_CALIB_CB_FILTER_QUADS);
if(found) cvFindCornerSubPix(img, corners[imagesWithBoard], cornersCount, cvSize(subpixel, subpixel), cvSize(-1,-1),
cvTermCriteria(CV_TERMCRIT_EPS | CV_TERMCRIT_ITER, 30, 0.1));
if(found && (cornersCount == cornersTotal)) {
cvDrawChessboardCorners(imgColor, boardSz, corners[imagesWithBoard], cornersCount, found);
imagesWithBoard++;
corners[imagesWithBoard] = (CvPoint2D32f*) malloc(cornersTotal * sizeof(CvPoint2D32f));
}
cvShowImage("Cam", imgColor);
cvWaitKey(0);
}
cvDestroyAllWindows();
printf("calibrating...\n");
fflush(stdout);
//TODO: can be started in parallel to watch calibration on image undistortion :)
calibrate(intrinsic, distortion, cvGetSize(img), boardSz, boardSide, corners, imagesWithBoard);
// save to xml files
cvSave("./intrinsic.xml", intrinsic);
cvSave("./distortion.xml", distortion);
printf("matrices saved to xml files.\n");
// let OS clean all images and matrices
return 0;
}
/*void usage(char *progName) {
printf( "usage:\n \
%s <x> <y> <camera-id> [-s]\n \
\tcamera-id is v4l id or -1 for pmd cam \
\tpress space or 'a' to grab image\n \
\tpress 'n' to skip grabbed frame\n \
\tpress 'c' to finish frame grabbing start calibration\n \
or:\n \
%s <x> <y> <image1cam.jpg, image1pmd.jpg, image2cam.png...>\n", progName, progName);
fflush(stdout);
}*/

@ -0,0 +1,209 @@
/////////////////////////////////////////////////////////////////////////////
// Name: spinctld.h
// Purpose: A double valued spin control, compatible with wxSpinCtrl
// Author: John Labenski
// Created: 11/05/02
// Copyright: John Labenski, 2002
// License: wxWidgets
/////////////////////////////////////////////////////////////////////////////
/*
wxSpinCtrlDbl is a double valued wxSpinCtrl using non native (wxWidgets) widgets
It consists of a wxSpinButton and a wxTextCtrl on a wxControl and can be used
as a drop in replacement for the wxSpinCtrl. It's been tested in GTK and MSW
and should work with MAC, but you may need to fix the sizing perhaps. It
will not work in Motif as there is no wxSpinButton in Motif.
Differences to wxSpinCtrl:
It remembers the initial value as a default value, call SetDefaultValue,
or press <ESC> to return to it
Shift + Arrow = *2 increment value
Ctrl + Arrow = *10 increment value
Alt + Arrow = *100 increment value
combinations of Shift, Ctrl, Alt increment by the product of the factors
PgUp & PgDn = *10 increment * the product of the Shift, Ctrl, Alt factors
<SPACE> sets the control's value to the it's last valid state
SetDigits controls the format of the text, # decimal places
exponential uses the %.Xle format otherwise %.Xlf, where places = X
for arbitray formats subclass control and override SyncSpinToText()
for proper behavior when a user types in a value
*/
#ifndef __wxSPINCTRLDBL_H__
#define __wxSPINCTRLDBL_H__
#if defined(__GNUG__) && !defined(NO_GCC_PRAGMA)
#pragma interface "spinctld.h"
#endif
#include "wx/spinbutt.h"
#include "wx/spinctrl.h" // for EVT_SPINCTRL
#include "wx/things/thingdef.h"
class WXDLLEXPORT wxTextCtrl;
class WXDLLIMPEXP_THINGS wxSpinCtrlDblTextCtrl;
enum
{
wxSPINCTRLDBL_AUTODIGITS = -1 // try to autocalc the # of digits
};
class WXDLLIMPEXP_THINGS wxSpinCtrlDbl: public wxControl
{
public:
wxSpinCtrlDbl() : wxControl() { Init(); }
// Native constructor - note &parent, this is to avoid ambiguity
wxSpinCtrlDbl( wxWindow &parent, wxWindowID id,
const wxString &value = wxEmptyString,
const wxPoint& pos = wxDefaultPosition,
const wxSize& size = wxSize(95,-1),
long style = 0,
double min = 0.0, double max = 100.0,
double initial = 0.0,
double increment = 1.0, int digits = wxSPINCTRLDBL_AUTODIGITS,
const wxString& name = _T("wxSpinCtrlDbl") )
{
Init();
Create(&parent, id, value, pos, size, style,
min, max, initial, increment, digits, name);
}
// wxSpinCtrl compatibility, call SetIncrement(increment,digits) after
wxSpinCtrlDbl( wxWindow *parent, wxWindowID id = wxID_ANY,
const wxString &value = wxEmptyString,
const wxPoint& pos = wxDefaultPosition,
const wxSize& size = wxSize(95,-1),
long style = 0,
int min = 0, int max = 100,
int initial = 0,
const wxString& name = _T("wxSpinCtrlDbl") )
{
Init();
Create(parent, id, value, pos, size, style,
(double)min, (double)max, (double)initial, 1.0, -1, name);
}
bool Create( wxWindow *parent,
wxWindowID id = wxID_ANY,
const wxString &value = wxEmptyString,
const wxPoint& pos = wxDefaultPosition,
const wxSize& size = wxSize(100,-1),
long style = 0,
double min = 0.0, double max = 100.0,
double initial = 0.0,
double increment = 1.0, int digits = wxSPINCTRLDBL_AUTODIGITS,
const wxString& name = _T("wxSpinCtrlDbl") );
virtual ~wxSpinCtrlDbl();
// -----------------------------------------------------------------------
// Public (normal usage) functions
enum formatType
{
lf_fmt, // %lf
le_fmt, // %le
lg_fmt // %lg
};
virtual void SetValue( double value );
void SetValue( double value, double min, double max, double increment,
int digits = wxSPINCTRLDBL_AUTODIGITS, formatType fmt = lg_fmt )
{ SetRange(min, max); SetIncrement(increment); SetDigits(digits, fmt); SetValue(value); }
// Set the value as text, if force then set text as is
virtual void SetValue( const wxString& text, bool force );
// Set the allowed range, if max_val < min_val then no range and all vals allowed.
void SetRange( double min_val, double max_val );
// Set the increment to use when the spin button or arrow keys pressed.
void SetIncrement( double increment );
void SetIncrement( double increment, int digits, formatType fmt = lg_fmt )
{ SetIncrement(increment); SetDigits(digits, fmt); }
// Set the number of digits to show, use wxSPINCTRLDBL_AUTODIGITS
// or specify exact number to show i.e. %.[digits]lf
// The format type is used to create an appropriate format string.
void SetDigits( int digits = wxSPINCTRLDBL_AUTODIGITS, formatType fmt = lg_fmt );
// Set the format string to use, ie. format="%.2lf" for .01
void SetFormat( const wxString& format );
// Set the control the the default value.
virtual void SetDefaultValue() { SetValue( m_default_value ); }
// Set the value of the default value, default is the inital value.
void SetDefaultValue( double default_value );
// Force the value to always be divisible by the increment, initially off.
// This uses the default_value as the basis, you'll get strange results
// for very large differences between the current value and default value
// when the increment is very small.
void SetSnapToTicks(bool forceTicks);
double GetValue() const { return m_value; }
double GetMin() const { return m_min; }
double GetMax() const { return m_max; }
virtual bool HasRange() const { return m_max >= m_min; }
virtual bool InRange(double value) const { return !HasRange() || ((value >= m_min) && (value <= m_max)); }
double GetIncrement() const { return m_increment; }
int GetDigits() const { return m_digits; }
wxString GetFormat() const { return m_textFormat; }
double GetDefaultValue() const { return m_default_value; }
bool GetSnapToTicks() const { return m_snap_ticks; }
bool IsDefaultValue() const { return (m_value == m_default_value); }
virtual bool SetFont( const wxFont &font );
wxFont GetFont() const;
virtual bool SetBackgroundColour(const wxColour& colour);
wxColour GetBackgroundColour() const;
virtual bool SetForegroundColour(const wxColour& colour);
wxColour GetForegroundColour() const;
// for setting... stuff
wxTextCtrl *GetTextCtrl() { return (wxTextCtrl*)m_textCtrl; }
protected:
void OnSpinUp( wxSpinEvent &event );
void OnSpinDown( wxSpinEvent &event );
void OnTextEnter( wxCommandEvent &event );
void OnText( wxCommandEvent &event );
// the textctrl is subclassed to get at pgup/dn and then sent here
void OnChar( wxKeyEvent &event );
virtual void SyncSpinToText(bool send_event = true, bool force_valid = true);
void DoSendEvent(); // send an event based on current state
virtual void DoSetSize(int x, int y, int width, int height,
int sizeFlags = wxSIZE_AUTO);
virtual wxSize DoGetBestSize() const;
void OnFocus( wxFocusEvent& event ); // pass focus to textctrl, for wxTAB_TRAVERSAL
void OnKillFocus( wxFocusEvent &event );
wxSpinButton *m_spinButton;
wxSpinCtrlDblTextCtrl *m_textCtrl;
double m_min; // min allowed value
double m_max; // max allowed value
double m_value; // current value
double m_default_value; // initial value, or SetDefaultValue(value)
double m_increment; // how much to to add per spin
int m_digits; // number of digits displayed after decimal point
bool m_snap_ticks; // value is divisible by increment
wxString m_textFormat; // used as wxString.Printf(m_textFormat.c_str(), m_value);
private:
friend class wxSpinCtrlDblTextCtrl;
void Init();
DECLARE_DYNAMIC_CLASS(wxSpinCtrlDbl)
DECLARE_EVENT_TABLE()
};
#endif // __wxSPINCTRLDBL_H__

@ -0,0 +1,241 @@
/**
* @file
* @brief Implementation of reading 3D scans
* @author Kai Lingemann. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Andreas Nuechter. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Jochen Sprickerhof
*/
#include "slam6d/scan_io_uos_map_frames.h"
#include "slam6d/globals.icc"
#include <fstream>
using std::ifstream;
#include <iostream>
using std::cout;
using std::cerr;
using std::endl;
#include <stdexcept>
using std::exception;
#ifdef _MSC_VER
#include <windows.h>
#endif
/**
* Reads specified scans from given directory.
*
* Scan poses will NOT be initialized after a call
* to this function.
*
* This function actually implements loading of 3D scans
* in UOS file format and will be compiled as shared lib.
*
* @param start Starts to read with this scan
* @param end Stops with this scan
* @param dir The directory from which to read
* @param maxDist Reads only Points up to this Distance
* @param minDist Reads only Points from this Distance
* @param euler Initital pose estimates (will not be applied to the points
* @param ptss Vector containing the read points
*/
int ScanIO_uos_map_frames::readScans(int start, int end, string &dir, int maxDist, int mindist,
double *euler, vector<Point> &ptss)
{
static int fileCounter = start - 1;
string scanFileName;
string framesFileName;
ifstream scan_in, frames_in;
double maxDist2 = sqr(maxDist);
int my_fileNr = fileCounter;
double transMat[16];
int type;
if (end > -1 && fileCounter > end) return -1; // 'nuf read
if (fileCounter == start - 1) {
double c, s;
// read map as first 3D scan
#define READ_MAP
#ifdef READ_MAP
scanFileName = dir + "Uni_Hannover.map";
scan_in.open(scanFileName.c_str());
if (!scan_in.good()) { cerr << "ERROR: Missing file " << scanFileName << endl; exit(1); }
cout << "Processing 3D Map " << scanFileName << endl;
euler[0] = euler[1] = euler[2] = euler[3] = euler[4] = euler[5] = 0.0;
c = cos(rad(-191.0));
s = sin(rad(-191.0));
while (scan_in.good()) {
double x1, x2, z1, z2;
double x1_t, x2_t, z1_t, z2_t;
scan_in >> x1_t >> z1_t >> x2_t >> z2_t;
x1_t = (x1_t - 113.07) * 100;
x2_t = (x2_t - 113.07) * 100;
z1_t = (z1_t + 64.05) * 100;
z2_t = (z2_t + 64.05) * 100;
x1 = x1_t * c + z1_t * s;
z1 = - x1_t * s + z1_t * c;
x2 = x2_t * c + z2_t * s;
z2 = - x2_t * s + z2_t * c;
double length = sqrt(sqr(x2-x1) + sqr(z2-z1));
double n_x = (x2 - x1) / length;
double n_z = (z2 - z1) / length;
for (double t = 0.0; t < length; t += 25.0) {
Point p;
p.x = x1 + t * n_x - 713.832183017;
p.z = z1 + t * n_z - 1238.220671;
for (double y = -15.0; y < 1000; y += 25) {
p.y = y + 13.8808;
ptss.push_back(p);
}
}
}
cout << ptss.size() << endl;
scan_in.close();
scan_in.clear();
#endif
#define READ_AERIAL
#ifdef READ_AERIAL
scanFileName = dir + "bereich_uni.txt";
scan_in.open(scanFileName.c_str());
if (!scan_in.good()) { cerr << "ERROR: Missing file " << scanFileName << endl; exit(1); }
cout << "Processing 3D Aerial Map " << scanFileName << endl;
euler[0] = euler[1] = euler[2] = euler[3] = euler[4] = euler[5] = 0.0;
c = cos(rad(-191.0));
s = sin(rad(-191.0));
while (scan_in.good()) {
double x1, z1;
double x1_t, y1_t, z1_t;
scan_in >> x1_t >> z1_t >> y1_t;
x1_t = (x1_t - 3548500 - 113.07) * 100;
z1_t = (z1_t - 5806400 + 64.05) * 100;
y1_t = (y1_t - 55.0) * 100;
x1 = x1_t * c + z1_t * s;
z1 = - x1_t * s + z1_t * c;
Point p;
p.x = x1 - 713.832183017;
p.z = z1 - 1238.220671;
p.y = y1_t + 13.8808;
ptss.push_back(p);
}
cout << "Map containts " << ptss.size() << " points" << endl;
scan_in.close();
scan_in.clear();
#endif
cout << "DONE" << endl;
fileCounter++;
return 1;
}
scanFileName = dir + "scan" + to_string(fileCounter,3) + ".3d";
framesFileName = dir + "scan" + to_string(fileCounter,3) + ".frames";
scan_in.open(scanFileName.c_str());
frames_in.open(framesFileName.c_str());
// read 3D scan
if (!frames_in.good() && !scan_in.good()) return -1; // no more files in the directory
if (!frames_in.good()) { cerr << "ERROR: Missing file " << framesFileName << endl; exit(1); }
if (!scan_in.good()) { cerr << "ERROR: Missing file " << scanFileName << endl; exit(1); }
cout << "Processing Scan " << scanFileName;
while(frames_in) {
try {
frames_in >> transMat >> type;
}
catch(const exception &e) {
break;
}
}
Matrix4ToEuler(transMat, &euler[3], euler);
cout << " @ pose (" << euler[0] << "," << euler[1] << "," << euler[2]
<< "," << euler[3] << "," << euler[4] << "," << euler[5] << ")" << endl;
// overread the first line
char dummy[255];
scan_in.getline(dummy, 255);
while (scan_in.good()) {
Point p;
try {
scan_in >> p;
} catch (...) {
break;
}
// load points up to a certain distance only
// maxDist2 = -1 indicates no limitation
if (maxDist == -1 || sqr(p.x) + sqr(p.y) + sqr(p.z) < maxDist2)
ptss.push_back(p);
}
scan_in.close();
scan_in.clear();
frames_in.close();
frames_in.clear();
fileCounter++;
return my_fileNr;
}
/**
* class factory for object construction
*
* @return Pointer to new object
*/
#ifdef _MSC_VER
extern "C" __declspec(dllexport) ScanIO* create()
#else
extern "C" ScanIO* create()
#endif
{
return new ScanIO_uos_map_frames;
}
/**
* class factory for object construction
*
* @return Pointer to new object
*/
#ifdef _MSC_VER
extern "C" __declspec(dllexport) void destroy(ScanIO *sio)
#else
extern "C" void destroy(ScanIO *sio)
#endif
{
delete sio;
}
#ifdef _MSC_VER
BOOL APIENTRY DllMain(HANDLE hModule, DWORD dwReason, LPVOID lpReserved)
{
return TRUE;
}
#endif

@ -0,0 +1,23 @@
FIND_PACKAGE(OpenCV REQUIRED)
SET(FBR_IO_SRC scan_cv.cc)
add_library(fbr_cv_io STATIC ${FBR_IO_SRC})
SET(FBR_PANORAMA_SRC panorama.cc)
add_library(fbr_panorama STATIC ${FBR_PANORAMA_SRC})
SET(FBR_FEATURE_SRC feature.cc)
add_library(fbr_feature STATIC ${FBR_FEATURE_SRC})
SET(FBR_FEATURE_MATCHER_SRC feature_matcher.cc)
add_library(fbr_feature_matcher STATIC ${FBR_FEATURE_MATCHER_SRC})
SET(FBR_REGISTRATION_SRC registration.cc)
add_library(fbr_registration STATIC ${FBR_REGISTRATION_SRC})
IF(WITH_FBR)
SET(FBR_LIBS scan ANN ${OpenCV_LIBS})
add_executable(featurebasedregistration feature_based_registration.cc fbr_global.cc)
target_link_libraries(featurebasedregistration fbr_cv_io fbr_panorama fbr_feature fbr_feature_matcher fbr_registration ${FBR_LIBS})
ENDIF(WITH_FBR)

@ -0,0 +1,156 @@
------------------------------------------------------------
ann_test: Version 1.0
Copyright: David M. Mount and Sunil Arya.
Latest Revision: Mar 1, 2005.
------------------------------------------------------------
validate = on (Warning: this may slow execution time.)
stats = query_stats
[Read Data Points:
data_size = 5000
file_name = test2-data.pts
dim = 8
]
[Read Query Points:
query_size = 100
file_name = test2-query.pts
dim = 8
]
[Build ann-structure:
split_rule = suggest
shrink_rule = none
data_size = 5000
dim = 8
bucket_size = 1
process_time = 0.18 sec
(Structure Statistics:
n_nodes = 9999 (opt = 10000, best if < 100000)
n_leaves = 5000 (0 contain no points)
n_splits = 4999
n_shrinks = 0
empty_leaves = 0 percent (best if < 50 percent)
depth = 17 (opt = 12, best if < 196)
avg_aspect_ratio = 2.03396 (best if < 20)
)
]
(Computing true nearest neighbors for validation. This may take time.)
[Run Queries:
query_size = 100
dim = 8
search_method = standard
epsilon = 0
near_neigh = 3
true_nn = 13
query_time = 0.0008 sec/query (biased by perf measurements)
(Performance stats: [ mean : stddev ]< min , max >
leaf_nodes = [ 269.6 : 154.1 ]< 68 , 1046 >
splitting_nodes = [ 448.2 : 259.2 ]< 100 , 1858 >
shrinking_nodes = [ 0 : 0 ]< 0 , 0 >
total_nodes = [ 717.8 : 412.6 ]< 168 , 2904 >
points_visited = [ 269.6 : 154.1 ]< 68 , 1046 >
coord_hits/pt = [ 0.1975 : 0.1075 ]< 0.0446 , 0.6974 >
floating_ops_(K) = [ 8.492 : 4.716 ]< 1.939 , 32.61 >
average_error = [ 0 : 0 ]< 0 , 0 >
rank_error = [ 0 : 0 ]< 0 , 0 >
)
]
[Run Queries:
query_size = 100
dim = 8
search_method = priority
epsilon = 0
near_neigh = 3
true_nn = 13
query_time = 0.0011 sec/query (biased by perf measurements)
(Performance stats: [ mean : stddev ]< min , max >
leaf_nodes = [ 237.7 : 131.6 ]< 68 , 801 >
splitting_nodes = [ 408.1 : 227.7 ]< 100 , 1398 >
shrinking_nodes = [ 0 : 0 ]< 0 , 0 >
total_nodes = [ 645.8 : 358.5 ]< 168 , 2149 >
points_visited = [ 237.7 : 131.6 ]< 68 , 801 >
coord_hits/pt = [ 0.1679 : 0.08993 ]< 0.0472 , 0.5492 >
floating_ops_(K) = [ 10.83 : 6.344 ]< 2.638 , 38.3 >
average_error = [ 0 : 0 ]< 0 , 0 >
rank_error = [ 0 : 0 ]< 0 , 0 >
)
]
[Run Queries:
query_size = 100
dim = 8
search_method = standard
epsilon = 0.1
near_neigh = 3
true_nn = 13
query_time = 0.0006 sec/query (biased by perf measurements)
(Performance stats: [ mean : stddev ]< min , max >
leaf_nodes = [ 200.9 : 115.8 ]< 51 , 762 >
splitting_nodes = [ 344.9 : 202.4 ]< 77 , 1407 >
shrinking_nodes = [ 0 : 0 ]< 0 , 0 >
total_nodes = [ 545.9 : 317.4 ]< 128 , 2169 >
points_visited = [ 200.9 : 115.8 ]< 51 , 762 >
coord_hits/pt = [ 0.1548 : 0.08517 ]< 0.0348 , 0.5494 >
floating_ops_(K) = [ 6.606 : 3.703 ]< 1.513 , 25.14 >
average_error = [ 0 : 0 ]< 0 , 0 >
rank_error = [ 0 : 0 ]< 0 , 0 >
)
]
[Run Queries:
query_size = 100
dim = 8
search_method = priority
epsilon = 0.1
near_neigh = 3
true_nn = 13
query_time = 0.0007 sec/query (biased by perf measurements)
(Performance stats: [ mean : stddev ]< min , max >
leaf_nodes = [ 176.1 : 101.1 ]< 49 , 629 >
splitting_nodes = [ 314.3 : 186.9 ]< 77 , 1285 >
shrinking_nodes = [ 0 : 0 ]< 0 , 0 >
total_nodes = [ 490.4 : 286.6 ]< 128 , 1914 >
points_visited = [ 176.1 : 101.1 ]< 49 , 629 >
coord_hits/pt = [ 0.1309 : 0.07112 ]< 0.0374 , 0.4332 >
floating_ops_(K) = [ 8.205 : 4.999 ]< 2.032 , 33.27 >
average_error = [ 0 : 0 ]< 0 , 0 >
rank_error = [ 0 : 0 ]< 0 , 0 >
)
]
[Run Queries:
query_size = 100
dim = 8
search_method = standard
epsilon = 0.5
near_neigh = 3
true_nn = 13
query_time = 0.0002 sec/query (biased by perf measurements)
(Performance stats: [ mean : stddev ]< min , max >
leaf_nodes = [ 83.07 : 46.06 ]< 23 , 264 >
splitting_nodes = [ 163.4 : 94.86 ]< 42 , 512 >
shrinking_nodes = [ 0 : 0 ]< 0 , 0 >
total_nodes = [ 246.5 : 140.2 ]< 67 , 776 >
points_visited = [ 83.07 : 46.06 ]< 23 , 264 >
coord_hits/pt = [ 0.0765 : 0.03992 ]< 0.0182 , 0.2192 >
floating_ops_(K) = [ 3.224 : 1.734 ]< 0.891 , 9.572 >
average_error = [ 0.0009039 : 0.009619 ]< 0 , 0.1516 >
rank_error = [ 0 : 0 ]< 0 , 0 >
)
]
[Run Queries:
query_size = 100
dim = 8
search_method = priority
epsilon = 0.5
near_neigh = 3
true_nn = 13
query_time = 0.0004 sec/query (biased by perf measurements)
(Performance stats: [ mean : stddev ]< min , max >
leaf_nodes = [ 69.72 : 38.29 ]< 21 , 246 >
splitting_nodes = [ 146.8 : 81.69 ]< 40 , 475 >
shrinking_nodes = [ 0 : 0 ]< 0 , 0 >
total_nodes = [ 216.5 : 118.8 ]< 65 , 721 >
points_visited = [ 69.72 : 38.29 ]< 21 , 246 >
coord_hits/pt = [ 0.06206 : 0.03155 ]< 0.0182 , 0.194 >
floating_ops_(K) = [ 3.608 : 1.989 ]< 1.126 , 12.28 >
average_error = [ 0.001425 : 0.011 ]< 0 , 0.1516 >
rank_error = [ 0 : 0 ]< 0 , 0 >
)
]

@ -0,0 +1,287 @@
//#define WANT_STREAM
#include "include.h"
#include "newmat.h"
#include "tmt.h"
#ifdef use_namespace
using namespace NEWMAT;
#endif
/**************************** test program ******************************/
void trymat2()
{
// cout << "\nSecond test of Matrix package\n\n";
Tracer et("Second test of Matrix package");
Tracer::PrintTrace();
int i,j;
Matrix M(3,5);
for (i=1; i<=3; i++) for (j=1; j<=5; j++) M(i,j) = 100*i + j;
Matrix X(8,10);
for (i=1; i<=8; i++) for (j=1; j<=10; j++) X(i,j) = 1000*i + 10*j;
Matrix Y = X; Matrix Z = X;
{ X.SubMatrix(2,4,3,7) << M; }
for (i=1; i<=3; i++) for (j=1; j<=5; j++) Y(i+1,j+2) = 100*i + j;
Print(Matrix(X-Y));
Real a[15]; Real* r = a;
for (i=1; i<=3; i++) for (j=1; j<=5; j++) *r++ = 100*i + j;
{ Z.SubMatrix(2,4,3,7) << a; }
Print(Matrix(Z-Y));
{ M=33; X.SubMatrix(2,4,3,7) << M; }
{ Z.SubMatrix(2,4,3,7) = 33; }
Print(Matrix(Z-X));
for (i=1; i<=8; i++) for (j=1; j<=10; j++) X(i,j) = 1000*i + 10*j;
Y = X;
UpperTriangularMatrix U(5);
for (i=1; i<=5; i++) for (j=i; j<=5; j++) U(i,j) = 100*i + j;
{ X.SubMatrix(3,7,5,9) << U; }
for (i=1; i<=5; i++) for (j=i; j<=5; j++) Y(i+2,j+4) = 100*i + j;
for (i=1; i<=5; i++) for (j=1; j<i; j++) Y(i+2,j+4) = 0.0;
Print(Matrix(X-Y));
for (i=1; i<=8; i++) for (j=1; j<=10; j++) X(i,j) = 1000*i + 10*j;
Y = X;
for (i=1; i<=5; i++) for (j=i; j<=5; j++) U(i,j) = 100*i + j;
{ X.SubMatrix(3,7,5,9).Inject(U); }
for (i=1; i<=5; i++) for (j=i; j<=5; j++) Y(i+2,j+4) = 100*i + j;
Print(Matrix(X-Y));
// test growing and shrinking a vector
{
ColumnVector V(100);
for (i=1;i<=100;i++) V(i) = i*i+i;
V = V.Rows(1,50); // to get first 50 vlaues.
{
V.Release(); ColumnVector VX=V;
V.ReSize(100); V = 0.0; V.Rows(1,50)=VX;
} // V now length 100
M=V; M=100; // to make sure V will hold its values
for (i=1;i<=50;i++) V(i) -= i*i+i;
Print(V);
// test redimensioning vectors with two dimensions given
ColumnVector CV1(10); CV1 = 10;
ColumnVector CV2(5); CV2.ReSize(10,1); CV2 = 10;
V = CV1-CV2; Print(V);
RowVector RV1(20); RV1 = 100;
RowVector RV2; RV2.ReSize(1,20); RV2 = 100;
V = (RV1-RV2).t(); Print(V);
X.ReSize(4,7);
for (i=1; i<=4; i++) for (j=1; j<=7; j++) X(i,j) = 1000*i + 10*j;
Y = 10.5 * X;
Z = 7.25 - Y;
M = Z + X * 10.5 - 7.25;
Print(M);
Y = 2.5 * X;
Z = 9.25 + Y;
M = Z - X * 2.5 - 9.25;
Print(M);
U.ReSize(8);
for (i=1; i<=8; i++) for (j=i; j<=8; j++) U(i,j) = 100*i + j;
Y = 100 - U;
M = Y + U - 100;
Print(M);
}
{
SymmetricMatrix S,T;
S << (U + U.t());
T = 100 - S; M = T + S - 100; Print(M);
T = 100 - 2 * S; M = T + S * 2 - 100; Print(M);
X = 100 - 2 * S; M = X + S * 2 - 100; Print(M);
T = S; T = 100 - T; M = T + S - 100; Print(M);
}
// test new
{
ColumnVector CV1; RowVector RV1;
Matrix* MX; MX = new Matrix; if (!MX) Throw(Bad_alloc("New fails "));
MX->ReSize(10,20);
for (i = 1; i <= 10; i++) for (j = 1; j <= 20; j++)
(*MX)(i,j) = 100 * i + j;
ColumnVector* CV = new ColumnVector(10);
if (!CV) Throw(Bad_alloc("New fails "));
*CV << 1 << 2 << 3 << 4 << 5 << 6 << 7 << 8 << 9 << 10;
RowVector* RV = new RowVector(CV->t() | (*CV + 10).t());
if (!RV) Throw(Bad_alloc("New fails "));
CV1 = ColumnVector(10); CV1 = 1; RV1 = RowVector(20); RV1 = 1;
*MX -= 100 * *CV * RV1 + CV1 * *RV;
Print(*MX);
delete MX; delete CV; delete RV;
}
// test copying of vectors and matrices with no elements
{
ColumnVector dims(16);
Matrix M1; Matrix M2 = M1; Print(M2);
dims(1) = M2.Nrows(); dims(2) = M2.Ncols();
dims(3) = (Real)(unsigned long)M2.Store(); dims(4) = M2.Storage();
M2 = M1;
dims(5) = M2.Nrows(); dims(6) = M2.Ncols();
dims(7) = (Real)(unsigned long)M2.Store(); dims(8) = M2.Storage();
M2.ReSize(10,20); M2.CleanUp();
dims(9) = M2.Nrows(); dims(10) = M2.Ncols();
dims(11) = (Real)(unsigned long)M2.Store(); dims(12) = M2.Storage();
M2.ReSize(20,10); M2.ReSize(0,0);
dims(13) = M2.Nrows(); dims(14) = M2.Ncols();
dims(15) = (Real)(unsigned long)M2.Store(); dims(16) = M2.Storage();
Print(dims);
}
{
ColumnVector dims(16);
ColumnVector M1; ColumnVector M2 = M1; Print(M2);
dims(1) = M2.Nrows(); dims(2) = M2.Ncols()-1;
dims(3) = (Real)(unsigned long)M2.Store(); dims(4) = M2.Storage();
M2 = M1;
dims(5) = M2.Nrows(); dims(6) = M2.Ncols()-1;
dims(7) = (Real)(unsigned long)M2.Store(); dims(8) = M2.Storage();
M2.ReSize(10); M2.CleanUp();
dims(9) = M2.Nrows(); dims(10) = M2.Ncols()-1;
dims(11) = (Real)(unsigned long)M2.Store(); dims(12) = M2.Storage();
M2.ReSize(10); M2.ReSize(0);
dims(13) = M2.Nrows(); dims(14) = M2.Ncols()-1;
dims(15) = (Real)(unsigned long)M2.Store(); dims(16) = M2.Storage();
Print(dims);
}
{
ColumnVector dims(16);
RowVector M1; RowVector M2 = M1; Print(M2);
dims(1) = M2.Nrows()-1; dims(2) = M2.Ncols();
dims(3) = (Real)(unsigned long)M2.Store(); dims(4) = M2.Storage();
M2 = M1;
dims(5) = M2.Nrows()-1; dims(6) = M2.Ncols();
dims(7) = (Real)(unsigned long)M2.Store(); dims(8) = M2.Storage();
M2.ReSize(10); M2.CleanUp();
dims(9) = M2.Nrows()-1; dims(10) = M2.Ncols();
dims(11) = (Real)(unsigned long)M2.Store(); dims(12) = M2.Storage();
M2.ReSize(10); M2.ReSize(0);
dims(13) = M2.Nrows()-1; dims(14) = M2.Ncols();
dims(15) = (Real)(unsigned long)M2.Store(); dims(16) = M2.Storage();
Print(dims);
}
// test identity matrix
{
Matrix M;
IdentityMatrix I(10); DiagonalMatrix D(10); D = 1;
M = I; M -= D; Print(M);
D -= I; Print(D);
ColumnVector X(8);
D = 1;
X(1) = Sum(D) - Sum(I);
X(2) = SumAbsoluteValue(D) - SumAbsoluteValue(I);
X(3) = SumSquare(D) - SumSquare(I);
X(4) = Trace(D) - Trace(I);
X(5) = Maximum(D) - Maximum(I);
X(6) = Minimum(D) - Minimum(I);
X(7) = LogDeterminant(D).LogValue() - LogDeterminant(I).LogValue();
X(8) = LogDeterminant(D).Sign() - LogDeterminant(I).Sign();
Clean(X,0.00000001); Print(X);
for (i = 1; i <= 10; i++) for (j = 1; j <= 10; j++)
M(i,j) = 100 * i + j;
Matrix N;
N = M * I - M; Print(N);
N = I * M - M; Print(N);
N = M * I.i() - M; Print(N);
N = I.i() * M - M; Print(N);
N = I.i(); N -= I; Print(N);
N = I.t(); N -= I; Print(N);
N = I.t(); N += (-I); Print(N); // <----------------
D = I; N = D; D = 1; N -= D; Print(N);
N = I; D = 1; N -= D; Print(N);
N = M + 2 * IdentityMatrix(10); N -= (M + 2 * D); Print(N);
I *= 4;
D = 4;
X.ReSize(14);
X(1) = Sum(D) - Sum(I);
X(2) = SumAbsoluteValue(D) - SumAbsoluteValue(I);
X(3) = SumSquare(D) - SumSquare(I);
X(4) = Trace(D) - Trace(I);
X(5) = Maximum(D) - Maximum(I);
X(6) = Minimum(D) - Minimum(I);
X(7) = LogDeterminant(D).LogValue() - LogDeterminant(I).LogValue(); // <--
X(8) = LogDeterminant(D).Sign() - LogDeterminant(I).Sign();
int i,j;
X(9) = I.Maximum1(i) - 4; X(10) = i-1;
X(11) = I.Maximum2(i,j) - 4; X(12) = i-10; X(13) = j-10;
X(14) = I.Nrows() - 10;
Clean(X,0.00000001); Print(X);
N = D.i();
N += I / (-16);
Print(N);
N = M * I - 4 * M; Print(N);
N = I * M - 4 * M; Print(N);
N = M * I.i() - 0.25 * M; Print(N);
N = I.i() * M - 0.25 * M; Print(N);
N = I.i(); N -= I * 0.0625; Print(N);
N = I.i(); N = N - 0.0625 * I; Print(N);
N = I.t(); N -= I; Print(N);
D = I * 2; N = D; D = 1; N -= 8 * D; Print(N);
N = I * 2; N -= 8 * D; Print(N);
N = 0.5 * I + M; N -= M; N -= 2.0 * D; Print(N);
IdentityMatrix J(10); J = 8;
D = 4;
DiagonalMatrix E(10); E = 8;
N = (I + J) - (D + E); Print(N);
N = (5*I + 3*J) - (5*D + 3*E); Print(N);
N = (-I + J) - (-D + E); Print(N);
N = (I - J) - (D - E); Print(N);
N = (I | J) - (D | E); Print(N);
N = (I & J) - (D & E); Print(N);
N = SP(I,J) - SP(D,E); Print(N);
N = D.SubMatrix(2,5,3,8) - I.SubMatrix(2,5,3,8); Print(N);
N = M; N.Inject(I); D << M; N -= (M + I); N += D; Print(N);
D = 4;
IdentityMatrix K = I.i()*7 - J.t()/4;
N = D.i() * 7 - E / 4 - K; Print(N);
K = I * J; N = K - D * E; Print(N);
N = I * J; N -= D * E; Print(N);
K = 5*I - 3*J;
N = K - (5*D - 3*E); Print(N);
K = I.i(); N = K - 0.0625 * I; Print(N);
K = I.t(); N = K - I; Print(N);
K.ReSize(20); D.ReSize(20); D = 1;
D -= K; Print(D);
I.ReSize(3); J.ReSize(3); K = I * J; N = K - I; Print(N);
K << D; N = K - D; Print(N);
}
// cout << "\nEnd of second test\n";
}

@ -0,0 +1,182 @@
/*
* elch6DunitQuat implementation
*
* Copyright (C) Jochen Sprickerhof
*
* Released under the GPL version 3.
*
*/
/**
* @file ELCH implementation using unit Quaternions
* @author Jochen Sprickerhof. Institute of Computer Science, University of Osnabrueck, Germany.
*/
#include "slam6d/elch6DunitQuat.h"
#include "slam6d/metaScan.h"
#include "slam6d/lum6Dquat.h"
#include "slam6d/globals.icc"
#include <iostream>
using std::cout;
using std::cerr;
using std::endl;
#include <fstream>
using std::ofstream;
#include <boost/graph/graph_traits.hpp>
using boost::graph_traits;
using namespace NEWMAT;
#ifdef _MSC_VER
#define tie tr1::tie
#endif
/**
* ELCH loop closing function using unit Quaternion
* matches first and last scan of a loop with ICP
* distributes the error
*
* @param allScans all laser scans
* @param first index of first laser scan in the loop
* @param last indes of last laser scan in the loop
* @param g graph for loop optimization
*/
void elch6DunitQuat::close_loop(const vector <Scan *> &allScans, int first, int last, graph_t &g)
{
int n = num_vertices(g);
graph_t grb[4];
Matrix C(7, 7);
graph_traits <graph_t>::edge_iterator ei, ei_end;
for(tie(ei, ei_end) = edges(g); ei != ei_end; ei++) {
int from = source(*ei, g);
int to = target(*ei, g);
lum6DQuat::covarianceQuat(allScans[from], allScans[to], my_icp6D->get_nns_method(), my_icp6D->get_rnd(), my_icp6D->get_max_dist_match2(), &C);
C = C.i();
for(int j = 0; j < 3; j++) {
add_edge(from, to, abs(C(j + 1, j + 1)), grb[j]);
}
add_edge(from, to, abs(C(4, 4)) + abs(C(5, 5)) + abs(C(6, 6)) + abs(C(7, 7)), grb[3]);
}
double *weights[4];
for(int i = 0; i < 4; i++) {
weights[i] = new double[n];
graph_balancer(grb[i], first, last, weights[i]);
}
vector <Scan *> meta_start;
meta_start.push_back(allScans[first]);
meta_start.push_back(allScans[first + 1]);
meta_start.push_back(allScans[first + 2]);
MetaScan *start = new MetaScan(meta_start, false, false);
vector <Scan *> meta_end;
meta_end.push_back(allScans[last - 2]);
meta_end.push_back(allScans[last - 1]);
meta_end.push_back(allScans[last]);
MetaScan *end = new MetaScan(meta_end, false, false);
//save poses bevor ICP
double pOld1[7], pOld2[7], pOld3[7];
pOld1[0] = allScans[last]->get_rPos()[0];
pOld1[1] = allScans[last]->get_rPos()[1];
pOld1[2] = allScans[last]->get_rPos()[2];
pOld1[3] = allScans[last]->get_rPosQuat()[0];
pOld1[4] = allScans[last]->get_rPosQuat()[1];
pOld1[5] = allScans[last]->get_rPosQuat()[2];
pOld1[6] = allScans[last]->get_rPosQuat()[3];
pOld2[0] = allScans[last - 1]->get_rPos()[0];
pOld2[1] = allScans[last - 1]->get_rPos()[1];
pOld2[2] = allScans[last - 1]->get_rPos()[2];
pOld2[3] = allScans[last - 1]->get_rPosQuat()[0];
pOld2[4] = allScans[last - 1]->get_rPosQuat()[1];
pOld2[5] = allScans[last - 1]->get_rPosQuat()[2];
pOld2[6] = allScans[last - 1]->get_rPosQuat()[3];
pOld3[0] = allScans[last - 2]->get_rPos()[0];
pOld3[1] = allScans[last - 2]->get_rPos()[1];
pOld3[2] = allScans[last - 2]->get_rPos()[2];
pOld3[3] = allScans[last - 2]->get_rPosQuat()[0];
pOld3[4] = allScans[last - 2]->get_rPosQuat()[1];
pOld3[5] = allScans[last - 2]->get_rPosQuat()[2];
pOld3[6] = allScans[last - 2]->get_rPosQuat()[3];
double delta[3];
delta[0] = allScans[last]->get_rPos()[0];
delta[1] = allScans[last]->get_rPos()[1];
delta[2] = allScans[last]->get_rPos()[2];
double q1[4];
q1[0] = allScans[last]->get_rPosQuat()[0];
q1[1] = -allScans[last]->get_rPosQuat()[1];
q1[2] = -allScans[last]->get_rPosQuat()[2];
q1[3] = -allScans[last]->get_rPosQuat()[3];
my_icp6D->match(start, end);
delete start;
delete end;
delta[0] = allScans[last]->get_rPos()[0] - delta[0];
delta[1] = allScans[last]->get_rPos()[1] - delta[1];
delta[2] = allScans[last]->get_rPos()[2] - delta[2];
double q2[4];
q2[0] = allScans[last]->get_rPosQuat()[0];
q2[1] = allScans[last]->get_rPosQuat()[1];
q2[2] = allScans[last]->get_rPosQuat()[2];
q2[3] = allScans[last]->get_rPosQuat()[3];
double deltaQ[4];
QMult(q2, q1, deltaQ); // q3 = q2*q1^-1
if(!quiet) {
double axisangle[4];
axisangle[0] = deltaQ[0];
axisangle[1] = deltaQ[1];
axisangle[2] = deltaQ[2];
axisangle[3] = deltaQ[3];
QuatToAA(axisangle);
cout << "Delta: " << delta[0] << " " << delta[1] << " " << delta[2] << " " << axisangle[0] << " " << axisangle[1] << " " << axisangle[2] << " " << axisangle[3] << endl;
}
// restore poses after ICP matching
allScans[last]->transformToQuat(pOld1, &pOld1[3], Scan::INVALID, -1);
allScans[last - 1]->transformToQuat(pOld2, &pOld2[3], Scan::INVALID, -1);
allScans[last - 2]->transformToQuat(pOld3, &pOld3[3], Scan::INVALID, -1);
//compute inverse rotation of Scan 0
double scan0Pdelta[4], scan0Q[4];
QMult(deltaQ, allScans[0]->get_rPosQuat(), scan0Pdelta);
scan0Q[0] = (1 - weights[3][0]) * allScans[0]->get_rPosQuat()[0] + scan0Pdelta[0] * weights[3][0];
scan0Q[1] = -1 * ((1 - weights[3][0]) * allScans[0]->get_rPosQuat()[1] + scan0Pdelta[1] * weights[3][0]);
scan0Q[2] = -1 * ((1 - weights[3][0]) * allScans[0]->get_rPosQuat()[2] + scan0Pdelta[2] * weights[3][0]);
scan0Q[3] = -1 * ((1 - weights[3][0]) * allScans[0]->get_rPosQuat()[3] + scan0Pdelta[3] * weights[3][0]);
Normalize4(scan0Q);
QMult(allScans[0]->get_rPosQuat(), scan0Q, scan0Pdelta);
double rPos[3], rPosQuat[4], tmpquat[4];
for(int i = 1; i < n; i++) {
rPos[0] = allScans[i]->get_rPos()[0] + delta[0] * (weights[0][i] - weights[0][0]);
rPos[1] = allScans[i]->get_rPos()[1] + delta[1] * (weights[1][i] - weights[1][0]);
rPos[2] = allScans[i]->get_rPos()[2] + delta[2] * (weights[2][i] - weights[2][0]);
QMult(deltaQ, allScans[i]->get_rPosQuat(), rPosQuat);
tmpquat[0] = (1 - weights[3][i]) * allScans[i]->get_rPosQuat()[0] + rPosQuat[0] * weights[3][i];
tmpquat[1] = (1 - weights[3][i]) * allScans[i]->get_rPosQuat()[1] + rPosQuat[1] * weights[3][i];
tmpquat[2] = (1 - weights[3][i]) * allScans[i]->get_rPosQuat()[2] + rPosQuat[2] * weights[3][i];
tmpquat[3] = (1 - weights[3][i]) * allScans[i]->get_rPosQuat()[3] + rPosQuat[3] * weights[3][i];
Normalize4(tmpquat);
QMult(scan0Pdelta, tmpquat, rPosQuat);
Normalize4(rPosQuat);
allScans[i]->transformToQuat(rPos, rPosQuat, Scan::ELCH, i == n-1 ? 2 : 1);
}
for(int i = 0; i < 4; i++) {
delete [] weights[i];
}
}

@ -0,0 +1,48 @@
//$$ controlw.h Control word class
#ifndef CONTROL_WORD_LIB
#define CONTROL_WORD_LIB 0
// for organising an int as a series of bits which indicate whether an
// option is on or off.
class ControlWord
{
protected:
int cw; // the control word
public:
ControlWord() : cw(0) {} // do nothing
ControlWord(int i) : cw(i) {} // load an integer
// select specific bits (for testing at least one set)
ControlWord operator*(ControlWord i) const
{ return ControlWord(cw & i.cw); }
void operator*=(ControlWord i) { cw &= i.cw; }
// set bits
ControlWord operator+(ControlWord i) const
{ return ControlWord(cw | i.cw); }
void operator+=(ControlWord i) { cw |= i.cw; }
// reset bits
ControlWord operator-(ControlWord i) const
{ return ControlWord(cw - (cw & i.cw)); }
void operator-=(ControlWord i) { cw -= (cw & i.cw); }
// check if all of selected bits set or reset
bool operator>=(ControlWord i) const { return (cw & i.cw) == i.cw; }
bool operator<=(ControlWord i) const { return (cw & i.cw) == cw; }
// flip selected bits
ControlWord operator^(ControlWord i) const
{ return ControlWord(cw ^ i.cw); }
ControlWord operator~() const { return ControlWord(~cw); }
// convert to integer
int operator+() const { return cw; }
int operator!() const { return cw==0; }
FREE_CHECK(ControlWord)
};
#endif

@ -0,0 +1,328 @@
///////////////////////////////////////////////////////////////////////////////
// Name: range.h
// Purpose: Simple min-max range class and associated selection array class
// Author: John Labenski
// Created: 12/01/2000
// Copyright: (c) John Labenski 2004
// Licence: wxWidgets
///////////////////////////////////////////////////////////////////////////////
#ifndef __WX_RANGE_H__
#define __WX_RANGE_H__
#if defined(__GNUG__) && !defined(NO_GCC_PRAGMA)
#pragma interface "range.h"
#endif
#include "wx/things/thingdef.h"
class WXDLLIMPEXP_THINGS wxRangeInt;
class WXDLLIMPEXP_THINGS wxRangeDouble;
class WXDLLIMPEXP_THINGS wxRangeIntSelection;
class WXDLLIMPEXP_THINGS wxRangeDoubleSelection;
#include "wx/dynarray.h"
WX_DECLARE_OBJARRAY_WITH_DECL(wxRangeInt, wxArrayRangeInt, class WXDLLIMPEXP_THINGS);
WX_DECLARE_OBJARRAY_WITH_DECL(wxRangeDouble, wxArrayRangeDouble, class WXDLLIMPEXP_THINGS);
WX_DECLARE_OBJARRAY_WITH_DECL(wxRangeIntSelection, wxArrayRangeIntSelection, class WXDLLIMPEXP_THINGS);
WX_DECLARE_OBJARRAY_WITH_DECL(wxRangeDoubleSelection, wxArrayRangeDoubleSelection, class WXDLLIMPEXP_THINGS);
// Empty versions of ranges (0, -1)
WXDLLIMPEXP_DATA_THINGS(extern const wxRangeInt) wxEmptyRangeInt;
WXDLLIMPEXP_DATA_THINGS(extern const wxRangeDouble) wxEmptyRangeDouble;
//=============================================================================
// wxRangeInt
//=============================================================================
class WXDLLIMPEXP_THINGS wxRangeInt
{
public:
inline wxRangeInt(int min_=0, int max_=0) : m_min(min_), m_max(max_) { }
// Get the width of the range
inline int GetRange() const { return m_max - m_min + 1; }
// Get/Set the min/max values of the range
inline int GetMin() const { return m_min; }
inline int GetMax() const { return m_max; }
inline void SetMin(int min_) { m_min = min_; }
inline void SetMax(int max_) { m_max = max_; }
inline void Set(int min_, int max_) { m_min = min_, m_max = max_; }
// Shift the range by i
void Shift(int i) { m_min += i; m_max += i; }
// Is the range empty, min < max
inline bool IsEmpty() const { return m_min > m_max; }
// Swap the min and max values
inline void SwapMinMax() { register int temp=m_min; m_min=m_max; m_max=temp; }
// returns -1 for i < min, 0 for in range, +1 for i > m_max
inline int Position(int i) const { return i < m_min ? -1 : (i > m_max ? 1 : 0); }
// Is this point or the range within this range
inline bool Contains( int i ) const { return (i >= m_min) && (i <= m_max); }
inline bool Contains( const wxRangeInt &r ) const
{ return (r.m_min >= m_min) && (r.m_max <= m_max); }
// returns if the range intersects the given range
inline bool Intersects(const wxRangeInt& r) const
{ return Intersect(r).IsEmpty(); }
// returns the intersection of the range with the other
inline wxRangeInt Intersect(const wxRangeInt& r) const
{ return wxRangeInt(wxMax(m_min, r.m_min), wxMin(m_max, r.m_max)); }
// returns the union of the range with the other
inline wxRangeInt Union(const wxRangeInt& r) const
{ return wxRangeInt(wxMin(m_min, r.m_min), wxMax(m_max, r.m_max)); }
// Is this point inside or touches +/- 1 of the range
inline bool Touches( int i ) const
{ return !IsEmpty() && wxRangeInt(m_min-1, m_max+1).Contains(i); }
// Is the range adjoining this range
inline bool Touches( const wxRangeInt &r ) const
{ if (IsEmpty() || r.IsEmpty()) return false;
wxRangeInt rExp(m_min-1, m_max+1);
return rExp.Contains(r.m_min) || rExp.Contains(r.m_max); }
// combine this single point with the range by expanding the m_min/m_max to contain it
// if only_if_touching then only combine if i is just outside the range by +/-1
// returns true if the range has been changed at all, false if not
bool Combine(int i, bool only_if_touching = false);
bool Combine(const wxRangeInt &r, bool only_if_touching = false);
// delete range r from this, return true is anything was done
// if r spans this then this and right become wxEmptyRangeInt
// else if r is inside of this then this is the left side and right is the right
// else if r.m_min > m_min then this is the left side
// else if r.m_min < m_min this is the right side
bool Delete( const wxRangeInt &r, wxRangeInt *right=NULL );
// operators
// no copy ctor or assignment operator - the defaults are ok
// comparison
inline bool operator==(const wxRangeInt& r) const { return (m_min == r.m_min)&&(m_max == r.m_max); }
inline bool operator!=(const wxRangeInt& r) const { return !(*this == r); }
// Adding ranges unions them to create the largest range
inline wxRangeInt operator+(const wxRangeInt& r) const { return Union(r); }
inline wxRangeInt& operator+=(const wxRangeInt& r) { if(r.m_min<m_min) m_min=r.m_min; if(r.m_max>m_max) m_max=r.m_max; return *this; }
// Subtracting ranges intersects them to get the smallest range
inline wxRangeInt operator-(const wxRangeInt& r) const { return Intersect(r); }
inline wxRangeInt& operator-=(const wxRangeInt& r) { if(r.m_min>m_min) m_min=r.m_min; if(r.m_max<m_max) m_max=r.m_max; return *this; }
// Adding/Subtracting with an int shifts the range
inline wxRangeInt operator+(const int i) const { return wxRangeInt(m_min+i, m_max+i); }
inline wxRangeInt operator-(const int i) const { return wxRangeInt(m_min-i, m_max-i); }
inline wxRangeInt& operator+=(const int i) { Shift( i); return *this; }
inline wxRangeInt& operator-=(const int i) { Shift(-i); return *this; }
int m_min, m_max;
};
//=============================================================================
// wxRangeIntSelection - ordered 1D array of wxRangeInts, combines to minimze size
//=============================================================================
class WXDLLIMPEXP_THINGS wxRangeIntSelection
{
public :
wxRangeIntSelection() {}
wxRangeIntSelection(const wxRangeInt& range) { if (!range.IsEmpty()) m_ranges.Add(range); }
wxRangeIntSelection(const wxRangeIntSelection &ranges) { Copy(ranges); }
// Make a full copy of the source
void Copy(const wxRangeIntSelection &source)
{
m_ranges.Clear();
WX_APPEND_ARRAY(m_ranges, source.GetRangeArray());
}
// Get the number of individual ranges
inline int GetCount() const { return m_ranges.GetCount(); }
// Get total number of items selected in all ranges, ie. sum of all wxRange::GetWidths
int GetItemCount() const;
// Get the ranges themselves to iterate though for example
const wxArrayRangeInt& GetRangeArray() const { return m_ranges; }
// Get a single range
const wxRangeInt& GetRange( int index ) const;
inline const wxRangeInt& Item( int index ) const { return GetRange(index); }
// Get a range of the min range value and max range value
wxRangeInt GetBoundingRange() const;
// Clear all the ranges
void Clear() { m_ranges.Clear(); }
// Is this point or range contained in the selection
inline bool Contains( int i ) const { return Index(i) != wxNOT_FOUND; }
inline bool Contains( const wxRangeInt &range ) const { return Index(range) != wxNOT_FOUND; }
// Get the index of the range that contains this, or wxNOT_FOUND
int Index( int i ) const;
int Index( const wxRangeInt &range ) const;
// Get the nearest index of a range, index returned contains i or is the one just below
// returns -1 if it's below all the selected ones, or no ranges
// returns GetCount() if it's above all the selected ones
int NearestIndex( int i ) const;
// Add the range to the selection, returning if anything was done, false if already selected
bool SelectRange( const wxRangeInt &range );
// Remove the range to the selection, returning if anything was done, false if not already selected
bool DeselectRange( const wxRangeInt &range );
// Set the min and max bounds of the ranges, returns true if anything was done
bool BoundRanges( const wxRangeInt &range );
// operators
inline const wxRangeInt& operator[](int index) const { return GetRange(index); }
wxRangeIntSelection& operator = (const wxRangeIntSelection& other) { Copy(other); return *this; }
protected :
wxArrayRangeInt m_ranges;
};
//=============================================================================
// wxRangeDouble
//=============================================================================
class WXDLLIMPEXP_THINGS wxRangeDouble
{
public:
inline wxRangeDouble(wxDouble min_=0, wxDouble max_=0) : m_min(min_), m_max(max_) {}
// Get the width of the range
inline wxDouble GetRange() const { return m_max - m_min; }
// Get/Set the min/max values of the range
inline wxDouble GetMin() const { return m_min; }
inline wxDouble GetMax() const { return m_max; }
inline void SetMin(wxDouble min_) { m_min = min_; }
inline void SetMax(wxDouble max_) { m_max = max_; }
inline void Set(wxDouble min_, wxDouble max_) { m_min = min_, m_max = max_; }
// Shift the range by i
void Shift(wxDouble i) { m_min += i; m_max += i; }
// Is the range empty, min < max
inline bool IsEmpty() const { return m_min > m_max; }
// Swap the min and max values
inline void SwapMinMax() { register wxDouble temp = m_min; m_min = m_max; m_max = temp; }
// returns -1 for i < min, 0 for in range, +1 for i > m_max
inline int Position(wxDouble i) const { return i < m_min ? -1 : i > m_max ? 1 : 0; }
// Is this point or the range within this range
inline bool Contains( wxDouble i ) const { return (i>=m_min)&&(i<=m_max); }
inline bool Contains( const wxRangeDouble &r ) const
{ return (r.m_min>=m_min)&&(r.m_max<=m_max); }
// returns if the range intersects the given range
inline bool Intersects(const wxRangeDouble& r) const
{ return Intersect(r).IsEmpty(); }
// returns the intersection of the range with the other
inline wxRangeDouble Intersect(const wxRangeDouble& r) const
{ return wxRangeDouble(wxMax(m_min, r.m_min), wxMin(m_max, r.m_max)); }
// returns the union of the range with the other
inline wxRangeDouble Union(const wxRangeDouble& r) const
{ return wxRangeDouble(wxMin(m_min, r.m_min), wxMax(m_max, r.m_max)); }
// no touches for double since what would be a good eps value?
// combine this single point with the range by expanding the m_min/m_max to contain it
// if only_if_touching then only combine if there is overlap
// returns true if the range has been changed at all, false if not
bool Combine(wxDouble i);
bool Combine( const wxRangeDouble &r, bool only_if_touching = false );
// delete range r from this, return true is anything was done
// if r spans this then this and right become wxEmptyRangeInt
// else if r is inside of this then this is the left side and right is the right
// else if r.m_min > m_min then this is the left side
// else if r.m_min < m_min this is the right side
bool Delete( const wxRangeDouble &r, wxRangeDouble *right=NULL );
// operators
// no copy ctor or assignment operator - the defaults are ok
// comparison
inline bool operator==(const wxRangeDouble& r) const { return (m_min == r.m_min)&&(m_max == r.m_max); }
inline bool operator!=(const wxRangeDouble& r) const { return !(*this == r); }
// Adding ranges unions them to create the largest range
inline wxRangeDouble operator+(const wxRangeDouble& r) const { return Union(r); }
inline wxRangeDouble& operator+=(const wxRangeDouble& r) { if(r.m_min<m_min) m_min=r.m_min; if(r.m_max>m_max) m_max=r.m_max; return *this; }
// Subtracting ranges intersects them to get the smallest range
inline wxRangeDouble operator-(const wxRangeDouble& r) const { return Intersect(r); }
inline wxRangeDouble& operator-=(const wxRangeDouble& r) { if(r.m_min>m_min) m_min=r.m_min; if(r.m_max<m_max) m_max=r.m_max; return *this; }
// Adding/Subtracting with a double shifts the range
inline wxRangeDouble operator+(const wxDouble i) const { return wxRangeDouble(m_min+i, m_max+i); }
inline wxRangeDouble operator-(const wxDouble i) const { return wxRangeDouble(m_min-i, m_max-i); }
inline wxRangeDouble& operator+=(const wxDouble i) { Shift( i); return *this; }
inline wxRangeDouble& operator-=(const wxDouble i) { Shift(-i); return *this; }
wxDouble m_min, m_max;
};
//=============================================================================
// wxRangeDoubleSelection - ordered 1D array of wxRangeDoubles, combines to minimze size
//=============================================================================
class WXDLLIMPEXP_THINGS wxRangeDoubleSelection
{
public :
wxRangeDoubleSelection() {}
wxRangeDoubleSelection(const wxRangeDouble& range) { if (!range.IsEmpty()) m_ranges.Add(range); }
wxRangeDoubleSelection(const wxRangeDoubleSelection &ranges) { Copy(ranges); }
// Make a full copy of the source
void Copy(const wxRangeDoubleSelection &source)
{
m_ranges.Clear();
WX_APPEND_ARRAY(m_ranges, source.GetRangeArray());
}
// Get the number of individual ranges
inline int GetCount() const { return m_ranges.GetCount(); }
// Get the ranges themselves to iterate though for example
const wxArrayRangeDouble& GetRangeArray() const { return m_ranges; }
// Get a single range
const wxRangeDouble& GetRange( int index ) const;
inline const wxRangeDouble& Item( int index ) const { return GetRange(index); }
// Get a range of the min range value and max range value
wxRangeDouble GetBoundingRange() const;
// Clear all the ranges
void Clear() { m_ranges.Clear(); }
// Is this point or range contained in the selection
inline bool Contains( wxDouble i ) const { return Index(i) != wxNOT_FOUND; }
inline bool Contains( const wxRangeDouble &range ) const { return Index(range) != wxNOT_FOUND; }
// Get the index of the range that contains this, or wxNOT_FOUND
int Index( wxDouble i ) const;
int Index( const wxRangeDouble &range ) const;
// Get the nearest index of a range, index returned contains i or is the one just below
// returns -1 if it's below all the selected ones, or no ranges
// returns GetCount() if it's above all the selected ones
int NearestIndex( wxDouble i ) const;
// Add the range to the selection, returning if anything was done, false if already selected
bool SelectRange( const wxRangeDouble &range);
// Remove the range to the selection, returning if anything was done, false if not already selected
bool DeselectRange( const wxRangeDouble &range);
// Set the min and max bounds of the ranges, returns true if anything was done
bool BoundRanges( const wxRangeDouble &range );
// operators
inline const wxRangeDouble& operator[](int index) const { return GetRange(index); }
wxRangeDoubleSelection& operator = (const wxRangeDoubleSelection& other) { Copy(other); return *this; }
protected :
wxArrayRangeDouble m_ranges;
};
#endif // __WX_RANGE_H__

@ -0,0 +1,36 @@
#ifndef __THERMO_H__
#define __THERMO_H__
#include <opencv/cv.h>
#include <opencv/highgui.h>
#include <string>
#include <slam6d/scan.h>
using namespace std;
typedef vector<vector<float> > Float2D[1200][1600];
void calcBoard(double point_array[][2], int board_n, double &x, double &y, double &cx, double &cy, bool pc);
void sortBlobs(double point_array[][2], int board_n, int board_h, int board_w, bool quiet);
IplImage* detectBlobs(IplImage *org_image, int &corner_exp, int board_h, int board_w, bool quiet, double point_array2[][2]);
void drawLines(double point_array2[][2], int corner_exp, IplImage *image, bool color=false);
IplImage* resizeImage(IplImage *source, int scale);
IplImage* detectCorners(IplImage *orgimage, int corner_exp, int board_h, int board_w, bool quiet, double point_array2[][2], int scale=1);
void CalibFunc(int board_w, int board_h, int start, int end, bool optical, bool chess, bool quiet, string dir, int scale=1);
void writeCalibParam(int images, int corner_exp, int board_w, CvMat* image_points, CvSize size, string dir);
void ProjectAndMap(int start, int end, bool optical, bool quiet, string dir,
IOType type, int scale, double rot_angle, double minDist, double maxDist,
bool correction, int neighborhood, int method=0);
bool readPoints(string filename, CvPoint3D32f *corners, int size) ;
void sortElementByElement(CvMat * vectors, int nr_elems, int nr_vectors);
void calculateExtrinsicsWithReprojectionCheck(CvMat * points2D, CvMat *
points3D, CvMat * rotation_vectors_temp, CvMat * translation_vectors_temp, CvMat
* distortions, CvMat * instrinsics, int corners, int successes, string dir, bool quiet=true, string substring = "") ;
void calculateExtrinsics(CvMat * rotation_vectors_temp, CvMat * translation_vectors_temp, int successes, string dir, bool quiet=true, string substring = "") ;
void CorrectErrorAndWrite(Float2D &data, fstream &outfile, CvSize size);
void clusterSearch(float ** points, int size, double thresh1, double thresh2, fstream &outfile);
void sortDistances(float ** points, int size);
void ExtrCalibFunc(int board_w, int board_h, int start, int end, bool optical, bool chess, bool quiet, string dir, int scale=1);
#endif

@ -0,0 +1,36 @@
/**
* @file
* @brief IO of 3D scans in Riegl file format
* @author Kai Lingemann. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Andreas Nuechter. Institute of Computer Science, University of Osnabrueck, Germany.
*/
#ifndef __SCAN_IO_RIEGL_PROJECT_H
#define __SCAN_IO_RIEGL_PROJECT_H
#include <string>
using std::string;
#include <vector>
using std::vector;
#include "scan_io.h"
/**
* @brief 3D scan loader for Riegl scans in the binary rxp format
*
* The compiled class is available as shared object file
*/
class ScanIO_riegl_project : public ScanIO {
public:
virtual int readScans(int start, int end, string &dir, int maxDist, int mindist,
double *euler, vector<Point> &ptss);
};
// Since this shared object file is loaded on the fly, we
// need class factories
// the types of the class factories
typedef ScanIO* create_sio();
typedef void destroy_sio(ScanIO*);
#endif

@ -0,0 +1,22 @@
/**
* @file ELCH implementation using unit Quaternions
* @author Jochen Sprickerhof. Institute of Computer Science, University of Osnabrueck, Germany.
*/
#ifndef __ELCH6D_UINTQUAT_H__
#define __ELCH6D_UNITQUAT_H__
#include "elch6D.h"
class elch6DunitQuat : public elch6D {
public:
elch6DunitQuat(bool _quiet, icp6Dminimizer *my_icp6Dminimizer, double mdm, int max_num_iterations,
int rnd, bool eP, int anim, double epsilonICP, int nns_method)
: elch6D(_quiet, my_icp6Dminimizer, mdm, max_num_iterations, rnd, eP, anim, epsilonICP, nns_method) {}
virtual void close_loop(const vector <Scan *> &allScans, int first, int last, graph_t &g);
};
#endif

@ -0,0 +1,122 @@
/*
* grabVideoAnd3D implementation
*
* Copyright (C) Stanislav Serebryakov
*
* Released under the GPL version 3.
*
*/
#include <stdio.h>
#include <stdlib.h>
#include <cv.h>
#include <highgui.h>
#include "pmdsdk2.h"
#include "cvpmd.h"
int main(int argc, char **argv)
{
int totalFrames = 0;
int ui = 1;
printf("%i\n", argc);
if(argc > 1) {
totalFrames = atoi(argv[1]);
ui = 0;
}
if(argc > 2) ui = 1;
//FIXME: here is lots of old code, should be removed
PMD *pmd = initPMD("../o3d.L32.pcp", "192.168.0.69");
CvCapture *capture = cvCaptureFromCAM(1); //FIXME: should be passed via argc
CvSize pmdSz = pmdGetSize(pmd);
printf("pmd sz: %i x %i\n", pmdSz.width, pmdSz.height);
IplImage *imgCamColor = cvQueryFrame(capture);
IplImage *imgPMD = cvCreateImage(pmdGetSize(pmd), 8, 1);
IplImage *imgPMDA = cvCreateImage(cvGetSize(imgPMD), 8, 1);
IplImage *imgCam = cvCreateImage(cvGetSize(imgCamColor), 8, 1);
CvPoint3D32f **pmdPts = (CvPoint3D32f**) cvAlloc(pmdSz.height * sizeof(CvPoint3D32f*));
for(int i = 0; i < pmdSz.height; i++) pmdPts[i] = (CvPoint3D32f*) cvAlloc(pmdSz.width * sizeof(CvPoint3D32f));
CvMat *intrinsicCam = (CvMat*)cvLoad("../intrinsic-cam-6x4.xml");
CvMat *distortionCam = (CvMat*)cvLoad("../distortion-cam-6x4.xml");
CvMat *intrinsicPMD = (CvMat*)cvLoad("../intrinsic-pmd-6x4.xml");
CvMat *distortionPMD = (CvMat*)cvLoad("../distortion-pmd-6x4.xml");
if(!intrinsicCam || !distortionCam|| !intrinsicPMD || !distortionPMD) {
fprintf(stderr, "ERROR: can't load intrinsic and/or distortion xml files!\n");
return 1;
}
// FILE *vPMDA = fopen("./s001.arv", "wb"); // ala dot Amplitudes Raw Video NOTE: i'm not sure it is amplitude :P
// FILE *vPMDAf = fopen("./s001.farv", "wb"); // same but Floating
FILE *vPMDI = fopen("./s001.irv", "wb"); // same but Intensities
FILE *vPMDIf = fopen("./s001.firv", "wb");
FILE *headers = fopen("./s001.head", "wb");
CvVideoWriter *vCam = cvCreateVideoWriter( "./s001.avi"
, CV_FOURCC('D', 'I', 'V', 'X')
, 25, cvGetSize(imgCam), 1);
FILE *pmdPtsFile = fopen("./s001.3dp", "w");
if(ui) {
cvNamedWindow("Cam", 0);
cvNamedWindow("PMD", 1);
}
printf("DEBUG: init done, going to grab %i frames.\n", totalFrames);
int frames = 0;
while(1) {
frames++;
if(0 == frames % 100) printf("%i frames grabbed...\n", frames);
// Image retriving
pmdUpdate(pmd->hnd);
imgCamColor = cvQueryFrame(capture);
pmdQueryImageAsync(pmd, imgPMD);
fwrite(pmdDataPtr(pmd), sizeof(float), pmdSz.width*pmdSz.height, vPMDIf);
//pmdQueryAmplitudesAsync(pmd, imgPMDA);
//fwrite(pmdDataPtr(pmd), sizeof(float), pmdSz.width*pmdSz.height, vPMDAf);
pmdRetriveDistancesAsync(pmd);
pmdProjectArrayToCartesian(pmd, intrinsicPMD, pmdPts);
ImageHeaderInformation *header = retriveHeader();
if(ui) {
cvShowImage("Cam", imgCamColor);
cvShowImage("PMD", imgPMD);
}
//FIXME: order col/str
for(int i = 0; i < pmdSz.height; i++)
fwrite(pmdPts[i], sizeof(CvPoint3D32f), pmdSz.width, pmdPtsFile);
fwrite(imgPMD->imageData, sizeof(char), pmdSz.width*pmdSz.height, vPMDI);
//fwrite(imgPMDA->imageData, sizeof(char), pmdSz.width*pmdSz.height, vPMDA);
fwrite(header, sizeof(ImageHeaderInformation), 1, headers);
cvWriteFrame(vCam, imgCamColor);
if(totalFrames && (frames >= totalFrames)) break;
if(ui) if(27 == cvWaitKey(5)) break;
}
// fclose(vPMDA);
// fclose(vPMDAf);
fclose(vPMDI);
fclose(vPMDIf);
fclose(pmdPtsFile);
fclose(headers);
printf("grabbed %i frames.\n", frames);
printf("See s001* files (you want to rename them).\n");
}

@ -0,0 +1,30 @@
/**
* @file
* @brief IO of a 3D scan in rts file format
* @author Thomas Escher
*/
#ifndef __SCAN_IO_UOS_H__
#define __SCAN_IO_UOS_H__
#include "scan_io.h"
/**
* @brief 3D scan loader for RTS scans
*
* The compiled class is available as shared object file
*/
class ScanIO_rts : public ScanIO {
public:
virtual std::list<std::string> readDirectory(const char* dir_path, unsigned int start, unsigned int end);
virtual void readPose(const char* dir_path, const char* identifier, double* pose);
virtual void readScan(const char* dir_path, const char* identifier, PointFilter&& filter, std::vector<double>* xyz, std::vector<unsigned char>* rgb, std::vector<float>* reflectance, std::vector<float>* amplitude, std::vector<int>* type, std::vector<float>* deviation);
virtual bool supports(IODataType type);
private:
std::string cached_dir;
std::vector<double> cached_poses;
};
#endif

@ -0,0 +1,38 @@
/** @file
* @brief Definition of the ICP error function minimization
* @author Peter Schneider. Institute of Computer Science, University of Koblenz and Landau, Germany.
* @author Andreas Nuechter. Jacobs University Bremen gGmbH, Germany
*/
#ifndef __ICP6DHELIX_H__
#define __ICP6DHELIX_H__
#include "icp6Dminimizer.h"
#include "newmat/newmatio.h"
using namespace NEWMAT;
/**
* @brief Implementation of the ICP error function minimization via helix-translation
*/
class icp6D_HELIX : public icp6Dminimizer
{
public:
/**
* Constructor
*/
icp6D_HELIX(bool quiet = false) : icp6Dminimizer(quiet) {};
/**
* Destructor
*/
virtual ~icp6D_HELIX() {};
double Point_Point_Align(const vector<PtPair>& Pairs, double *alignxf,
const double centroid_m[3], const double centroid_d[3]);
static void computeRt(const ColumnVector* ccs, const int vectorOffset, double *alignxf);
inline int getAlgorithmID() { return 5; };
};
#endif

@ -0,0 +1,180 @@
/**
* @file
* @brief Implementation of reading 3D scans
* @author Andreas Nuechter. Jacobs University Bremen gGmbH
* @author Dorit Borrmann. Smart Systems Group, Jacobs University Bremen gGmbH, Germany.
*/
#include "slam6d/scan_io_riegl_txt.h"
#include "slam6d/globals.icc"
#include <fstream>
using std::ifstream;
#include <iostream>
using std::cerr;
using std::endl;
#include <algorithm>
using std::swap;
#ifdef _MSC_VER
#include <windows.h>
#endif
/**
* Reads specified scans from given directory in
* the file format Riegl Laser Measurement GmbH
* uses. It will be compiled as shared lib.
*
* Scan poses will NOT be initialized after a call
* to this function. Initial pose estimation works
* only with the -p switch, i.e., trusting the initial
* estimations by Riegl.
*
* The scans have to be exported from the Riegl software
* as follows:
* 1. Export point cloud data to ASCII
* Use Scanners own Coordinate System (SOCS)
* X Y Z Range Theta Phi Reflectance
* 2. Export acqusition location (after you have registered
* with the Riegl software)
* Export SOP
* Write out as .dat file
*
* @param start Starts to read with this scan
* @param end Stops with this scan
* @param dir The directory from which to read
* @param maxDist Reads only Points up to this Distance
* @param minDist Reads only Points from this Distance
* @param euler Initital pose estimates (will not be applied to the points
* @param ptss Vector containing the read points
*/
int ScanIO_riegl_txt::readScans(int start, int end, string &dir, int maxDist, int minDist,
double *euler, vector<Point> &ptss)
{
static int fileCounter = start;
string scanFileName;
string poseFileName;
double maxDist2 = sqr(maxDist);
double minDist2 = sqr(minDist);
ifstream scan_in, pose_in;
if (end > -1 && fileCounter > end) return -1; // 'nuf read
poseFileName = dir + "scan" + to_string(fileCounter,3) + ".dat";
scanFileName = dir + "scan" + to_string(fileCounter,3) + ".txt";
scan_in.open(scanFileName.c_str());
pose_in.open(poseFileName.c_str());
// read 3D scan
if (!pose_in.good() && !scan_in.good()) return -1; // no more files in the directory
if (!pose_in.good()) { cerr << "ERROR: Missing file " << poseFileName << endl; exit(1); }
if (!scan_in.good()) { cerr << "ERROR: Missing file " << scanFileName << endl; exit(1); }
cout << "Processing Scan " << scanFileName;
cout.flush();
double rPos[3], rPosTheta[16];
double inMatrix[16], tMatrix[16];
for (unsigned int i = 0; i < 16; pose_in >> inMatrix[i++]);
// transform input pose
tMatrix[0] = inMatrix[5];
tMatrix[1] = -inMatrix[9];
tMatrix[2] = -inMatrix[1];
tMatrix[3] = -inMatrix[13];
tMatrix[4] = -inMatrix[6];
tMatrix[5] = inMatrix[10];
tMatrix[6] = inMatrix[2];
tMatrix[7] = inMatrix[14];
tMatrix[8] = -inMatrix[4];
tMatrix[9] = inMatrix[8];
tMatrix[10] = inMatrix[0];
tMatrix[11] = inMatrix[12];
tMatrix[12] = -inMatrix[7];
tMatrix[13] = inMatrix[11];
tMatrix[14] = inMatrix[3];
tMatrix[15] = inMatrix[15];
Matrix4ToEuler(tMatrix, rPosTheta, rPos);
euler[0] = 100*rPos[0];
euler[1] = 100*rPos[1];
euler[2] = 100*rPos[2];
euler[3] = rPosTheta[0];
euler[4] = rPosTheta[1];
euler[5] = rPosTheta[2];
long num_pts = 0;
if (scan_in.good()) {
scan_in >> num_pts;
cout << " with " << num_pts << " Points";
cout.flush();
ptss.reserve(num_pts);
}
// read point data and transform into slam6D coordinate system
while (scan_in.good()) {
Point p;
double range, theta, phi, reflectance;
scan_in >> p.z >> p.x >> p.y >> range >> theta >> phi >> reflectance;
p.x *= -100;
p.y *= 100;
p.z *= 100;
p.reflectance = reflectance;
if (maxDist == -1 || sqr(p.x) + sqr(p.y) + sqr(p.z) < maxDist2)
if (minDist == -1 || sqr(p.x) + sqr(p.y) + sqr(p.z) > minDist2)
ptss.push_back(p);
}
cout << " done" << endl;
scan_in.close();
scan_in.clear();
pose_in.close();
pose_in.clear();
fileCounter++;
return fileCounter-1;
}
/**
* class factory for object construction
*
* @return Pointer to new object
*/
#ifdef _MSC_VER
extern "C" __declspec(dllexport) ScanIO* create()
#else
extern "C" ScanIO* create()
#endif
{
return new ScanIO_riegl_txt;
}
/**
* class factory for object construction
*
* @return Pointer to new object
*/
#ifdef _MSC_VER
extern "C" __declspec(dllexport) void destroy(ScanIO *sio)
#else
extern "C" void destroy(ScanIO *sio)
#endif
{
delete sio;
}
#ifdef _MSC_VER
BOOL APIENTRY DllMain(HANDLE hModule, DWORD dwReason, LPVOID lpReserved)
{
return TRUE;
}
#endif

@ -0,0 +1,42 @@
inline void D2Tree::calcDivide(double x_size, double y_size, double z_size,
double center[3],
double &x_sizeNew, double &y_sizeNew, double &z_sizeNew,
double newcenter[8][3])
{
x_sizeNew = x_size * 0.5;
y_sizeNew = y_size * 0.5;
z_sizeNew = z_size * 0.5;
newcenter[0][0] = center[0] - x_sizeNew;
newcenter[0][1] = center[1] - y_sizeNew;
newcenter[0][2] = center[2] - z_sizeNew;
newcenter[1][0] = center[0] + x_sizeNew;
newcenter[1][1] = center[1] - y_sizeNew;
newcenter[1][2] = center[2] - z_sizeNew;
newcenter[2][0] = center[0] - x_sizeNew;
newcenter[2][1] = center[1] + y_sizeNew;
newcenter[2][2] = center[2] - z_sizeNew;
newcenter[3][0] = center[0] - x_sizeNew;
newcenter[3][1] = center[1] - y_sizeNew;
newcenter[3][2] = center[2] + z_sizeNew;
newcenter[4][0] = center[0] + x_sizeNew;
newcenter[4][1] = center[1] + y_sizeNew;
newcenter[4][2] = center[2] - z_sizeNew;
newcenter[5][0] = center[0] + x_sizeNew;
newcenter[5][1] = center[1] - y_sizeNew;
newcenter[5][2] = center[2] + z_sizeNew;
newcenter[6][0] = center[0] - x_sizeNew;
newcenter[6][1] = center[1] + y_sizeNew;
newcenter[6][2] = center[2] + z_sizeNew;
newcenter[7][0] = center[0] + x_sizeNew;
newcenter[7][1] = center[1] + y_sizeNew;
newcenter[7][2] = center[2] + z_sizeNew;
}

@ -0,0 +1,77 @@
/***************By yuanjun**************************/
#pragma once
#include "veloslam/veloscan.h"
#include "veloslam/matrix.h"
using namespace std;
typedef struct _X_state
{
float x_position;
float z_positon;
float x_speed;
float z_speed;
}ObjectState;
typedef struct _Z_measurement
{
float x_measurement;
float z_measurement;
}Measurement;
class KalmanFilter
{
public:
KalmanFilter();
KalmanFilter(clusterFeature &glu,double rollAngle);
~KalmanFilter(void);
void InitialKalmanFilter(clusterFeature &glu);
void timeUpdate();
void stateUpdate(clusterFeature &glu,double rollAngle,double *pos);
ObjectState GetCurrentState();
ObjectState GetPredictState();
Measurement GetPredictMeasurement(double rollAngle,double *pos);
CMatrix CalMeasureDeviation();
KalmanFilter& operator = (const KalmanFilter& anotherKF);
void CalCoorRoll(double angle);
public:
CMatrix A;
CMatrix H;
CMatrix X1;
CMatrix X2;
CMatrix Z;
CMatrix K;
CMatrix Q;
CMatrix R;
CMatrix P1;
CMatrix P2;
CMatrix CoordinateRoll;
double angle;
};

@ -0,0 +1,22 @@
/**
* @file ELCH implementation using Euler angles
* @author Jochen Sprickerhof. Institute of Computer Science, University of Osnabrueck, Germany.
*/
#ifndef __ELCH6D_EULER_H__
#define __ELCH6D_EULER_H__
#include "elch6D.h"
class elch6Deuler : public elch6D {
public:
elch6Deuler(bool _quiet, icp6Dminimizer *my_icp6Dminimizer, double mdm, int max_num_iterations,
int rnd, bool eP, int anim, double epsilonICP, int nns_method)
: elch6D(_quiet, my_icp6Dminimizer, mdm, max_num_iterations, rnd, eP, anim, epsilonICP, nns_method) {}
virtual void close_loop(const vector <Scan *> &allScans, int first, int last, graph_t &g);
};
#endif

@ -0,0 +1,149 @@
/**
* @file
* @brief Implementation of reading 3D scans
* @author Andreas Nuechter. Institute of Computer Science, University of Osnabrueck, Germany.
*/
#include "slam6d/scan_io_wrl.h"
#include "slam6d/globals.icc"
#include <fstream>
using std::ifstream;
#include <iostream>
using std::cerr;
using std::endl;
#ifdef _MSC_VER
#include <windows.h>
#endif
#include <cstring>
/**
* Reads specified scans from given directory in
* the PLY file format. It will be compiled as
* shared lib.
*
* Scan poses will NOT be initialized after a call
* to this function.
*
*
* @param start Starts to read with this scan
* @param end Stops with this scan
* @param dir The directory from which to read
* @param maxDist Reads only Points up to this Distance
* @param minDist Reads only Points from this Distance
* @param euler Initital pose estimates (will not be applied to the points
* @param ptss Vector containing the read points
*/
int ScanIO_wrl::readScans(int start, int end, string &dir, int maxDist, int mindist,
double *euler, vector<Point> &ptss)
{
static int fileCounter = start;
string scanFileName;
string poseFileName;
int maxDist2 = (maxDist == -1 ? -1 : sqr(maxDist));
int my_fileNr = fileCounter;
ifstream scan_in, pose_in;
for (int i = 0; i < 6; i++) euler[i] = 0;
if (end > -1 && fileCounter > end) return -1;
poseFileName = dir + to_string(fileCounter,3) + "/position.dat";
pose_in.open(poseFileName.c_str());
// read 3D scan
if (!pose_in.good()) return -1; // no more files in the directory
cout << "Processing Scan " << dir << to_string(fileCounter, 3);
for (unsigned int i = 0; i < 6; pose_in >> euler[i++]);
// convert mm to cm
for (unsigned int i = 0; i < 3; i++) euler[i] = euler[i] * 0.1;
// convert angles from deg to rad
for (unsigned int i = 3; i <= 5; i++) {
euler[i] *= 0.01;
// if (euler[i] < 0.0) euler[i] += 360;
euler[i] = rad(euler[i]);
}
cout << " @ pose (" << euler[0] << "," << euler[1] << "," << euler[2]
<< "," << deg(euler[3]) << "," << deg(euler[4]) << "," << deg(euler[5]) << ")" << endl;
if (end > -1 && fileCounter > end) return -1; // 'nuf read
scanFileName = dir + to_string(fileCounter,3) + ".wrl";
scan_in.open(scanFileName.c_str());
// read 3D scan
if (!scan_in.good()) return -1; // no more scans to read
// overread the first 7 tokes / 4 lines - don't care here
char dummy[255];
for (int i = 0; i < 4; i++) {
scan_in.getline(dummy, 255);
}
do {
char cx[25], cy[25], cz[25];
double xyz[3];
scan_in >> cx >> cy >> cz;
if (!scan_in.good()) break;
// remove the "," from the z coordinate
cz[strlen(cz)-1] = 0;
xyz[0] = atof(cx);
xyz[1] = atof(cy);
xyz[2] = atof(cz);
Point p(xyz);
if (maxDist == -1 || sqr(p.x) + sqr(p.y) + sqr(p.z) < maxDist2)
ptss.push_back(p);
} while (scan_in.good());
scan_in.close();
scan_in.clear();
pose_in.close();
pose_in.clear();
fileCounter++;
return my_fileNr;
}
/**
* class factory for object construction
*
* @return Pointer to new object
*/
#ifdef _MSC_VER
extern "C" __declspec(dllexport) ScanIO* create()
#else
extern "C" ScanIO* create()
#endif
{
return new ScanIO_wrl;
}
/**
* class factory for object construction
*
* @return Pointer to new object
*/
#ifdef _MSC_VER
extern "C" __declspec(dllexport) void destroy(ScanIO *sio)
#else
extern "C" void destroy(ScanIO *sio)
#endif
{
delete sio;
}
#ifdef _MSC_VER
BOOL APIENTRY DllMain(HANDLE hModule, DWORD dwReason, LPVOID lpReserved)
{
return TRUE;
}
#endif

@ -0,0 +1,46 @@
Microsoft Visual Studio Solution File, Format Version 9.00
# Visual Studio 2005
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "dll", "dll\dll.vcproj", "{A7D00B21-CB9C-4BBB-8DEE-51025104F867}"
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "sample", "sample\sample.vcproj", "{C76F5A10-7A4A-4546-9414-296DB38BE825}"
ProjectSection(ProjectDependencies) = postProject
{A7D00B21-CB9C-4BBB-8DEE-51025104F867} = {A7D00B21-CB9C-4BBB-8DEE-51025104F867}
EndProjectSection
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "test", "test\test.vcproj", "{6AC673C7-7B3F-4520-A761-647B212A4BEF}"
ProjectSection(ProjectDependencies) = postProject
{A7D00B21-CB9C-4BBB-8DEE-51025104F867} = {A7D00B21-CB9C-4BBB-8DEE-51025104F867}
EndProjectSection
EndProject
Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "ann2fig", "ann2fig\ann2fig.vcproj", "{622DD7D8-0C0A-4303-9176-C9A8AF467E70}"
ProjectSection(ProjectDependencies) = postProject
{A7D00B21-CB9C-4BBB-8DEE-51025104F867} = {A7D00B21-CB9C-4BBB-8DEE-51025104F867}
EndProjectSection
EndProject
Global
GlobalSection(SolutionConfigurationPlatforms) = preSolution
Debug|Win32 = Debug|Win32
Release|Win32 = Release|Win32
EndGlobalSection
GlobalSection(ProjectConfigurationPlatforms) = postSolution
{A7D00B21-CB9C-4BBB-8DEE-51025104F867}.Debug|Win32.ActiveCfg = Debug|Win32
{A7D00B21-CB9C-4BBB-8DEE-51025104F867}.Debug|Win32.Build.0 = Debug|Win32
{A7D00B21-CB9C-4BBB-8DEE-51025104F867}.Release|Win32.ActiveCfg = Release|Win32
{A7D00B21-CB9C-4BBB-8DEE-51025104F867}.Release|Win32.Build.0 = Release|Win32
{C76F5A10-7A4A-4546-9414-296DB38BE825}.Debug|Win32.ActiveCfg = Debug|Win32
{C76F5A10-7A4A-4546-9414-296DB38BE825}.Debug|Win32.Build.0 = Debug|Win32
{C76F5A10-7A4A-4546-9414-296DB38BE825}.Release|Win32.ActiveCfg = Release|Win32
{C76F5A10-7A4A-4546-9414-296DB38BE825}.Release|Win32.Build.0 = Release|Win32
{6AC673C7-7B3F-4520-A761-647B212A4BEF}.Debug|Win32.ActiveCfg = Debug|Win32
{6AC673C7-7B3F-4520-A761-647B212A4BEF}.Debug|Win32.Build.0 = Debug|Win32
{6AC673C7-7B3F-4520-A761-647B212A4BEF}.Release|Win32.ActiveCfg = Release|Win32
{6AC673C7-7B3F-4520-A761-647B212A4BEF}.Release|Win32.Build.0 = Release|Win32
{622DD7D8-0C0A-4303-9176-C9A8AF467E70}.Debug|Win32.ActiveCfg = Debug|Win32
{622DD7D8-0C0A-4303-9176-C9A8AF467E70}.Debug|Win32.Build.0 = Debug|Win32
{622DD7D8-0C0A-4303-9176-C9A8AF467E70}.Release|Win32.ActiveCfg = Release|Win32
{622DD7D8-0C0A-4303-9176-C9A8AF467E70}.Release|Win32.Build.0 = Release|Win32
EndGlobalSection
GlobalSection(SolutionProperties) = preSolution
HideSolutionNode = FALSE
EndGlobalSection
EndGlobal

@ -0,0 +1,5 @@
P6
# Created by Paint Shop Pro
11 17
255
¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüÿÿÿ¿¿¿ÿÿÿ¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿ÿÿÿ¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿ÿÿÿ¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿ÿÿÿ¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿ÿÿÿ¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿ÿÿÿ¿¿¿þþþ¿¿¿¿¿¿ÿÿÿ¿¿¿¿¿¿þþþ¿¿¿¿¿¿¿¿¿ÿÿÿ¿¿¿¿¿¿¿¿¿þþþ¿¿¿¿¿¿¿¿¿¿¿¿ÿÿÿ¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿ÿÿÿ¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿ÿÿÿ¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿ÿÿÿ¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿ÿÿÿ¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿¿

@ -0,0 +1,51 @@
IF (WITH_SHAPE_DETECTION)
include_directories(${CMAKE_SOURCE_DIR}/3rdparty/gocr-0.48/src)
include_directories(${CMAKE_SOURCE_DIR}/3rdparty/gocr-0.48/include)
include_directories(${CMAKE_SOURCE_DIR}/include/shapes/)
# # Compile gocr library
# SET(GOCR_DIR ${CMAKE_SOURCE_DIR}/3rdparty/gocr-0.48/src/)
# add_library(Pgm2asc SHARED ${GOCR_DIR}gocr.c ${GOCR_DIR}pgm2asc.c ${GOCR_DIR}box.c ${GOCR_DIR}database.c
# ${GOCR_DIR}detect.c ${GOCR_DIR}barcode.c ${GOCR_DIR}lines.c ${GOCR_DIR}list.c
# ${GOCR_DIR}ocr0.c ${GOCR_DIR}ocr0n.c ${GOCR_DIR}ocr1.c ${GOCR_DIR}otsu.c
# ${GOCR_DIR}output.c ${GOCR_DIR}pixel.c ${GOCR_DIR}unicode.c ${GOCR_DIR}remove.c
# ${GOCR_DIR}pnm.c ${GOCR_DIR}pcx.c ${GOCR_DIR}progress.c ${GOCR_DIR}job.c)
# add_executable(shapes shapes.cc geom_math.cc numberrec.cc scan_ransac.cc )
#
# IF(WIN32)
# target_link_libraries(shapes scan XGetopt netpbm Pgm2asc)
# ENDIF(WIN32)
#
# IF (UNIX)
# target_link_libraries(shapes scan newmat dl netpbm Pgm2asc )
# ENDIF(UNIX)
#
add_executable(planes plane.cc)
# add_executable(image toImage.cc image.cc hough.cc convexplane.cc accumulator.cc hsm3d.cc ConfigFileHough.cc parascan.cc quadtree.cc geom_math.cc )
# add_executable(matchMarker matchMarker.cc)
IF(UNIX)
target_link_libraries(planes scan shape newmat dl ANN)
# target_link_libraries(image scan newmat sparse dl ANN )
# target_link_libraries(matchMarker scan newmat sparse dl ANN )
ENDIF(UNIX)
IF (WIN32)
target_link_libraries(planes scan newmat XGetopt shape ANN)
# target_link_libraries(image scan newmat sparse ANN XGetopt)
ENDIF(WIN32)
SET(SHAPELIB_SRCS
hough.cc convexplane.cc accumulator.cc hsm3d.cc ConfigFileHough.cc parascan.cc quadtree.cc geom_math.cc )
add_library(shape STATIC ${SHAPELIB_SRCS})
#target_link_libraries(shapelib)
IF(EXPORT_SHARED_LIBS)
add_library(shape_s SHARED ${SHAPELIB_SRCS})
#target_link_libraries(scan_s ${Boost_LIBRARIES} newmat)
ENDIF(EXPORT_SHARED_LIBS)
ENDIF(WITH_SHAPE_DETECTION)

@ -0,0 +1,42 @@
/** @file
* @brief Definition of the ICP error function minimization
* @author Andreas Nuechter. Jacobs University Bremen gGmbH, Germany
* @author Kai Lingemann. Institute of Computer Science, University of Osnabrueck, Germany.
*/
#ifndef __ICP6DAPX_H__
#define __ICP6DAPX_H__
#include "icp6Dminimizer.h"
/**
* @brief Implementation of the ICP error function minimization via approximation
*/
class icp6D_APX : public icp6Dminimizer
{
public:
/**
* Constructor
*/
icp6D_APX(bool quiet = false) : icp6Dminimizer(quiet) {};
/**
* Destructor
*/
virtual ~icp6D_APX() {};
double Point_Point_Align(const vector<PtPair>& Pairs, double *alignxf,
const double centroid_m[3], const double centroid_d[3]);
double Point_Point_Align_Parallel(const int openmp_num_threads,
const unsigned int n[OPENMP_NUM_THREADS],
const double sum[OPENMP_NUM_THREADS],
const double centroid_m[OPENMP_NUM_THREADS][3],
const double centroid_d[OPENMP_NUM_THREADS][3],
const vector<PtPair> pairs[OPENMP_NUM_THREADS],
double *alignxf);
static void computeRt(const double *x, const double *dx, double *alignxf);
inline int getAlgorithmID() { return 6; };
};
#endif

@ -0,0 +1,19 @@
/**
* @file
* @brief Server/Client wide definitions.
*
* If running multiple instances of the scanserver, one can change these shared memory names individually.
*
* @author Thomas Escher
*/
#ifndef SCANSERVER_DEFINES_H
#define SCANSERVER_DEFINES_H
//! shared memory for SharedScans, Frames and communications
#define SHM_NAME_DATA "3dtk_scanserver_data"
//! CacheManager/CacheObject only shared memory
#define SHM_NAME_CACHE "3dtk_scanserver_cache"
#endif //SCANSERVER_DEFINES_H

@ -0,0 +1,47 @@
#ifndef __SCANGRID_H_
#define __SCANGRID_H_
#include "grid/grid.h"
/**
* The class represents a 2D section of a scan.
* It inherrits from grid -> the internal representation is an array
*
* @author Uwe Hebbelmann, Sebastian Stock, Andre Schemschat
*
* @date 14.02.2008
*/
class scanGrid : public grid
{
/** The position of the robot (X) */
long viewpointX;
/** The position of the robot (Z) */
long viewpointZ;
public:
/** @brief CTor */
scanGrid(long viewX, long viewZ, long offsetX, long offsetZ,
long sizeX, long sizeZ);
/** @brief DTor */
virtual ~scanGrid();
/**
* Getter for the x position of the robot when the scan was made
* @return x position
*/
inline long getViewpointX() const {
return this->viewpointX;
}
/**
* Getter for the z position of the robot when the scan was made
* @return z position
*/
inline long getViewpointZ() const {
return this->viewpointZ;
}
};
#endif

@ -0,0 +1,100 @@
#ifndef NRRANSAC_OCTREE_H
#define NRRANSAC_OCTREE_H
#include "shapes/geom_math.h"
#include "shapes/ransac_Boctree.h"
#include "slam6d/Boctree.h"
template <class T=double>
class NumberRecOctTree : public RansacOctTree<T> {
public:
// NumberRecOctTree(vector<T *> &pts, T voxelSize, PointType<T> _pointtype = PointType<T>() ) : RansacOctTree<T>(pts, voxelSize, _pointtype) {}
NumberRecOctTree(vector<const T *> &pts, T voxelSize, PointType _pointtype = PointType() ) : RansacOctTree<T>(pts, voxelSize, _pointtype) {}
long PointsOnNumber(double plane[4], double maxdist, double _center[3], double radius) {
setNumber(plane, _center, radius, maxdist);
return PointsOnNumber(*BOctTree<T>::root, BOctTree<T>::center, BOctTree<T>::size);
}
void PointsOnNumber(double plane[4], double maxdist, double _center[3], double radius, vector<T *> &n) {
setNumber(plane, _center, radius, maxdist);
PointsOnNumber(*BOctTree<T>::root, BOctTree<T>::center, BOctTree<T>::size, n);
}
protected:
long PointsOnNumber(bitoct &node, T *center, T size) {
if (!SphereInAABB(center[0], center[1], center[2], size)) {
return 0;
}
T ccenter[3];
bitunion<T> *children;
bitoct::getChildren(node, children);
long result = 0;
for (short i = 0; i < 8; i++) {
if ( ( 1 << i ) & node.valid ) { // if ith node exists
childcenter(center, ccenter, size, i); // childrens center
if ( ( 1 << i ) & node.leaf ) { // if ith node is leaf get center
// check if leaf contains plane
if ( SphereInAABB(ccenter[0], ccenter[1], ccenter[2], size/2.0) ) {
pointrep *points = children->points;
unsigned int length = points[0].length;
T *point = &(points[1].v); // first point
for(unsigned int iterator = 0; iterator < length; iterator++ ) {
if( closeToPlane(point) )
result++;
point += BOctTree<T>::POINTDIM;
}
}
} else { // recurse
result += PointsOnNumber( children->node, ccenter, size/2.0);
}
++children; // next child
}
}
return result;
}
void PointsOnNumber(bitoct &node, T *center, T size, vector<T*> &n) {
if (!SphereInAABB(center[0], center[1], center[2], size)) {
return ;
}
T ccenter[3];
bitunion<T> *children;
bitoct::getChildren(node, children);
for (short i = 0; i < 8; i++) {
if ( ( 1 << i ) & node.valid ) { // if ith node exists
childcenter(center, ccenter, size, i); // childrens center
if ( ( 1 << i ) & node.leaf ) { // if ith node is leaf get center
// check if leaf contains plane
if ( SphereInAABB(ccenter[0], ccenter[1], ccenter[2], size/2.0) ) {
pointrep *points = children->points;
unsigned int length = points[0].length;
T *point = &(points[1].v); // first point
for(unsigned int iterator = 0; iterator < length; iterator++ ) {
if( closeToPlane(point) )
n.push_back(point);
point+=BOctTree<T>::POINTDIM;
}
}
} else { // recurse
PointsOnNumber( children->node, ccenter, size/2.0, n);
}
++children; // next child
}
}
}
};
#endif

@ -0,0 +1,165 @@
GOCR (JOCR at SF.net)
GOCR is an optical character recognition program, released under the
GNU General Public License. It reads images in many formats and outputs
a text file. Possible image formats are pnm, pbm, pgm, ppm, some pcx and
tga image files. Other formats like pnm.gz, pnm.bz2, png, jpg, tiff, gif,
bmp will be automatically converted using the netpbm-progs, gzip and bzip2
via unix pipe.
A simple graphical frontend written in tcl/tk and some
sample files are included.
Gocr is also able to recognize and translate barcodes.
You do not have to train the program or store large font bases.
Simply call gocr from the command line and get your results.
To see installation instructions, see the INSTALL file.
How to start? (QUICK START)
---------------------------
Some examples of how you can use gocr:
gocr -h # help
gocr file.pbm # minimum options
gocr -v 1 file.pbm >out.txt 2>out.log # generate text- and log file
djpeg -pnm -gray text.jpg | gocr - # using JPEG-files
gzip -cd text.pbm.gz | gocr - # using gzipped PBM-files
giftopnm text.gif | gocr - # using GIF-files
gocr -v 1 -v 32 -m 4 file.pbm # zoning and out30.bmp output
xli -geometry 400x400 out30.bmp # see details using xli (recommanded viewer)
wish gocr.tcl # X11-tcl/tk-frontend (development version)
# see manual pages for more details
How to get image files?
-----------------------
Scan text pages and save it as PGM/PBM/PNM file. Use a program such as
The GIMP or Sane. You can also use netpbm-progs to convert several image
formats into PGM/PBM/PNM. The tool djpeg can be used to convert jpeg into pgm.
If you have a POSIX compatible system like linux and PNM-tools, gzip and bzip2
are installed, you are lucky and gocr will do conversion
from [.pnm.gz, .pnm.bz2, .jpg, .jpeg, .bmp, .tiff, .png, .ps, .eps]
to [.pgm] for you. This list can easily be extended editing src/pnm.c.
Gocr also comes with some examples, try: make examples.
Memory limitations
------------------
WARNING!!!
If you use a 300dpi scan of A4 letter, the image is about 2500x3500 pixels and
gocr requires 8.75MB for storing the picture into the memory. Not only that,
but gocr may create a 2nd copy, using a total of 17MB. This is independent
of using b/w or gray-scale images. Be sure that you have enough RAM installed
in your machine! Alternatively you can cut the picture into small pieces.
You can use the pnmcut, from the netpbm package to cut the file. Example:
pnmcut -left 0 -right 2500 -top 0 -height 1000 bigfile.pnm > smallfile.pnm
And then use gocr in the cropped image as usual. Take care: if you chopp the
characters, gocr won't be able to understand that line.
Future versions will take care of this issue automatically.
Limitations
-----------
gocr is still in its early stages. Your images should fit in these requirements
if you want a good output:
- good scans (all chars well seperated, one column, no tables etc, 12pt 300dpi)
should work well
- fonts 20-60 pixels ( 5pt * 1in/72pt * 300 dpi = 20 dots )
- output of image file for controlling detection
And note that speed is very slow (this will be changed when recognition works
well)
12pt 300dpi 1700x950 16lines 700chars 22x28 P90=40s..90s v0.2.3 (gcc -O0)
You can try to optimize the results:
- make good scans/treat image
- try to change the critical gray level (option -l <n>)
- control the result on out10.png, out30.png (option -v 32)
example: ./gocr -v 32 -m 4 -m 256 -m 56 ~/aac.jpg # only check layout
- enlarge option -d <n> for high resolution images which are noisy
- try different combinations for option -m <n>
- for thousends of documents with same font
you can use/create a database (-m 2/-m 130)
- use options -d 0 -m 8 on screen shots (font8x12)
- use filter option -C to through out wrong recognized chars (ex: gothic)
What does >> NOT << work at the moment:
- complex layouts (try option -m 4)
- bad scans, noisy/snowy images, FAX-quality images
- serif fonts, italic fonts, slanted fonts
- handwritten texts (this is valid for the next ten years I guess)
the exisctence of autotrace can shorten this
- rotated images (but slightly rotated images should be no problem)
- small fonts (fax like) or mix of different font size
- colored images (use gray or black/white)
- Chinese, Arabian, Egyptian, Cyrillic or Klingon fonts
How it works or how it should work?
- put the entire file into RAM (300dpi grayscale recommended)
- remove dust and snow
- detect small angle (lines which are not horizontal)
- detect text boxes (option -m 4)
- detect text-lines
- detect characters
- first step recognition (every character has its own empirical procedure)
- no neural network or similar general algorithms
- analyze not detected chars by comparison with detected ones
- try to divide overlapping chars
- testwise: compare all letters (like compression of pictures)
- for more details look to the gocr.html documentation
Why the result of the new version are worse compared to the old version?
- the algorithms of gocr are sometimes evolutionary, a fine tuned old
algorithm will be replased by a completly new algorithm which is more
general but a bit worse for your problem.
Please send your sample and give the new algo the chance to become
better as the old one.
Security
--------
Because gocr only reads and writes files it is quite sure, except the
popen-function which allows you to call gocr with non-pnm-image formats
directly. The popen function can be misused to start other probably
dangerous programs.
If you care about conversion to pnm format, you can safely disable
popen-function by removing "#define HAVE_POPEN 1" from config.h before
compiling the gocr package.
How can you help gocr?
----------------------
- Send comments, ideas and patches (diff -ru gocr_original/ gocr_changed/).
- If you have a lot of money, spend a bit (paypal). Ok, paypal has changed,
so please forget about it. Also the importand problem is now the missing
spare time for coding.
- I always need example files (.pbm.gz or jpeg <100kB) for testing
the behavior of the ocr engine under different conditions,
because scanning does take a lot of time which I do not have.
But do not send files which are not convertable by commercial ocr programs
or which are protected from copying and electronic processing by copyright.
That will help, to get the world's best OCR open source program. :) Thanks!
- Please dont send captchas.
- Send me your results (errors,num_chars,dpi) and if possible results
and name of professional OCR programs for statistics.
- Read OCR literature, extract the essentials and send a short report
to me ;).
- If you have a good idea, how to manage some OCR-tasks, tell me!
- Tell your friends about gocr. Tell me about your success. Be happy.
After all, is it gocr or jocr?
------------------------------
The original name of this project is gocr, from GNU Optical Character
Recognition. Another project is using the same name, however; so the
name was changed to jocr. If you have a good idea for a name, please
send it.
Latest news
------------
http://jocr.sourceforge.net
Authors: (see AUTHORS)

@ -0,0 +1,76 @@
/****************************************************************************
GLUI User Interface Toolkit
---------------------------
glui_column.cpp - GLUI_Column control class
--------------------------------------------------
Copyright (c) 1998 Paul Rademacher
This program is freely distributable without licensing fees and is
provided without guarantee or warrantee expressed or implied. This
program is -not- in the public domain.
*****************************************************************************/
#include "glui.h"
#include "stdinc.h"
/**************************************** GLUI_Column::draw() ************/
void GLUI_Column::draw( int x, int y )
{
int orig;
int panel_x, panel_y, panel_w, panel_h, panel_x_off, panel_y_off;
int y_diff;
if ( NOT can_draw() )
return;
if ( int_val == 1 ) { /* Draw a vertical bar */
orig = set_to_glut_window();
if ( parent() != NULL ) {
get_this_column_dims(&panel_x, &panel_y, &panel_w, &panel_h,
&panel_x_off, &panel_y_off);
y_diff = y_abs - panel_y;
if ( 0 ) {
glLineWidth(1.0);
glBegin( GL_LINES );
glColor3f( .5, .5, .5 );
glVertex2i( -GLUI_XOFF+1, -y_diff + GLUI_SEPARATOR_HEIGHT/2 );
glVertex2i( -GLUI_XOFF+1, -y_diff + panel_h - GLUI_SEPARATOR_HEIGHT/2);
glColor3f( 1.0, 1.0, 1.0 );
glVertex2i( -GLUI_XOFF+2, -y_diff + GLUI_SEPARATOR_HEIGHT/2 );
glVertex2i( -GLUI_XOFF+2, -y_diff + panel_h - GLUI_SEPARATOR_HEIGHT/2);
glEnd();
}
else {
glLineWidth(1.0);
glBegin( GL_LINES );
glColor3f( .5, .5, .5 );
glVertex2i( -2, 0 );
glVertex2i( -2, h );
/*glVertex2i( 0, -y_diff + GLUI_SEPARATOR_HEIGHT/2 ); */
/*glVertex2i( 0, -y_diff + panel_h - GLUI_SEPARATOR_HEIGHT/2); */
glColor3f( 1.0, 1.0, 1.0 );
glVertex2i( -1, 0 );
glVertex2i( -1, h );
/*glVertex2i( 1, -y_diff + GLUI_SEPARATOR_HEIGHT/2 ); */
/*glVertex2i( 1, -y_diff + panel_h - GLUI_SEPARATOR_HEIGHT/2); */
glEnd();
}
}
restore_window(orig);
}
}

@ -0,0 +1,289 @@
/*
This is a Optical-Character-Recognition program
Copyright (C) 2000-2009 Joerg Schulenburg
This program is free software; you can redistribute it and/or
modify it under the terms of the GNU General Public License
as published by the Free Software Foundation; either version 2
of the License, or (at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program; if not, write to the Free Software
Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
see README for EMAIL-address
the following code was send by Ryan Dibble <dibbler@umich.edu>
The algorithm is very simple but works good hopefully.
Compare the grayscale histogram with a mass density diagram:
I think the algorithm is a kind of
divide a body into two parts in a way that the mass
centers have the largest distance from each other,
the function is weighted in a way that same masses have a advantage
- otsu algorithm is failing on diskrete multi color images
TODO:
RGB: do the same with all colors (CMYG?) seperately
test: hardest case = two colors
bbg: test done, using a two color gray file. Output:
# threshold: Value = 43 gmin=43 gmax=188
my changes:
- float -> double
- debug option added (vvv & 1..2)
- **image => *image, &image[i][1] => &image[i*cols+1]
- do only count pixels near contrast regions
this makes otsu much better for shadowed fonts or multi colored text
on white background
(m) Joerg Schulenburg (see README for email address)
ToDo:
- measure contrast
- detect low-contrast regions
*/
#include <stdio.h>
#include <string.h>
#define Abs(x) ((x<0)?-(x):x)
/*======================================================================*
* global thresholding routine *
* takes a 2D unsigned char array pointer, number of rows, and *
* number of cols in the array. returns the value of the threshold *
* x0,y0,x0+dx,y0+dy are the edgepoints of the interesting region *
* vvv is the verbosity for debugging purpose *
*======================================================================*/
int
otsu (unsigned char *image, int rows, int cols,
int x0, int y0, int dx, int dy, int vvv) {
unsigned char *np; // pointer to position in the image we are working with
unsigned char op1, op2; // predecessor of pixel *np (start value)
int maxc=0; // maximum contrast (start value)
int thresholdValue=1; // value we will threshold at
int ihist[256]; // image histogram
int chist[256]; // contrast histogram
int i, j, k; // various counters
int is, i1, i2, ns, n1, n2, gmin, gmax;
double m1, m2, sum, csum, fmax, sb;
// zero out histogram ...
memset(ihist, 0, sizeof(ihist));
memset(chist, 0, sizeof(chist));
op1=op2=0;
gmin=255; gmax=0; k=dy/512+1;
// v0.43 first get max contrast, dont do it together with next step
// because it failes if we have pattern as background (on top)
for (i = 0; i < dy ; i+=k) {
np = &image[(y0+i)*cols+x0];
for (j = 0; j < dx ; j++) {
ihist[*np]++;
if(*np > gmax) gmax=*np;
if(*np < gmin) gmin=*np;
if (Abs(*np-op1)>maxc) maxc=Abs(*np-op1); /* new maximum contrast */
if (Abs(*np-op2)>maxc) maxc=Abs(*np-op2); /* new maximum contrast */
/* we hope that maxc will be find its maximum very fast */
op2=op1; /* shift old pixel to next older */
op1=*np; /* store old pixel for contrast check */
np++; /* next pixel */
}
}
// generate the histogram
// Aug06 images with large white or black homogeneous
// areas give bad results, so we only add pixels on contrast edges
for (i = 0; i < dy ; i+=k) {
np = &image[(y0+i)*cols+x0];
for (j = 0; j < dx ; j++) {
if (Abs(*np-op1)>maxc/4
|| Abs(*np-op2)>maxc/4)
chist[*np]++; // count only relevant pixels
op2=op1; /* shift old pixel to next older */
op1=*np; /* store old pixel for contrast check */
np++; /* next pixel */
}
}
// set up everything
sum = csum = 0.0;
ns = 0;
is = 0;
for (k = 0; k <= 255; k++) {
sum += (double) k * (double) chist[k]; /* x*f(x) cmass moment */
ns += chist[k]; /* f(x) cmass */
is += ihist[k]; /* f(x) imass */
// Debug: output to out_hist.dat?
// fprintf(stderr,"\chistogram %3d %6d (brightness weight)", k, ihist[k]);
}
if (!ns) {
// if n has no value we have problems...
fprintf (stderr, "NOT NORMAL, thresholdValue = 160\n");
return (160);
}
// ToDo: only care about extremas in a 3 pixel environment
// check if there are more than 2 mass centers (more colors)
// return object colors and color radius instead of threshold value
// also the reagion, where colored objects are found
// what if more than one background color? no otsu at all?
// whats background? box with lot of other boxes in it
// threshold each box (examples/invers.png,colors.png)
// get maximum white and minimum black pixel color (possible range)
// check range between them for low..high contrast ???
// typical scenes (which must be covered):
// - white page with text of different colors (gray values)
// - binear page: background (gray=1) + black text (gray=0)
// - text mixed with big (dark) images
// ToDo: recursive clustering for maximum multipol moments?
// idea: normalize ihist to max=1024 before otsu?
// do the otsu global thresholding method
if ((vvv&1)) // Debug
fprintf(stderr,"# threshold: value ihist chist mass_dipol_moment\n");
fmax = -1.0;
n1 = 0;
for (k = 0; k < 255; k++) {
n1 += chist[k]; // left mass (integration)
if (!n1) continue; // we need at least one foreground pixel
n2 = ns - n1; // right mass (num pixels - left mass)
if (n2 == 0) break; // we need at least one background pixel
csum += (double) k *chist[k]; // left mass moment
m1 = csum / n1; // left mass center (black chars)
m2 = (sum - csum) / n2; // right mass center (white background)
// max. dipol moment?
// orig: sb = (double) n1 *(double) n2 * (m1 - m2) * (m1 - m2);
sb = (double) n1 *(double) n2 * (m2 - m1); // seems to be better Aug06
/* bbg: note: can be optimized. */
if (sb > fmax) {
fmax = sb;
thresholdValue = k + 1;
// thresholdValue = (m1 + 3 * m2) / 4;
}
if ((vvv&1) && ihist[k]) // Debug
fprintf(stderr,"# threshold: %3d %6d %6d %8.2f\n",
k, ihist[k], chist[k],
sb/(dx*dy)); /* normalized dipol moment */
}
// ToDo: error = left/right point where sb is 90% of maximum?
// now we count all pixels for background detection
i1 = 0;
for (k = 0; k < thresholdValue; k++) {
i1 += ihist[k]; // left mass (integration)
}
i2 = is - i1; // right mass (num pixels - left mass)
// at this point we have our thresholding value
// black_char: value<cs, white_background: value>=cs
// can it happen? check for sureness
if (thresholdValue > gmax) {
fprintf(stderr,"# threshold: Value >gmax\n");
thresholdValue = gmax;
}
if (thresholdValue <= gmin) {
fprintf(stderr,"# threshold: Value<=gmin\n");
thresholdValue = gmin+1;
}
// debug code to display thresholding values
if ( vvv & 1 )
fprintf(stderr,"# threshold: Value = %d gmin=%d gmax=%d cmax=%d"
" b/w= %d %d\n",
thresholdValue, gmin, gmax, maxc, i1, i2);
// this is a primitive criteria for inversion and should be improved
// old: i1 >= 4*i2, but 0811qemu1.png has a bit above 1/4
if (2*i1 > 7*i2) { // more black than white, obviously black is background
if ( vvv & 1 )
fprintf(stderr,"# threshold: invert the image\n");
// we do inversion here (no data lost)
for (i = 0; i < dy ; i++) {
np = &image[(y0+i)*cols+x0];
for (j = 0; j < dx ; j++) {
*np=255-*np;
np++; /* next pixel */
}
}
thresholdValue=255-thresholdValue+1;
}
return(thresholdValue);
/* range: 0 < thresholdValue <= 255, example: 1 on b/w images */
/* 0..threshold-1 is foreground */
/* threshold..255 is background */
/* ToDo: min=blackmasscenter/2,thresh,max=(whitemasscenter+255)/2 */
}
/*======================================================================*/
/* thresholding the image (set threshold to 128+32=160=0xA0) */
/* now we have a fixed thresholdValue good to recognize on gray image */
/* - so lower bits can used for other things (bad design?) */
/* ToDo: different foreground colors, gray on black/white background */
/*======================================================================*/
int
thresholding (unsigned char *image, int rows, int cols,
int x0, int y0, int dx, int dy, int thresholdValue) {
unsigned char *np; // pointer to position in the image we are working with
int i, j; // various counters
int gmin=255,gmax=0;
int nmin=255,nmax=0;
// calculate min/max (twice?)
for (i = y0 + 1; i < y0 + dy - 1; i++) {
np = &image[i*cols+x0+1];
for (j = x0 + 1; j < x0 + dx - 1; j++) {
if(*np > gmax) gmax=*np;
if(*np < gmin) gmin=*np;
np++; /* next pixel */
}
}
/* allowed_threshold=gmin+1..gmax v0.43 */
if (thresholdValue<=gmin || thresholdValue>gmax){
thresholdValue=(gmin+gmax+1)/2; /* range=0..1 -> threshold=1 */
fprintf(stderr,"# thresholdValue out of range %d..%d, reset to %d\n",
gmin, gmax, thresholdValue);
}
/* b/w: min=0,tresh=1,max=1 v0.43 */
// actually performs the thresholding of the image...
// later: grayvalues should also be used, only rescaling threshold=160=0xA0
// sometimes images have no contrast (thresholdValue == gmin)
for (i = y0; i < y0+dy; i++) {
np = &image[i*cols+x0];
for (j = x0; j < x0+dx; j++) {
*np = (unsigned char) (*np >= thresholdValue || thresholdValue == gmin ?
(255-(gmax - *np)* 80/(gmax - thresholdValue + 1)) :
( 0+(*np - gmin)*150/(thresholdValue - gmin )) );
if(*np > nmax) nmax=*np;
if(*np < nmin) nmin=*np;
np++;
}
}
// fprintf(stderr,"# thresholding: nmin=%d nmax=%d\n", nmin, nmax);
return(128+32); // return the new normalized threshold value
/* 0..159 is foreground */
/* 160..255 is background */
}

@ -0,0 +1,136 @@
/*
* elch6Dquat implementation
*
* Copyright (C) Jochen Sprickerhof
*
* Released under the GPL version 3.
*
*/
/**
* @file ELCH implementation using Quaternions
* @author Jochen Sprickerhof. Institute of Computer Science, University of Osnabrueck, Germany.
*/
#include "slam6d/elch6Dquat.h"
#include "slam6d/metaScan.h"
#include "slam6d/lum6Dquat.h"
#include "slam6d/globals.icc"
#include <iostream>
using std::cout;
using std::cerr;
using std::endl;
#include <fstream>
using std::ofstream;
#include <boost/graph/graph_traits.hpp>
using boost::graph_traits;
using namespace NEWMAT;
#ifdef _MSC_VER
#define tie tr1::tie
#endif
/**
* ELCH loop closing function using Quaternions
* matches first and last scan of a loop with ICP
* distributes the error
*
* @param allScans all laser scans
* @param first index of first laser scan in the loop
* @param last indes of last laser scan in the loop
* @param g graph for loop optimization
*/
void elch6Dquat::close_loop(const vector <Scan *> &allScans, int first, int last, graph_t &g)
{
int n = num_vertices(g);
graph_t grb[7];
Matrix C(7, 7);
graph_traits <graph_t>::edge_iterator ei, ei_end;
for(tie(ei, ei_end) = edges(g); ei != ei_end; ei++) {
int from = source(*ei, g);
int to = target(*ei, g);
lum6DQuat::covarianceQuat(allScans[from], allScans[to], my_icp6D->get_nns_method(), my_icp6D->get_rnd(), my_icp6D->get_max_dist_match2(), &C);
C = C.i();
for(int j = 0; j < 7; j++) {
add_edge(from, to, fabs(C(j + 1, j + 1)), grb[j]);
}
}
double *weights[7];
for(int i = 0; i < 7; i++) {
weights[i] = new double[n];
graph_balancer(grb[i], first, last, weights[i]);
}
vector <Scan *> meta_start;
meta_start.push_back(allScans[first]);
meta_start.push_back(allScans[first + 1]);
meta_start.push_back(allScans[first + 2]);
MetaScan *start = new MetaScan(meta_start, false, false);
vector <Scan *> meta_end;
meta_end.push_back(allScans[last - 2]);
meta_end.push_back(allScans[last - 1]);
meta_end.push_back(allScans[last]);
MetaScan *end = new MetaScan(meta_end, false, false);
for(int i = last - 2; i <= last; i++) {
for(int j = 0; j < 7; j++) {
weights[j][i] = 0.0;
}
}
double delta[7];
delta[0] = allScans[last]->get_rPos()[0];
delta[1] = allScans[last]->get_rPos()[1];
delta[2] = allScans[last]->get_rPos()[2];
delta[3] = allScans[last]->get_rPosQuat()[0];
delta[4] = allScans[last]->get_rPosQuat()[1];
delta[5] = allScans[last]->get_rPosQuat()[2];
delta[6] = allScans[last]->get_rPosQuat()[3];
my_icp6D->match(start, end);
delete start;
delete end;
delta[0] = allScans[last]->get_rPos()[0] - delta[0];
delta[1] = allScans[last]->get_rPos()[1] - delta[1];
delta[2] = allScans[last]->get_rPos()[2] - delta[2];
delta[3] = allScans[last]->get_rPosQuat()[0] - delta[3];
delta[4] = allScans[last]->get_rPosQuat()[1] - delta[4];
delta[5] = allScans[last]->get_rPosQuat()[2] - delta[5];
delta[6] = allScans[last]->get_rPosQuat()[3] - delta[6];
if(!quiet) {
double axisangle[4];
axisangle[0] = delta[3];
axisangle[1] = delta[4];
axisangle[2] = delta[5];
axisangle[3] = delta[6];
QuatToAA(axisangle);
cout << "Delta: " << delta[0] << " " << delta[1] << " " << delta[2] << " " << axisangle[0] << " " << axisangle[1] << " " << axisangle[2] << " " << axisangle[3] << endl;
}
double rPos[3], rPosQuat[4];
for(int i = 1; i < n; i++) {
rPos[0] = allScans[i]->get_rPos()[0] + delta[0] * (weights[0][i] - weights[0][0]);
rPos[1] = allScans[i]->get_rPos()[1] + delta[1] * (weights[1][i] - weights[1][0]);
rPos[2] = allScans[i]->get_rPos()[2] + delta[2] * (weights[2][i] - weights[2][0]);
rPosQuat[0] = allScans[i]->get_rPosQuat()[0] + delta[3] * (weights[3][i] - weights[3][0]);
rPosQuat[1] = allScans[i]->get_rPosQuat()[1] + delta[4] * (weights[4][i] - weights[4][0]);
rPosQuat[2] = allScans[i]->get_rPosQuat()[2] + delta[5] * (weights[5][i] - weights[5][0]);
rPosQuat[3] = allScans[i]->get_rPosQuat()[3] + delta[6] * (weights[6][i] - weights[6][0]);
Normalize4(rPosQuat);
allScans[i]->transformToQuat(rPos, rPosQuat, Scan::ELCH, i == n-1 ? 2 : 1);
}
for(int i = 0; i < 7; i++) {
delete [] weights[i];
}
}

@ -0,0 +1,44 @@
//----------------------------------------------------------------------
// File: kd_fix_rad_search.h
// Programmer: Sunil Arya and David Mount
// Description: Standard kd-tree fixed-radius kNN search
// Last modified: 05/03/05 (Version 1.1)
//----------------------------------------------------------------------
// Copyright (c) 1997-2005 University of Maryland and Sunil Arya and
// David Mount. All Rights Reserved.
//
// This software and related documentation is part of the Approximate
// Nearest Neighbor Library (ANN). This software is provided under
// the provisions of the Lesser GNU Public License (LGPL). See the
// file ../ReadMe.txt for further information.
//
// The University of Maryland (U.M.) and the authors make no
// representations about the suitability or fitness of this software for
// any purpose. It is provided "as is" without express or implied
// warranty.
//----------------------------------------------------------------------
// History:
// Revision 1.1 05/03/05
// Initial release
//----------------------------------------------------------------------
#ifndef ANN_kd_fix_rad_search_H
#define ANN_kd_fix_rad_search_H
#include "kd_tree.h" // kd-tree declarations
#include "kd_util.h" // kd-tree utilities
#include "pr_queue_k.h" // k-element priority queue
#include <ANN/ANNperf.h> // performance evaluation
//----------------------------------------------------------------------
// Global variables
// These are active for the life of each call to
// annRangeSearch(). They are set to save the number of
// variables that need to be passed among the various search
// procedures.
//----------------------------------------------------------------------
extern ANNpoint ANNkdFRQ; // query point (static copy)
#endif

@ -0,0 +1,28 @@
/**
* @file
* @brief
*
* @author Thomas Escher
*/
#ifndef SHARED_FRAME_H
#define SHARED_FRAME_H
#include "slam6d/frame.h"
#include <boost/interprocess/managed_shared_memory.hpp>
#include <boost/interprocess/containers/vector.hpp>
// hide the boost namespace and shorten others
namespace
{
namespace ip = boost::interprocess;
// the segment manager providing the allocations
typedef ip::managed_shared_memory::segment_manager SegmentManager;
}
typedef ip::allocator<Frame, SegmentManager> FrameAllocator;
typedef ip::vector<Frame, FrameAllocator> FrameVector;
#endif //SHARED_FRAME_H

@ -0,0 +1,340 @@
/*
This is a Optical-Character-Recognition program
Copyright (C) 2000-2009 Joerg Schulenburg
This program is free software; you can redistribute it and/or
modify it under the terms of the GNU General Public License
as published by the Free Software Foundation; either version 2
of the License, or (at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program; if not, write to the Free Software
Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
see README for EMAIL-address
sometimes I have written comments in german language, sorry for that
This file was retrieved from pgm2asc.cc of Joerg, in order to have
a library of the ocr-engine from Klaas Freitag
*/
#include "config.h"
#include <stdlib.h>
#include <stdio.h>
#include <assert.h>
#include <string.h>
#ifdef HAVE_GETTIMEOFDAY
#include <sys/time.h>
#endif
#ifdef HAVE_UNISTD_H
#include <unistd.h>
#endif
#include "pnm.h"
#include "pgm2asc.h"
#include "pcx.h"
#include "ocr0.h" /* only_numbers */
#include "progress.h"
#include "version.h"
static void out_version(int v) {
fprintf(stderr, " Optical Character Recognition --- gocr "
version_string " " release_string "\n"
" Copyright (C) 2001-2009 Joerg Schulenburg GPG=1024D/53BDFBE3\n"
" released under the GNU General Public License\n");
/* as recommended, (c) and license should be part of the binary */
/* no email because of SPAM, see README for contacting the author */
if (v)
fprintf(stderr, " use option -h for help\n");
if (v & 2)
exit(1);
return;
}
static void help(void) {
out_version(0);
/* output is shortened to essentials, see manual page for details */
fprintf(stderr,
" using: gocr [options] pnm_file_name # use - for stdin\n"
" options (see gocr manual pages for more details):\n"
" -h, --help\n"
" -i name - input image file (pnm,pgm,pbm,ppm,pcx,...)\n"
" -o name - output file (redirection of stdout)\n"
" -e name - logging file (redirection of stderr)\n"
" -x name - progress output to fifo (see manual)\n"
" -p name - database path including final slash (default is ./db/)\n");
fprintf(stderr, /* string length less than 509 bytes for ISO C89 */
" -f fmt - output format (ISO8859_1 TeX HTML XML UTF8 ASCII)\n"
" -l num - threshold grey level 0<160<=255 (0 = autodetect)\n"
" -d num - dust_size (remove small clusters, -1 = autodetect)\n"
" -s num - spacewidth/dots (0 = autodetect)\n"
" -v num - verbose (see manual page)\n"
" -c string - list of chars (debugging, see manual)\n"
" -C string - char filter (ex. hexdigits: ""0-9A-Fx"", only ASCII)\n"
" -m num - operation modes (bitpattern, see manual)\n");
fprintf(stderr, /* string length less than 509 bytes for ISO C89 */
" -a num - value of certainty (in percent, 0..100, default=95)\n"
" -u string - output this string for every unrecognized character\n");
fprintf(stderr, /* string length less than 509 bytes for ISO C89 */
" examples:\n"
"\tgocr -m 4 text1.pbm # do layout analyzis\n"
"\tgocr -m 130 -p ./database/ text1.pbm # extend database\n"
"\tdjpeg -pnm -gray text.jpg | gocr - # use jpeg-file via pipe\n"
"\n");
fprintf(stderr, " webpage: http://jocr.sourceforge.net/\n");
exit(0);
}
#ifdef HAVE_GETTIMEOFDAY
/* from the glibc documentation */
static int timeval_subtract (struct timeval *result, struct timeval *x,
struct timeval *y) {
/* Perform the carry for the later subtraction by updating Y. */
if (x->tv_usec < y->tv_usec) {
int nsec = (y->tv_usec - x->tv_usec) / 1000000 + 1;
y->tv_usec -= 1000000 * nsec;
y->tv_sec += nsec;
}
if (x->tv_usec - y->tv_usec > 1000000) {
int nsec = (x->tv_usec - y->tv_usec) / 1000000;
y->tv_usec += 1000000 * nsec;
y->tv_sec -= nsec;
}
/* Compute the time remaining to wait.
`tv_usec' is certainly positive. */
result->tv_sec = x->tv_sec - y->tv_sec;
result->tv_usec = x->tv_usec - y->tv_usec;
/* Return 1 if result is negative. */
return x->tv_sec < y->tv_sec;
}
#endif
static void process_arguments(job_t *job, int argn, char *argv[])
{
int i;
char *s1;
assert(job);
if (argn <= 1) {
out_version(1);
exit(0);
}
#ifdef HAVE_PGM_H
pnm_init(&argn, &argv);
#endif
/* process arguments */
for (i = 1; i < argn; i++) {
if (strcmp(argv[i], "--help") == 0)
help(); /* and quits */
if (argv[i][0] == '-' && argv[i][1] != 0) {
s1 = "";
if (i + 1 < argn)
s1 = argv[i + 1];
switch (argv[i][1]) {
case 'h': /* help */
help();
break;
case 'i': /* input image file */
job->src.fname = s1;
i++;
break;
case 'e': /* logging file */
if (s1[0] == '-' && s1[1] == '\0') {
#ifdef HAVE_UNISTD_H
dup2(STDOUT_FILENO, STDERR_FILENO); /* -e /dev/stdout works */
#else
fprintf(stderr, "stderr redirection not possible without unistd.h\n");
#endif
}
else if (!freopen(s1, "w", stderr)) {
fprintf(stderr, "stderr redirection to %s failed\n", s1);
}
i++;
break;
case 'p': /* database path */
job->cfg.db_path=s1;
i++;
break;
case 'o': /* output file */
if (s1[0] == '-' && s1[1] == '\0') { /* default */
}
else if (!freopen(s1, "w", stdout)) {
fprintf(stderr, "stdout redirection to %s failed\n", s1);
};
i++;
break;
case 'f': /* output format */
if (strcmp(s1, "ISO8859_1") == 0) job->cfg.out_format=ISO8859_1; else
if (strcmp(s1, "TeX") == 0) job->cfg.out_format=TeX; else
if (strcmp(s1, "HTML") == 0) job->cfg.out_format=HTML; else
if (strcmp(s1, "XML") == 0) job->cfg.out_format=XML; else
if (strcmp(s1, "SGML") == 0) job->cfg.out_format=SGML; else
if (strcmp(s1, "UTF8") == 0) job->cfg.out_format=UTF8; else
if (strcmp(s1, "ASCII") == 0) job->cfg.out_format=ASCII; else
fprintf(stderr,"Warning: unknown format (-f %s)\n",s1);
i++;
break;
case 'c': /* list of chars (_ = not recognized chars) */
job->cfg.lc = s1;
i++;
break;
case 'C': /* char filter, default: NULL (all chars) */
/* ToDo: UTF8 input, wchar */
job->cfg.cfilter = s1;
i++;
break;
case 'd': /* dust size */
job->cfg.dust_size = atoi(s1);
i++;
break;
case 'l': /* grey level 0<160<=255, 0 for autodetect */
job->cfg.cs = atoi(s1);
i++;
break;
case 's': /* spacewidth/dots (0 = autodetect) */
job->cfg.spc = atoi(s1);
i++;
break;
case 'v': /* verbose mode */
job->cfg.verbose |= atoi(s1);
i++;
break;
case 'm': /* operation modes */
job->cfg.mode |= atoi(s1);
i++;
break;
case 'n': /* numbers only */
job->cfg.only_numbers = atoi(s1);
i++;
break;
case 'x': /* initialize progress output s1=fname */
ini_progress(s1);
i++;
break;
case 'a': /* set certainty */
job->cfg.certainty = atoi(s1);;
i++;
break;
case 'u': /* output marker for unrecognized chars */
job->cfg.unrec_marker = s1;
i++;
break;
default:
fprintf(stderr, "# unknown option use -h for help\n");
}
continue;
}
else /* argument can be filename v0.2.5 */ if (argv[i][0] != '-'
|| argv[i][1] == '\0' ) {
job->src.fname = argv[i];
}
}
}
static void mark_start(job_t *job) {
assert(job);
if (job->cfg.verbose) {
out_version(0);
/* insert some helpful info for support */
fprintf(stderr, "# compiled: " __DATE__ );
#if defined(__GNUC__)
fprintf(stderr, " GNUC-%d", __GNUC__ );
#endif
#ifdef __GNUC_MINOR__
fprintf(stderr, ".%d", __GNUC_MINOR__ );
#endif
#if defined(__linux)
fprintf(stderr, " linux");
#elif defined(__unix)
fprintf(stderr, " unix");
#endif
#if defined(__WIN32) || defined(__WIN32__)
fprintf(stderr, " WIN32");
#endif
#if defined(__WIN64) || defined(__WIN64__)
fprintf(stderr, " WIN64");
#endif
#if defined(__VERSION__)
fprintf(stderr, " version " __VERSION__ );
#endif
fprintf(stderr, "\n");
fprintf(stderr,
"# options are: -l %d -s %d -v %d -c %s -m %d -d %d -n %d -a %d -C \"%s\"\n",
job->cfg.cs, job->cfg.spc, job->cfg.verbose, job->cfg.lc, job->cfg.mode,
job->cfg.dust_size, job->cfg.only_numbers, job->cfg.certainty,
job->cfg.cfilter);
fprintf(stderr, "# file: %s\n", job->src.fname);
#ifdef USE_UNICODE
fprintf(stderr,"# using unicode\n");
#endif
#ifdef HAVE_GETTIMEOFDAY
gettimeofday(&job->tmp.init_time, NULL);
#endif
}
}
static void mark_end(job_t *job) {
assert(job);
#ifdef HAVE_GETTIMEOFDAY
/* show elapsed time */
if (job->cfg.verbose) {
struct timeval end, result;
gettimeofday(&end, NULL);
timeval_subtract(&result, &end, &job->tmp.init_time);
fprintf(stderr,"Elapsed time: %d:%02d:%3.3f.\n", (int)result.tv_sec/60,
(int)result.tv_sec%60, (float)result.tv_usec/1000);
}
#endif
}
static int read_picture(job_t *job) {
int rc=0;
assert(job);
if (strstr(job->src.fname, ".pcx"))
readpcx(job->src.fname, &job->src.p, job->cfg.verbose);
else
rc=readpgm(job->src.fname, &job->src.p, job->cfg.verbose);
return rc; /* 1 for multiple images, 0 else */
}
/* subject of change, we need more output for XML (ToDo) */
void print_output(job_t *job) {
int linecounter = 0;
const char *line;
assert(job);
linecounter = 0;
line = getTextLine(linecounter++);
while (line) {
/* notice: decode() is shiftet to getTextLine since 0.38 */
fputs(line, stdout);
if (job->cfg.out_format==HTML) fputs("<br />",stdout);
if (job->cfg.out_format!=XML) fputc('\n', stdout);
line = getTextLine(linecounter++);
}
free_textlines();
}
/* FIXME jb: remove JOB; */
job_t *JOB;
/* -------------------------------------------------------------
// ------ MAIN - replace this by your own aplication!
// ------------------------------------------------------------- */

@ -0,0 +1,79 @@
// Copyright (C) 2007 by Cristóbal Carnero Liñán
// grendel.ccl@gmail.com
//
// This file is part of cvBlob.
//
// cvBlob is free software: you can redistribute it and/or modify
// it under the terms of the Lesser GNU General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// cvBlob 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
// Lesser GNU General Public License for more details.
//
// You should have received a copy of the Lesser GNU General Public License
// along with cvBlob. If not, see <http://www.gnu.org/licenses/>.
//
#include <cmath>
#if (defined(_WIN32) || defined(__WIN32__) || defined(__TOS_WIN__) || defined(__WINDOWS__) || (defined(__APPLE__) & defined(__MACH__)))
#include <cv.h>
#else
#include <opencv/cv.h>
#endif
#include "cvblob.h"
namespace cvb
{
//////////////////////////////////////////////////////////////////////////////////////////////////////////////
// http://www.topcoder.com/tc?module=Static&d1=tutorials&d2=geometry1
double cvDotProductPoints(CvPoint const &a, CvPoint const &b, CvPoint const &c)
{
double abx = b.x-a.x;
double aby = b.y-a.y;
double bcx = c.x-b.x;
double bcy = c.y-b.y;
return abx*bcx + aby*bcy;
}
double cvCrossProductPoints(CvPoint const &a, CvPoint const &b, CvPoint const &c)
{
double abx = b.x-a.x;
double aby = b.y-a.y;
double acx = c.x-a.x;
double acy = c.y-a.y;
return abx*acy - aby*acx;
}
double cvDistancePointPoint(CvPoint const &a, CvPoint const &b)
{
double abx = a.x-b.x;
double aby = a.y-b.y;
return sqrt(abx*abx + aby*aby);
}
double cvDistanceLinePoint(CvPoint const &a, CvPoint const &b, CvPoint const &c, bool isSegment)
{
if (isSegment)
{
double dot1 = cvDotProductPoints(a, b, c);
if (dot1>0) return cvDistancePointPoint(b, c);
double dot2 = cvDotProductPoints(b, a, c);
if(dot2>0) return cvDistancePointPoint(a, c);
}
return fabs(cvCrossProductPoints(a,b,c)/cvDistancePointPoint(a,b));
}
//////////////////////////////////////////////////////////////////////////////////////////////////////////////
}

@ -0,0 +1,24 @@
int glui_img_spindown_0[] = { 12, 8, /* width, height */
255,255,255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 255,255,255, 127,127,127, 127,127,127,
127,127,127, 127,127,127, 127,127,127, 127,127,127, 127,127,127,
127,127,127, 127,127,127, 127,127,127, 0, 0, 0, 255,255,255,
191,191,191, 191,191,191, 191,191,191, 191,191,191, 191,191,191,
191,191,191, 191,191,191, 191,191,191, 191,191,191, 127,127,127,
0, 0, 0, 255,255,255, 191,191,191, 191,191,191, 191,191,191,
191,191,191, 0, 0, 0, 127,127,127, 191,191,191, 191,191,191,
191,191,191, 127,127,127, 0, 0, 0, 255,255,255, 191,191,191,
191,191,191, 191,191,191, 0, 0, 0, 0, 0, 0, 0, 0, 0,
127,127,127, 191,191,191, 191,191,191, 127,127,127, 0, 0, 0,
255,255,255, 191,191,191, 191,191,191, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 127,127,127, 191,191,191,
127,127,127, 0, 0, 0, 255,255,255, 191,191,191, 191,191,191,
191,191,191, 191,191,191, 191,191,191, 191,191,191, 191,191,191,
191,191,191, 191,191,191, 127,127,127, 0, 0, 0, 255,255,255,
255,255,255, 255,255,255, 255,255,255, 255,255,255, 255,255,255,
255,255,255, 255,255,255, 255,255,255, 255,255,255, 255,255,255,
0, 0, 0,
};

@ -0,0 +1,299 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 2.8
# Default target executed when no arguments are given to make.
default_target: all
.PHONY : default_target
#=============================================================================
# Special targets provided by cmake.
# Disable implicit rules so canoncical targets will work.
.SUFFIXES:
# Remove some rules from gmake that .SUFFIXES does not remove.
SUFFIXES =
.SUFFIXES: .hpux_make_needs_suffix_list
# Suppress display of executed commands.
$(VERBOSE).SILENT:
# A target that is always out of date.
cmake_force:
.PHONY : cmake_force
#=============================================================================
# Set environment variables for the build.
# The shell in which to execute make rules.
SHELL = /bin/sh
# The CMake executable.
CMAKE_COMMAND = /usr/bin/cmake
# The command to remove a file.
RM = /usr/bin/cmake -E remove -f
# The program to use to edit the cache.
CMAKE_EDIT_COMMAND = /usr/bin/ccmake
# The top-level source directory on which CMake was run.
CMAKE_SOURCE_DIR = /home/dborrman/Jacobs/software/slam6d/trunk
# The top-level build directory on which CMake was run.
CMAKE_BINARY_DIR = /home/dborrman/Jacobs/software/slam6d/trunk
#=============================================================================
# Targets provided globally by CMake.
# Special rule for the target edit_cache
edit_cache:
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake cache editor..."
/usr/bin/ccmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR)
.PHONY : edit_cache
# Special rule for the target edit_cache
edit_cache/fast: edit_cache
.PHONY : edit_cache/fast
# Special rule for the target rebuild_cache
rebuild_cache:
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..."
/usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR)
.PHONY : rebuild_cache
# Special rule for the target rebuild_cache
rebuild_cache/fast: rebuild_cache
.PHONY : rebuild_cache/fast
# The main all target
all: cmake_check_build_system
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(CMAKE_COMMAND) -E cmake_progress_start /home/dborrman/Jacobs/software/slam6d/trunk/CMakeFiles /home/dborrman/Jacobs/software/slam6d/trunk/3rdparty/cvblob/CMakeFiles/progress.marks
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f CMakeFiles/Makefile2 3rdparty/cvblob/all
$(CMAKE_COMMAND) -E cmake_progress_start /home/dborrman/Jacobs/software/slam6d/trunk/CMakeFiles 0
.PHONY : all
# The main clean target
clean:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f CMakeFiles/Makefile2 3rdparty/cvblob/clean
.PHONY : clean
# The main clean target
clean/fast: clean
.PHONY : clean/fast
# Prepare targets for installation.
preinstall: all
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f CMakeFiles/Makefile2 3rdparty/cvblob/preinstall
.PHONY : preinstall
# Prepare targets for installation.
preinstall/fast:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f CMakeFiles/Makefile2 3rdparty/cvblob/preinstall
.PHONY : preinstall/fast
# clear depends
depend:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1
.PHONY : depend
# Convenience name for target.
3rdparty/cvblob/CMakeFiles/cvblob.dir/rule:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f CMakeFiles/Makefile2 3rdparty/cvblob/CMakeFiles/cvblob.dir/rule
.PHONY : 3rdparty/cvblob/CMakeFiles/cvblob.dir/rule
# Convenience name for target.
cvblob: 3rdparty/cvblob/CMakeFiles/cvblob.dir/rule
.PHONY : cvblob
# fast build rule for target.
cvblob/fast:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/build
.PHONY : cvblob/fast
cvaux.o: cvaux.cpp.o
.PHONY : cvaux.o
# target to build an object file
cvaux.cpp.o:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvaux.cpp.o
.PHONY : cvaux.cpp.o
cvaux.i: cvaux.cpp.i
.PHONY : cvaux.i
# target to preprocess a source file
cvaux.cpp.i:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvaux.cpp.i
.PHONY : cvaux.cpp.i
cvaux.s: cvaux.cpp.s
.PHONY : cvaux.s
# target to generate assembly for a file
cvaux.cpp.s:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvaux.cpp.s
.PHONY : cvaux.cpp.s
cvblob.o: cvblob.cpp.o
.PHONY : cvblob.o
# target to build an object file
cvblob.cpp.o:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvblob.cpp.o
.PHONY : cvblob.cpp.o
cvblob.i: cvblob.cpp.i
.PHONY : cvblob.i
# target to preprocess a source file
cvblob.cpp.i:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvblob.cpp.i
.PHONY : cvblob.cpp.i
cvblob.s: cvblob.cpp.s
.PHONY : cvblob.s
# target to generate assembly for a file
cvblob.cpp.s:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvblob.cpp.s
.PHONY : cvblob.cpp.s
cvcolor.o: cvcolor.cpp.o
.PHONY : cvcolor.o
# target to build an object file
cvcolor.cpp.o:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvcolor.cpp.o
.PHONY : cvcolor.cpp.o
cvcolor.i: cvcolor.cpp.i
.PHONY : cvcolor.i
# target to preprocess a source file
cvcolor.cpp.i:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvcolor.cpp.i
.PHONY : cvcolor.cpp.i
cvcolor.s: cvcolor.cpp.s
.PHONY : cvcolor.s
# target to generate assembly for a file
cvcolor.cpp.s:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvcolor.cpp.s
.PHONY : cvcolor.cpp.s
cvcontour.o: cvcontour.cpp.o
.PHONY : cvcontour.o
# target to build an object file
cvcontour.cpp.o:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvcontour.cpp.o
.PHONY : cvcontour.cpp.o
cvcontour.i: cvcontour.cpp.i
.PHONY : cvcontour.i
# target to preprocess a source file
cvcontour.cpp.i:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvcontour.cpp.i
.PHONY : cvcontour.cpp.i
cvcontour.s: cvcontour.cpp.s
.PHONY : cvcontour.s
# target to generate assembly for a file
cvcontour.cpp.s:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvcontour.cpp.s
.PHONY : cvcontour.cpp.s
cvlabel.o: cvlabel.cpp.o
.PHONY : cvlabel.o
# target to build an object file
cvlabel.cpp.o:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvlabel.cpp.o
.PHONY : cvlabel.cpp.o
cvlabel.i: cvlabel.cpp.i
.PHONY : cvlabel.i
# target to preprocess a source file
cvlabel.cpp.i:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvlabel.cpp.i
.PHONY : cvlabel.cpp.i
cvlabel.s: cvlabel.cpp.s
.PHONY : cvlabel.s
# target to generate assembly for a file
cvlabel.cpp.s:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvlabel.cpp.s
.PHONY : cvlabel.cpp.s
cvtrack.o: cvtrack.cpp.o
.PHONY : cvtrack.o
# target to build an object file
cvtrack.cpp.o:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvtrack.cpp.o
.PHONY : cvtrack.cpp.o
cvtrack.i: cvtrack.cpp.i
.PHONY : cvtrack.i
# target to preprocess a source file
cvtrack.cpp.i:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvtrack.cpp.i
.PHONY : cvtrack.cpp.i
cvtrack.s: cvtrack.cpp.s
.PHONY : cvtrack.s
# target to generate assembly for a file
cvtrack.cpp.s:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(MAKE) -f 3rdparty/cvblob/CMakeFiles/cvblob.dir/build.make 3rdparty/cvblob/CMakeFiles/cvblob.dir/cvtrack.cpp.s
.PHONY : cvtrack.cpp.s
# Help Target
help:
@echo "The following are some of the valid targets for this Makefile:"
@echo "... all (the default if no target is provided)"
@echo "... clean"
@echo "... depend"
@echo "... cvblob"
@echo "... edit_cache"
@echo "... rebuild_cache"
@echo "... cvaux.o"
@echo "... cvaux.i"
@echo "... cvaux.s"
@echo "... cvblob.o"
@echo "... cvblob.i"
@echo "... cvblob.s"
@echo "... cvcolor.o"
@echo "... cvcolor.i"
@echo "... cvcolor.s"
@echo "... cvcontour.o"
@echo "... cvcontour.i"
@echo "... cvcontour.s"
@echo "... cvlabel.o"
@echo "... cvlabel.i"
@echo "... cvlabel.s"
@echo "... cvtrack.o"
@echo "... cvtrack.i"
@echo "... cvtrack.s"
.PHONY : help
#=============================================================================
# Special targets to cleanup operation of make.
# Special rule to run CMake to check the build system integrity.
# No rule that depends on this can have commands that come from listfiles
# because they might be regenerated.
cmake_check_build_system:
cd /home/dborrman/Jacobs/software/slam6d/trunk && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0
.PHONY : cmake_check_build_system

@ -0,0 +1,662 @@
/****************************************************************************
GLUI User Interface Toolkit
---------------------------
glui_add_controls.cpp - Routines for adding controls to a GLUI window
--------------------------------------------------
Copyright (c) 1998 Paul Rademacher
This program is freely distributable without licensing fees and is
provided without guarantee or warrantee expressed or implied. This
program is -not- in the public domain.
*****************************************************************************/
#include "glui.h"
#include "stdinc.h"
/*********************************** GLUI:: add_checkbox() ************/
GLUI_Checkbox *GLUI:: add_checkbox( char *name, int *value_ptr,
int id, GLUI_Update_CB callback )
{
return add_checkbox_to_panel( main_panel,
name, value_ptr, id, callback );
}
/*********************************** GLUI:: add_checkbox_to_panel() **********/
GLUI_Checkbox *GLUI::add_checkbox_to_panel( GLUI_Panel *panel,
char *name, int *value_ptr,
int id,
GLUI_Update_CB callback )
{
GLUI_Checkbox *control;
control = new GLUI_Checkbox;
if ( control ) {
control->set_ptr_val( value_ptr );
control->user_id = id;
control->set_name( name );
control->callback = callback;
add_control( panel, control );
control->init_live();
return control;
}
else {
return NULL;
}
}
/************************************ GLUI_Main::add_control() **************/
int GLUI_Main::add_control( GLUI_Node *parent, GLUI_Control *control )
{
GLUI_Control *parent_control;
/*** Collapsible nodes have to be handled differently, b/c the first and
last children are swapped in and out ***/
parent_control = ((GLUI_Control*)parent);
if ( parent_control->collapsible == true ) {
if ( NOT parent_control->is_open ) {
/** Swap in the original first and last children **/
parent_control->child_head = parent_control->collapsed_node.child_head;
parent_control->child_tail = parent_control->collapsed_node.child_tail;
/*** Link this control ***/
control->link_this_to_parent_last( parent );
/** Swap the children back out ***/
parent_control->collapsed_node.child_head = parent_control->child_head;
parent_control->collapsed_node.child_tail = parent_control->child_tail;
parent_control->child_head = NULL;
parent_control->child_tail = NULL;
}
else {
control->link_this_to_parent_last( parent );
}
}
else {
control->link_this_to_parent_last( parent );
}
control->glui = (GLUI*) this;
control->update_size();
control->enabled = ((GLUI_Control*) parent)->enabled;
control->glui->refresh();
/** Now set the 'hidden' var based on the parent **/
if ( parent_control->hidden OR
(parent_control->collapsible AND NOT parent_control->is_open ) )
{
control->hidden = true;
}
return true;
}
/********************************************* GLUI::add_panel() *************/
GLUI_Panel *GLUI::add_panel( char *name, int type )
{
return add_panel_to_panel( main_panel, name, type );
}
/**************************************** GLUI::add_panel_to_panel() *********/
GLUI_Panel *GLUI::add_panel_to_panel( GLUI_Panel *parent_panel,
char *name, int type )
{
GLUI_Panel *panel;
panel = new GLUI_Panel;
if ( panel ) {
panel->set_name( name );
panel->user_id = -1;
panel->int_val = type;
add_control( parent_panel, panel );
return panel;
}
else {
return NULL;
}
}
/***************************** GLUI::add_radiogroup() ***************/
GLUI_RadioGroup *GLUI::add_radiogroup( int *value_ptr,
int user_id, GLUI_Update_CB callback)
{
return add_radiogroup_to_panel( main_panel, value_ptr,
user_id, callback );
}
/***************************** GLUI::add_radiogroup_to_panel() ***************/
GLUI_RadioGroup *GLUI::add_radiogroup_to_panel( GLUI_Panel *panel,
int *value_ptr,
int user_id, GLUI_Update_CB callback)
{
GLUI_RadioGroup *control;
GLUI_String buf;
control = new GLUI_RadioGroup;
if ( control ) {
control->set_ptr_val( value_ptr );
if ( value_ptr ) {
control->int_val = *value_ptr; /** Can't call set_int_val(), b/c that
function will try to call the
callback, etc */
/** Actually, maybe not **/
control->last_live_int = *value_ptr;
}
control->user_id = user_id;
sprintf( buf, "RadioGroup: %p", control );
control->set_name( buf );
control->callback = callback;
add_control( panel, control );
control->init_live();
return control;
}
else {
return NULL;
}
}
/***************************** GLUI::add_radiobutton_to_group() *************/
GLUI_RadioButton *GLUI::add_radiobutton_to_group( GLUI_RadioGroup *group,
char *name )
{
GLUI_RadioButton *control;
if ( group->type != GLUI_CONTROL_RADIOGROUP ) {
/*fprintf( stderr, "ERROR: Trying to add radiobutton to non-radiogroup\n" ); */
/*fflush( stderr ); */
return NULL;
}
control = new GLUI_RadioButton;
if ( control ) {
control->set_int_val( 0 );
/*int_val = 0; */
/** A radio button's user id is always its ordinal number (zero-indexed)
within the group */
control->user_id = group->num_buttons;
group->num_buttons++; /* Increments radiogroup's button count */
control->set_name( name );
control->group = group;
add_control( group, control );
/*** Now update button states ***/
group->set_int_val( group->int_val ); /* This tells the group to
reset itself to its
current value, thereby
updating all its buttons */
return control;
}
else {
return NULL;
}
}
/********************************** GLUI::add_statictext() ************/
GLUI_StaticText *GLUI::add_statictext( char *name )
{
return add_statictext_to_panel( main_panel, name );
}
/******************************* GLUI::add_statictext_to_panel() **********/
GLUI_StaticText *GLUI::
add_statictext_to_panel( GLUI_Panel *panel, char *name )
{
GLUI_StaticText *control;
control = new GLUI_StaticText;
if ( control ) {
control->set_name( name );
add_control( panel, control );
return control;
}
else {
return NULL;
}
}
/***************************************** GLUI:: add_button() ************/
GLUI_Button *GLUI:: add_button( char *name,
int id, GLUI_Update_CB callback )
{
return add_button_to_panel( main_panel,
name, id, callback );
}
/*********************************** GLUI:: add_button_to_panel() **********/
GLUI_Button *GLUI::add_button_to_panel( GLUI_Panel *panel,
char *name,
int id,
GLUI_Update_CB callback )
{
GLUI_Button *control;
control = new GLUI_Button;
if ( control ) {
/* control->set_ptr_val( value_ptr );
if ( value_ptr ) {
control->set_int_val( *value_ptr );
}*/
control->user_id = id;
control->callback = callback;
control->set_name( name );
add_control( panel, control );
return control;
}
else {
return NULL;
}
}
/********************************** GLUI::add_separator() ************/
void GLUI::add_separator( void )
{
add_separator_to_panel( main_panel );
}
/******************************* GLUI::add_separator_to_panel() **********/
void GLUI::add_separator_to_panel( GLUI_Panel *panel )
{
GLUI_Separator *control = new GLUI_Separator;
if ( control ) {
add_control( panel, control );
}
}
/********************************** GLUI::add_edittext() ************/
GLUI_EditText *GLUI::add_edittext( char *name,
int data_type, void *data,
int id, GLUI_Update_CB callback)
{
return add_edittext_to_panel( main_panel, name, data_type, data,
id, callback );
}
/******************************* GLUI::add_edittext_to_panel() **********/
GLUI_EditText *GLUI::
add_edittext_to_panel( GLUI_Panel *panel, char *name,
int data_type, void *data,
int id, GLUI_Update_CB callback)
{
GLUI_EditText *control;
control = new GLUI_EditText;
if ( control ) {
control->set_name( name );
control->data_type = data_type;
control->ptr_val = data;
control->user_id = id;
control->callback = callback;
if ( data_type == GLUI_EDITTEXT_TEXT ) {
control->live_type = GLUI_LIVE_TEXT;
}
else if ( data_type == GLUI_EDITTEXT_INT ) {
control->live_type = GLUI_LIVE_INT;
if ( data == NULL )
control->set_int_val(control->int_val); /** Set to some default, in case of no live var **/
}
else if ( data_type == GLUI_EDITTEXT_FLOAT ) {
control->live_type = GLUI_LIVE_FLOAT;
control->num_periods = 1;
if ( data == NULL )
control->set_float_val(control->float_val); /** Set to some default, in case of no live var **/
}
else {
return NULL; /* Did not pass in a valid data type */
}
add_control( panel, control );
control->init_live();
return control;
}
else {
return NULL;
}
}
/********************************** GLUI::add_spinner() ************/
GLUI_Spinner *GLUI::add_spinner( char *name,
int data_type, void *data,
int id, GLUI_Update_CB callback)
{
return add_spinner_to_panel( main_panel, name, data_type, data,
id, callback );
}
/******************************* GLUI::add_spinner_to_panel() **********/
GLUI_Spinner *GLUI::
add_spinner_to_panel( GLUI_Panel *panel, char *name,
int data_type, void *data,
int id, GLUI_Update_CB callback)
{
GLUI_Spinner *control;
int text_type;
control = new GLUI_Spinner;
if ( NOT strcmp( name, "Spinner Test" ))
id=id;
if ( control ) {
if ( data_type == GLUI_SPINNER_INT ) {
text_type = GLUI_EDITTEXT_INT;
/* control->live_type = GLUI_LIVE_INT; */
}
else if ( data_type == GLUI_SPINNER_FLOAT ) {
text_type = GLUI_EDITTEXT_FLOAT;
/* control->live_type = GLUI_LIVE_FLOAT; */
}
else {
return NULL; /* Did not pass in a valid data type */
}
GLUI_EditText *edittext =
add_edittext_to_panel( (GLUI_Panel*) control, name, text_type, data,
id, callback );
if ( edittext ) {
control->set_name( name );
control->edittext = edittext; /* Link the edittext to the spinner */
/* control->ptr_val = data; */
control->user_id = id;
control->data_type = data_type;
control->callback = callback;
edittext->spinner = control; /* Link the spinner to the edittext */
add_control( panel, control );
return control;
}
else {
return NULL;
}
}
else {
return NULL;
}
}
/********************************** GLUI::add_column() ************/
void GLUI::add_column( int draw_bar )
{
add_column_to_panel( main_panel, draw_bar );
}
/******************************* GLUI::add_column_to_panel() **********/
void GLUI::add_column_to_panel( GLUI_Panel *panel, int draw_bar )
{
GLUI_Column *control = new GLUI_Column;
if ( control ) {
control->int_val = draw_bar; /* Whether to draw vertical bar or not */
add_control( panel, control );
}
else {
}
}
/*********************************** GLUI:: add_listbox() ************/
GLUI_Listbox *GLUI:: add_listbox( char *name, int *value_ptr,
int id, GLUI_Update_CB callback )
{
return add_listbox_to_panel( main_panel,
name, value_ptr, id, callback );
}
/*********************************** GLUI:: add_listbox_to_panel() **********/
GLUI_Listbox *GLUI::add_listbox_to_panel( GLUI_Panel *panel,
char *name, int *value_ptr,
int id,
GLUI_Update_CB callback )
{
GLUI_Listbox *control;
control = new GLUI_Listbox;
if ( control ) {
control->set_ptr_val( value_ptr );
control->user_id = id;
control->set_name( name );
control->callback = callback;
add_control( panel, control );
control->init_live();
return control;
}
else {
return NULL;
}
}
/*********************************** GLUI:: add_rotation() ************/
GLUI_Rotation *GLUI:: add_rotation( char *name, float *value_ptr,
int id, GLUI_Update_CB callback )
{
return add_rotation_to_panel( main_panel,
name, value_ptr, id, callback );
}
/*********************************** GLUI:: add_rotation_to_panel() **********/
GLUI_Rotation *GLUI::add_rotation_to_panel( GLUI_Panel *panel,
char *name, float *value_ptr,
int id,
GLUI_Update_CB callback )
{
GLUI_Rotation *control;
control = new GLUI_Rotation;
if ( control ) {
control->set_ptr_val( value_ptr );
control->user_id = id;
control->set_name( name );
control->callback = callback;
add_control( panel, control );
control->init_live();
/*** Init the live 4x4 matrix. This is different than the standard
live variable behavior, since the original value of the 4x4 matrix
is ignored and reset to Identity ***/
if ( value_ptr != NULL ) {
int i, j, index;
for( i=0; i<4; i++ ) {
for( j=0; j<4; j++ ) {
index = i*4+j;
if ( i==j )
value_ptr[index] = 1.0;
else
value_ptr[index] = 0.0;
}
}
}
/*init_ball(); */
return control;
}
else {
return NULL;
}
}
/*********************************** GLUI:: add_translation() ************/
GLUI_Translation
*GLUI:: add_translation( char *name, int trans_type,
float *value_ptr, int id, GLUI_Update_CB callback )
{
return add_translation_to_panel( main_panel,name,trans_type,
value_ptr, id, callback );
}
/*********************************** GLUI:: add_translation_to_panel() **********/
GLUI_Translation
*GLUI::add_translation_to_panel(
GLUI_Panel *panel, char *name,
int trans_type, float *value_ptr,
int id, GLUI_Update_CB callback )
{
GLUI_Translation *control;
control = new GLUI_Translation;
if ( control ) {
control->set_ptr_val( value_ptr );
control->user_id = id;
control->set_name( name );
control->callback = callback;
add_control( panel, control );
control->init_live();
control->trans_type = trans_type;
if ( trans_type == GLUI_TRANSLATION_XY ) {
control->float_array_size = 2;
}
else if ( trans_type == GLUI_TRANSLATION_X ) {
control->float_array_size = 1;
}
else if ( trans_type == GLUI_TRANSLATION_Y ) {
control->float_array_size = 1;
}
else if ( trans_type == GLUI_TRANSLATION_Z ) {
control->float_array_size = 1;
}
return control;
}
else {
return NULL;
}
}
/********************************** GLUI::add_rollout() **************/
GLUI_Rollout *GLUI::add_rollout( char *name, int open )
{
return add_rollout_to_panel( main_panel, name, open );
}
/****************************** GLUI::add_rollout_to_panel() *********/
GLUI_Rollout *GLUI::add_rollout_to_panel(GLUI_Panel *panel,char *name,int open)
{
GLUI_Rollout *rollout;
rollout = new GLUI_Rollout;
if ( rollout ) {
rollout->set_name( name );
rollout->user_id = -1;
rollout->int_val = GLUI_PANEL_EMBOSSED;
if ( NOT open ) {
rollout->is_open = false;
rollout->h = GLUI_DEFAULT_CONTROL_HEIGHT + 7;
}
add_control( panel, rollout );
return rollout;
}
else {
return NULL;
}
}

@ -0,0 +1,21 @@
/**
* @file HOG-Man wrapper
* @author Jochen Sprickerhof. Institute of Computer Science, University of Osnabrueck, Germany.
*/
#ifndef __LOOP_HOG_MAN_H__
#define __LOOP_HOG_MAN_H__
#include "loopSlam6D.h"
class loopHOGMan : public loopSlam6D {
public:
loopHOGMan(bool _quiet, icp6Dminimizer *my_icp6Dminimizer, double mdm, int max_num_iterations,
int rnd, bool eP, int anim, double epsilonICP, int nns_method)
: loopSlam6D(_quiet, my_icp6Dminimizer, mdm, max_num_iterations, rnd, eP, anim, epsilonICP, nns_method) {}
virtual void close_loop(const vector <Scan *> &allScans, int first, int last, graph_t &g);
};
#endif

@ -0,0 +1,447 @@
/*
* ghelix6DQ2 implementation
*
* Copyright (C) Peter Schneider, Jan Elseberg, Andreas Nuechter
*
* Released under the GPL version 3.
*
*/
/**
* @file
* @brief The implementation of globally consistent scan matching algorithm by using helix correction
* @author Peter Schneider. Institute of Computer Science, University of Koblenz, Germany.
* @author Andreas Nuechter. Jacobs University Bremen gGmbH, Germany
* @author Jan Elseberg. Jacobs University Bremen gGmbH, Germany
*/
#ifdef _MSC_VER
#if !defined _OPENMP && defined OPENMP
#define _OPENMP
#endif
#endif
#include "slam6d/ghelix6DQ2.h"
#include "slam6d/icp6Dhelix.h"
#include "sparse/csparse.h"
#include <cfloat>
#include <fstream>
using std::flush;
#include <cstring>
#include "slam6d/globals.icc"
using std::ofstream;
/**
* Constructor
*
* @param my_icp6Dminimizer Pointer to ICP minimization functor
* @param mdm Maximum PtoP distance to which point pairs are collected for ICP
* @param max_dist_match Maximum PtoP distance to which point pairs are collected for LUM
* @param max_num_iterations Maximal number of iterations for ICP
* @param quiet Suspesses all output to std out
* @param meta Indicates if metascan matching has to be used
* @param rnd Indicates if randomization has to be used
* @param eP Extrapolate odometry?
* @param anim Animate which frames?
* @param epsilonICP Termination criterion for ICP
* @param nns_method Specifies which NNS method to use
* @param epsilonLUM Termination criterion for LUM
*/
ghelix6DQ2::ghelix6DQ2(icp6Dminimizer *my_icp6Dminimizer,
double mdm, double max_dist_match,
int max_num_iterations, bool quiet, bool meta, int rnd,
bool eP, int anim, double epsilonICP, int nns_method, double epsilonLUM)
: graphSlam6D(my_icp6Dminimizer,
mdm, max_dist_match,
max_num_iterations, quiet, meta, rnd,
eP, anim, epsilonICP, nns_method, epsilonLUM)
{ }
/**
* Destructor
*/
ghelix6DQ2::~ghelix6DQ2()
{
delete my_icp;
}
/**
* This function generates the matrices B and Bd that are used for solving B * c = Bd.
* This function has to be called once for every linked scan-pair.
*
* @param firstScanNum The number of the first scan of the linked scan-pair
* @param secondScanNum The number of the second scan of the linked scan-pair
* @param ptpairs Vector that holds all point-pairs for the actual scan-pair
* @param B Matrix with dimension (6*(number of scans-1)) x (6 * (number of scans-1))
* @param Bd Vector with dimension (6*(number of scans-1))
* @return returns the sum of square distance
*/
double ghelix6DQ2::genBBdForLinkedPair( int firstScanNum, int secondScanNum, vPtPair *ptpairs,
Matrix *B, ColumnVector *Bd )
{
double Btemp1[6][3];
double Btemp2[6][3];
memset(&Btemp1[0][0], 0, 18 * sizeof(double));
memset(&Btemp2[0][0], 0, 18 * sizeof(double));
double bd1[6];
double bd2[6];
memset(&bd1[0], 0, 6 * sizeof(double));
memset(&bd2[0], 0, 6 * sizeof(double));
double p1x, p1y, p1z, p2x, p2y, p2z, pDistX, pDistY, pDistZ, px2Sq, py2Sq, pz2Sq;
int n = (*ptpairs).size();
double sum = 0;
for (int i = 0; i < n; i++) {
p1x = (*ptpairs)[i].p1.x;
p1y = (*ptpairs)[i].p1.y;
p1z = (*ptpairs)[i].p1.z;
p2x = (*ptpairs)[i].p2.x;
p2y = (*ptpairs)[i].p2.y;
p2z = (*ptpairs)[i].p2.z;
//px1Sq = p1x * p1x;
//py1Sq = p1y * p1y;
//pz1Sq = p1z * p1z;
px2Sq = p2x * p2x;
py2Sq = p2y * p2y;
pz2Sq = p2z * p2z;
Btemp1[4][0] += -p2z;
// Btemp1[3][1] += p2z;
Btemp1[5][0] += p2y;
// Btemp1[3][2] += -p2y;
Btemp1[4][2] += p2x;
// Btemp1[5][1] += -p2x;
Btemp1[0][0] += pz2Sq + py2Sq;
Btemp1[1][0] += p2y*-p2x;
Btemp1[2][0] += -p2z*p2x;
Btemp1[1][1] += pz2Sq + px2Sq;
Btemp1[2][1] += p2z*-p2y;
Btemp1[2][2] += px2Sq + py2Sq;
pDistX = p1x - p2x;
pDistY = p1y - p2y;
pDistZ = p1z - p2z;
bd1[0] += -p1z*pDistY + p1y*pDistZ;
bd1[1] += p1z*pDistX - p1x*pDistZ;
bd1[2] += -p1y*pDistX + p1x*pDistY;
bd1[3] += pDistX;
bd1[4] += pDistY;
bd1[5] += pDistZ;
bd2[0] += -p2z*-pDistY + p2y*-pDistZ;
bd2[1] += p2z*-pDistX - p2x*-pDistZ;
bd2[2] += -p2y*-pDistX + p2x*-pDistY;
bd2[3] += -pDistX;
bd2[4] += -pDistY;
bd2[5] += -pDistZ;
sum += pDistX*pDistX + pDistY*pDistY + pDistZ*pDistZ;
}
#ifdef _OPENMP
#pragma omp critical (enterB)
#endif
{
int matPlace1 = (firstScanNum-1) * 6;
if(firstScanNum != 0)
{
(*B)(matPlace1+4,matPlace1+4) += n;
(*B)(matPlace1+5,matPlace1+5) += n;
(*B)(matPlace1+6,matPlace1+6) += n;
(*B)(matPlace1+1,matPlace1+5) += Btemp1[4][0];
(*B)(matPlace1+5,matPlace1+1) += Btemp1[4][0];
(*B)(matPlace1+2,matPlace1+4) += -Btemp1[4][0];
(*B)(matPlace1+4,matPlace1+2) += -Btemp1[4][0];
(*B)(matPlace1+1,matPlace1+6) += Btemp1[5][0];
(*B)(matPlace1+6,matPlace1+1) += Btemp1[5][0];
(*B)(matPlace1+3,matPlace1+4) += -Btemp1[5][0];
(*B)(matPlace1+4,matPlace1+3) += -Btemp1[5][0];
(*B)(matPlace1+3,matPlace1+5) += Btemp1[4][2];
(*B)(matPlace1+5,matPlace1+3) += Btemp1[4][2];
(*B)(matPlace1+2,matPlace1+6) += -Btemp1[4][2];
(*B)(matPlace1+6,matPlace1+2) += -Btemp1[4][2];
(*B)(matPlace1+1,matPlace1+2) += Btemp1[1][0];
(*B)(matPlace1+2,matPlace1+1) += Btemp1[1][0];
(*B)(matPlace1+1,matPlace1+3) += Btemp1[2][0];
(*B)(matPlace1+3,matPlace1+1) += Btemp1[2][0];
(*B)(matPlace1+2,matPlace1+3) += Btemp1[2][1];
(*B)(matPlace1+3,matPlace1+2) += Btemp1[2][1];
(*B)(matPlace1+1,matPlace1+1) += Btemp1[0][0];
(*B)(matPlace1+2,matPlace1+2) += Btemp1[1][1];
(*B)(matPlace1+3,matPlace1+3) += Btemp1[2][2];
(*Bd)(matPlace1+1) += bd1[0];
(*Bd)(matPlace1+2) += bd1[1];
(*Bd)(matPlace1+3) += bd1[2];
(*Bd)(matPlace1+4) += bd1[3];
(*Bd)(matPlace1+5) += bd1[4];
(*Bd)(matPlace1+6) += bd1[5];
}
//-------------------------------------------
unsigned int matPlace2 = (secondScanNum-1) * 6;
(*B)(matPlace2+4,matPlace2+4) += n;
(*B)(matPlace2+5,matPlace2+5) += n;
(*B)(matPlace2+6,matPlace2+6) += n;
(*B)(matPlace2+1,matPlace2+5) += Btemp1[4][0];
(*B)(matPlace2+5,matPlace2+1) += Btemp1[4][0];
(*B)(matPlace2+2,matPlace2+4) += -Btemp1[4][0];
(*B)(matPlace2+4,matPlace2+2) += -Btemp1[4][0];
(*B)(matPlace2+1,matPlace2+6) += Btemp1[5][0];
(*B)(matPlace2+6,matPlace2+1) += Btemp1[5][0];
(*B)(matPlace2+3,matPlace2+4) += -Btemp1[5][0];
(*B)(matPlace2+4,matPlace2+3) += -Btemp1[5][0];
(*B)(matPlace2+3,matPlace2+5) += Btemp1[4][2];
(*B)(matPlace2+5,matPlace2+3) += Btemp1[4][2];
(*B)(matPlace2+2,matPlace2+6) += -Btemp1[4][2];
(*B)(matPlace2+6,matPlace2+2) += -Btemp1[4][2];
(*B)(matPlace2+1,matPlace2+2) += Btemp1[1][0];
(*B)(matPlace2+2,matPlace2+1) += Btemp1[1][0];
(*B)(matPlace2+1,matPlace2+3) += Btemp1[2][0];
(*B)(matPlace2+3,matPlace2+1) += Btemp1[2][0];
(*B)(matPlace2+2,matPlace2+3) += Btemp1[2][1];
(*B)(matPlace2+3,matPlace2+2) += Btemp1[2][1];
(*B)(matPlace2+1,matPlace2+1) += Btemp1[0][0];
(*B)(matPlace2+2,matPlace2+2) += Btemp1[1][1];
(*B)(matPlace2+3,matPlace2+3) += Btemp1[2][2];
(*Bd)(matPlace2+1) += bd2[0];
(*Bd)(matPlace2+2) += bd2[1];
(*Bd)(matPlace2+3) += bd2[2];
(*Bd)(matPlace2+4) += bd2[3];
(*Bd)(matPlace2+5) += bd2[4];
(*Bd)(matPlace2+6) += bd2[5];
//-------------------------------------------
if( firstScanNum != 0)
{
(*B)(matPlace1+4,matPlace2+4) -= n;
(*B)(matPlace1+5,matPlace2+5) -= n;
(*B)(matPlace1+6,matPlace2+6) -= n;
(*B)(matPlace1+1,matPlace2+5) += -Btemp1[4][0];
(*B)(matPlace1+5,matPlace2+1) += -Btemp1[4][0];
(*B)(matPlace1+2,matPlace2+4) += Btemp1[4][0];
(*B)(matPlace1+4,matPlace2+2) += Btemp1[4][0];
(*B)(matPlace1+1,matPlace2+6) += -Btemp1[5][0];
(*B)(matPlace1+6,matPlace2+1) += -Btemp1[5][0];
(*B)(matPlace1+3,matPlace2+4) += Btemp1[5][0];
(*B)(matPlace1+4,matPlace2+3) += Btemp1[5][0];
(*B)(matPlace1+3,matPlace2+5) += -Btemp1[4][2];
(*B)(matPlace1+5,matPlace2+3) += -Btemp1[4][2];
(*B)(matPlace1+2,matPlace2+6) += Btemp1[4][2];
(*B)(matPlace1+6,matPlace2+2) += Btemp1[4][2];
(*B)(matPlace1+1,matPlace2+2) += -Btemp1[1][0];
(*B)(matPlace1+2,matPlace2+1) += -Btemp1[1][0];
(*B)(matPlace1+1,matPlace2+3) += -Btemp1[2][0];
(*B)(matPlace1+3,matPlace2+1) += -Btemp1[2][0];
(*B)(matPlace1+2,matPlace2+3) += -Btemp1[2][1];
(*B)(matPlace1+3,matPlace2+2) += -Btemp1[2][1];
(*B)(matPlace1+1,matPlace2+1) += -Btemp1[0][0];
(*B)(matPlace1+2,matPlace2+2) += -Btemp1[1][1];
(*B)(matPlace1+3,matPlace2+3) += -Btemp1[2][2];
//----------------------------------------
(*B)(matPlace2+4,matPlace1+4) -= n;
(*B)(matPlace2+5,matPlace1+5) -= n;
(*B)(matPlace2+6,matPlace1+6) -= n;
(*B)(matPlace2+1,matPlace1+5) += -Btemp1[4][0];
(*B)(matPlace2+5,matPlace1+1) += -Btemp1[4][0];
(*B)(matPlace2+2,matPlace1+4) += Btemp1[4][0];
(*B)(matPlace2+4,matPlace1+2) += Btemp1[4][0];
(*B)(matPlace2+1,matPlace1+6) += -Btemp1[5][0];
(*B)(matPlace2+6,matPlace1+1) += -Btemp1[5][0];
(*B)(matPlace2+3,matPlace1+4) += Btemp1[5][0];
(*B)(matPlace2+4,matPlace1+3) += Btemp1[5][0];
(*B)(matPlace2+3,matPlace1+5) += -Btemp1[4][2];
(*B)(matPlace2+5,matPlace1+3) += -Btemp1[4][2];
(*B)(matPlace2+2,matPlace1+6) += Btemp1[4][2];
(*B)(matPlace2+6,matPlace1+2) += Btemp1[4][2];
(*B)(matPlace2+1,matPlace1+2) += -Btemp1[1][0];
(*B)(matPlace2+2,matPlace1+1) += -Btemp1[1][0];
(*B)(matPlace2+1,matPlace1+3) += -Btemp1[2][0];
(*B)(matPlace2+3,matPlace1+1) += -Btemp1[2][0];
(*B)(matPlace2+2,matPlace1+3) += -Btemp1[2][1];
(*B)(matPlace2+3,matPlace1+2) += -Btemp1[2][1];
(*B)(matPlace2+1,matPlace1+1) += -Btemp1[0][0];
(*B)(matPlace2+2,matPlace1+2) += -Btemp1[1][1];
(*B)(matPlace2+3,matPlace1+3) += -Btemp1[2][2];
}
} // of pragma omp critical
return sqrt( sum / (double) n );
}
/**
* This function is used to match a set of laser scans with any minimally
* connected Graph, using the globally consistent LUM-algorithm in 3D.
*
* @param gr Some Graph with no real subgraphs except for itself
* @param allScans Contains all laser scans
* @param nrIt The number of iterations the LUM-algorithm will run
* @return Euclidian distance of all pose shifts
*/
double ghelix6DQ2::doGraphSlam6D(Graph gr, vector <Scan *> allScans, int nrIt)
{
#ifdef WRITE_GRAPH_NET
// for debug only:
static int d = 0;
cout << "writing graph.dat ....................................." << endl;
d++;
string gfilename = "graph_" + to_string(d, 3) + ".net";
ofstream out(gfilename.c_str());
for (int i=0; i < gr.getNrLinks(); i++) {
int from = gr.getLink(i,0);
int to = gr.getLink(i,1);
// shouldn't be necessary, just in case a (out of date) graph file is loaded:
if (from < (int)allScans.size() && to < (int)allScans.size()) {
out << allScans[from]->get_rPos()[0] << " "
<< allScans[from]->get_rPos()[1] << " "
<< allScans[from]->get_rPos()[2] << endl
<< allScans[to ]->get_rPos()[0] << " "
<< allScans[to ]->get_rPos()[1] << " "
<< allScans[to ]->get_rPos()[2] << endl << endl;
}
}
out.close();
out.clear();
#endif
// the IdentityMatrix to transform some Scans with
double id[16];
M4identity(id);
vPtPair **ptpairs = 0; // Contains sets of point pairs for all links
Matrix B ( 6 * (gr.getNrScans()-1), 6 * (gr.getNrScans()-1) );
ColumnVector ccs( 6*(gr.getNrScans()-1) ), bd( 6*(gr.getNrScans()-1) );
B = 0.0;
bd = 0.0;
double sum_position_diff = 0;
double ret = DBL_MAX;
for(int iteration = 0;
iteration < nrIt && ret > epsilonLUM;
iteration++) {
sum_position_diff = 0;
if (nrIt > 1) cout << "Iteration match " << iteration << endl;
if (ptpairs != 0) delete [] ptpairs;
ptpairs = new vPtPair*[gr.getNrLinks()];
for (int i = 0; i < gr.getNrLinks(); i++) {
ptpairs[i] = new vPtPair;
}
// Get all point pairs after ICP
int end_loop = gr.getNrLinks();
#ifdef _OPENMP
omp_set_num_threads(OPENMP_NUM_THREADS);
#pragma omp parallel for schedule(dynamic)
#endif
for ( int i = 0; i < end_loop; i++) {
cout << "P" << i << flush;
Scan * FirstScan = allScans[gr.getLink(i,0)];
Scan * SecondScan = allScans[gr.getLink(i,1)];
#ifdef _OPENMP
int thread_num = omp_get_thread_num();
#else
int thread_num = 0;
#endif
double dummy_centroid_m[3];
double dummy_centroid_d[3];
double dummy_sum;
Scan::getPtPairs(ptpairs[i], FirstScan, SecondScan, thread_num,
(int)my_icp->get_rnd(), (int)max_dist_match2_LUM, dummy_sum,
dummy_centroid_m, dummy_centroid_d);
// faulty network
if (ptpairs[i]->size() <= 1) {
cout << "Error: Link (" << gr.getLink(i,0)
<< " - " << gr.getLink(i, 1) << " ) is empty with "
<< ptpairs[i]->size() << " Corr. points. iteration = "
<< iteration << endl;
// exit(1);
} else
// build the matrix B and vector bd
genBBdForLinkedPair( gr.getLink(i,0), gr.getLink(i,1), ptpairs[i], &B, &bd );
}
cout <<" building matrices done! "<<endl;
ccs = solveSparseCholesky(B, bd);
// delete ptPairs
for (int i = 0; i < gr.getNrLinks(); i++) {
ptpairs[i]->clear();
delete (ptpairs[i]);
}
ColumnVector t0(3), t(3), tlast(3);
int vectorOffset;
int loop_end = gr.getNrScans();
double alignxfLum[16];
for(int i = 1; i < loop_end; i++)
{
vectorOffset = (i-1) * 6;
icp6D_HELIX::computeRt( &ccs, vectorOffset, alignxfLum);
// Update the Pose
cout << "Old pose estimate, Scan " << i << endl;
cout << "x: " << allScans[i]->get_rPos()[0]
<< " y: " << allScans[i]->get_rPos()[1]
<< " z: " << allScans[i]->get_rPos()[2]
<< " tx: " << allScans[i]->get_rPosTheta()[0]
<< " ty: " << allScans[i]->get_rPosTheta()[1]
<< " tz: " << allScans[i]->get_rPosTheta()[2]
<< endl;
if (i < loop_end - 1) {
allScans[i]->transform(alignxfLum, Scan::LUM, 1);
} else {
allScans[i]->transform(alignxfLum, Scan::LUM, 2);
}
cout << "x: " << allScans[i]->get_rPos()[0]
<< " y: " << allScans[i]->get_rPos()[1]
<< " z: " << allScans[i]->get_rPos()[2]
<< " tx: " << allScans[i]->get_rPosTheta()[0]
<< " ty: " << allScans[i]->get_rPosTheta()[1]
<< " tz: " << allScans[i]->get_rPosTheta()[2] << endl << endl;
sum_position_diff += sqrt( sqr(alignxfLum[12]) + sqr(alignxfLum[13]) + sqr(alignxfLum[14]));
}
cout << "Sum of Position differences = " << sum_position_diff << endl << endl;
ret = (sum_position_diff / (double)gr.getNrScans());
}
delete [] ptpairs;
ptpairs = 0;
return ret;
}

@ -0,0 +1,45 @@
Read 500 data points - begin fit
-2247.993783 25945.58733
-537.4533239
-554.5885614
-537.2164816 26.36266449
-520.7034774
-519.7069034 6.153112127
-516.7045383
-516.690955 1.394658892
-516.396412
-516.215149 0.1555724069
-516.1509657
-516.1486772 0.02342168856
-516.1420803
-516.1404735 0.002342030975
-516.1395282
-516.1394913 0.0003287516503
-516.1393961
-516.1393755 3.25631984e-05
Converged
estimates and standard errors
1.56690 0.22311
0.80046 0.20274
0.45307 0.08428
0.34655 0.09081
correlation matrix
1.00 0.00 -0.02 0.01
0.00 1.00 0.21 -0.81
-0.02 0.21 1.00 -0.63
0.01 -0.81 -0.63 1.00
inverse of correlation matrix
1.00 0.03 0.04 0.04
0.03 4.77 2.28 5.28
0.04 2.28 2.73 3.55
0.04 5.28 3.55 7.48

@ -0,0 +1,32 @@
/** @file
* @brief Definition of the ICP error function minimization
* @author Andreas Nuechter. Jacobs University Bremen gGmbH, Germany
*/
#ifndef __ICP6DLUMEULER_H__
#define __ICP6DLUMEULER_H__
#include "icp6Dminimizer.h"
/**
* @brief Implementation of the ICP error function minimization via singular value decomposition
*/
class icp6D_LUMEULER : public icp6Dminimizer
{
public:
/**
* Constructor
*/
icp6D_LUMEULER(bool quiet = false) : icp6Dminimizer(quiet) {};
/**
* Destructor
*/
virtual ~icp6D_LUMEULER() {};
double Point_Point_Align(const vector<PtPair>& Pairs, double *alignxf,
const double centroid_m[3], const double centroid_d[3]);
inline int getAlgorithmID() { return 3; };
};
#endif

@ -0,0 +1,36 @@
/**
* @file
* @brief IO of 3D scans in Riegl file format
* @author Kai Lingemann. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Andreas Nuechter. Institute of Computer Science, University of Osnabrueck, Germany.
*/
#ifndef __SCAN_IO_RIEGL_H__
#define __SCAN_IO_RIEGL_H__
#include <string>
using std::string;
#include <vector>
using std::vector;
#include "scan_io.h"
/**
* @brief 3D scan loader for Riegl scans
*
* The compiled class is available as shared object file
*/
class ScanIO_riegl_bin : public ScanIO {
public:
virtual int readScans(int start, int end, string &dir, int maxDist, int mindist,
double *euler, vector<Point> &ptss);
};
// Since this shared object file is loaded on the fly, we
// need class factories
// the types of the class factories
typedef ScanIO* create_sio();
typedef void destroy_sio(ScanIO*);
#endif

@ -0,0 +1,229 @@
/***********************************************************************
quaternion.cpp
A quaternion class
-------------------------------------------------------------------
Feb 1998, Paul Rademacher (rademach@cs.unc.edu)
************************************************************************/
#include "quaternion.h"
#include <math.h>
#include "stdinc.h"
/******************************************* constructors **************/
quat::quat( void )
{
*this = quat_identity();
}
quat::quat(const float x, const float y, const float z, const float w)
{
v.set( x, y, z );
s = w;
}
quat::quat( vec3 _v, float _s )
{
set( _v, _s );
}
quat::quat( float _s, vec3 _v )
{
set( _v, _s );
}
quat::quat( const float *d )
{
v[0] = d[0];
v[1] = d[1];
v[2] = d[2];
s = d[3];
}
quat::quat( const double *d )
{
v[0] = d[0];
v[1] = d[1];
v[2] = d[2];
s = d[3];
}
quat::quat( const quat &q )
{
v = q.v;
s = q.s;
}
void quat::set( vec3 _v, float _s )
{
v = _v;
s = _s;
}
quat& quat::operator = (const quat& q)
{
v = q.v; s = q.s; return *this;
}
/* ... */
/******** quat friends ************/
quat operator + (const quat &a, const quat &b)
{
return quat( a.s+b.s, a.v+b.v );
}
quat operator - (const quat &a, const quat &b)
{
return quat( a.s-b.s, a.v-b.v );
}
quat operator - (const quat &a )
{
return quat( -a.s, -a.v );
}
quat operator * ( const quat &a, const quat &b)
{
return quat( a.s*b.s - a.v*b.v, a.s*b.v + b.s*a.v + ((a.v)^(b.v)) );
}
quat operator * ( const quat &a, const float t)
{
return quat( a.v * t, a.s * t );
}
quat operator * ( const float t, const quat &a )
{
return quat( a.v * t, a.s * t );
}
mat4 quat::to_mat4( void )
{
float t, xs, ys, zs, wx, wy, wz, xx, xy, xz, yy, yz, zz;
t = 2.0 / (v*v + s*s);
xs = v[VX]*t; ys = v[VY]*t; zs = v[VZ]*t;
wx = s*xs; wy = s*ys; wz = s*zs;
xx = v[VX]*xs; xy = v[VX]*ys; xz = v[VX]*zs;
yy = v[VY]*ys; yz = v[VY]*zs; zz = v[VZ]*zs;
mat4 matrix( 1.0-(yy+zz), xy+wz, xz-wy, 0.0,
xy-wz, 1.0-(xx+zz), yz+wx, 0.0,
xz+wy, yz-wx, 1.0-(xx+yy), 0.0,
0.0, 0.0, 0.0, 1.0 );
return matrix;
}
/************************************************* quat_identity() *****/
/* Returns quaternion identity element */
quat quat_identity( void )
{
return quat( vec3( 0.0, 0.0, 0.0 ), 1.0 );
}
/************************************************ quat_slerp() ********/
/* Quaternion spherical interpolation */
quat quat_slerp( quat from, quat to, float t )
{
quat to1;
double omega, cosom, sinom, scale0, scale1;
/* calculate cosine */
cosom = from.v * to.v + from.s + to.s;
/* Adjust signs (if necessary) */
if ( cosom < 0.0 ) {
cosom = -cosom;
to1 = -to;
}
else
{
to1 = to;
}
/* Calculate coefficients */
if ((1.0 - cosom) > FUDGE ) {
/* standard case (slerp) */
omega = acos( cosom );
sinom = sin( omega );
scale0 = sin((1.0 - t) * omega) / sinom;
scale1 = sin(t * omega) / sinom;
}
else {
/* 'from' and 'to' are very close - just do linear interpolation */
scale0 = 1.0 - t;
scale1 = t;
}
return scale0 * from + scale1 * to1;
}
/********************************************** set_angle() ************/
/* set rot angle (degrees) */
void quat::set_angle( float f )
{
vec3 axis = get_axis();
s = cos( DEG2RAD( f ) / 2.0 );
v = axis * sin(DEG2RAD(f) / 2.0);
}
/********************************************** scale_angle() ************/
/* scale rot angle (degrees) */
void quat::scale_angle( float f )
{
set_angle( f * get_angle() );
}
/********************************************** get_angle() ************/
/* get rot angle (degrees). Assumes s is between -1 and 1 */
float quat::get_angle( void )
{
return RAD2DEG( 2.0 * acos( s ) );
}
/********************************************* get_axis() **************/
vec3 quat::get_axis( void )
{
float scale;
scale = sin( acos( s ) );
if ( scale < FUDGE AND scale > -FUDGE )
return vec3( 0.0, 0.0, 0.0 );
else
return v / scale;
}
/******************************************* quat::print() ************/
void quat::print( FILE *dest, char *name )
{
fprintf( dest, "%s: v:<%3.2f %3.2f %3.2f> s:%3.2f\n", name,
v[0], v[1], v[2], s );
}

@ -0,0 +1,20 @@
/**
* @file
* @brief
*
* @author Thomas Escher
*/
#ifndef ACCESS_DATA_H
#define ACCESS_DATA_H
/**
* @brief Derivable class to store access informations in.
*
* Obviously a TODO
*/
class AccessData {
};
#endif //ACCESS_DATA_H

@ -0,0 +1,269 @@
/*
* convergence implementation
*
* Copyright (C) Jochen Sprickerhof, Peter Schneider
*
* Released under the GPL version 3.
*
*/
/**
* @file
* @brief Implementation for generating a convergence graph of a scanseries frame
* @author Jochen Sprickerhof. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Peter Schneider. Institute of Computer Science, University of Koblenz, Germany.
*/
#include <stdexcept>
using std::exception;
#include "slam6d/scan.h"
#include "slam6d/convergence.h"
/**
* Storing the base directory
*/
string filepath;
/**
* Explains the usage of this program's command line parameters
* @param prog name of the program
*/
void usage(char* prog)
{
#ifndef _MSC_VER
const string bold("\033[1m");
const string normal("\033[m");
#else
const string bold("");
const string normal("");
#endif
cout << endl
<< "Usage: " << prog << " [-s NR] filepath, [-z NR] convergence type" << endl << endl;
cout << " -s NR generate convergence-data for frame NR" << endl
<< endl;
cout << " -z NR type of convergence (0 = global, 1 = local)" << endl
<< endl;
exit(1);
}
/**
* A function that parses the command-line arguments and sets the respective flags.
*
* @param argc the number of arguments
* @param argv the arguments
* @param dir parsing result - the directory
* @param start parsing result - starting at scan number 'start'
* @param type parsing result - the type of convergence that should be stored (lokal, global)
* @return 0, if the parsing was successful, 1 otherwise
*/
int parseArgs(int argc,char **argv, string &dir, int &frame, int &type)
{
frame = 0;
type = 0;
int c;
// from unistd.h
extern char *optarg;
extern int optind;
cout << endl;
while ((c = getopt (argc, argv, "s:z:m:M:p:wt")) != -1)
switch (c)
{
case 's':
frame = atoi(optarg);
if (frame < 0) { cerr << "Error: Cannot generate data of a negative frame number.\n"; exit(1); }
break;
case 'z':
type = atoi(optarg);
if (type > 2 || type < 0) { cerr << "Error: only global (0) or local (1) available.\n"; exit(1); }
break;
case '?':
usage(argv[0]);
return 1;
default:
abort ();
}
if (optind != argc-1) {
cerr << "\n*** Directory missing ***" << endl;
usage(argv[0]);
}
dir = argv[optind];
#ifndef _MSC_VER
if (dir[dir.length()-1] != '/') dir = dir + "/";
#else
if (dir[dir.length()-1] != '\\') dir = dir + "\\";
#endif
return 0;
}
void getLocalConvergence(ifstream *inputFile, ofstream *outputFile)
{
double transMat[16];
int type;
double rPos[3];
double rPosTheta[3];
cout<<"starting local convergence"<<endl;
while ((*inputFile).good()) {
try {
(*inputFile) >> transMat >> type;
if(type == Scan::ICP)
{
Matrix4ToEuler(transMat, rPosTheta, rPos);
(*outputFile)<<rPos[0]<<" "<<rPos[1]<<" "<<rPos[2]<<endl;
}
}
catch (const exception &e) {
break;
}
}
}
void getAllConvergence(ifstream *inputFile, ofstream *outputFile, int FrameNr)
{
double transMat[16];
int type;
double rPosOrg[3], rPosThetaOrg[3];
double quatOrg[4];
//108
//double truth[16] = {-0.125888, 0.0122898, -0.991968, 0, 0.00384827, 0.999922, 0.0118999, 0, 0.992037, -0.00231931, -0.125925, 0, -1702.16, 34.255, 285.929, 1};
//344
//double truth[16] = {-0.548304, -0.00375733, 0.83627, 0, 0.0294523, 0.999283, 0.0238003, 0, -0.83576, 0.0376799, -0.5478, 0, 691.717, 55.8939, 216.401, 1};
//556
double truth[16] = {0.996696, 0.0336843, -0.073908, 0, -0.0325397, 0.999332, 0.016638, 0, 0.0744191, -0.0141781, 0.997126, 0, 6211.62, 364.291, -3468.65, 1};
//708
//double truth[16] = {0.000564156, -0.0283691, -0.999597, 0, 0.00348951, 0.999591, -0.0283669, 0, 0.999994, -0.0034721, 0.00066292, 0, 7591.08, -31.354, 6938.24, 1};
Matrix4ToEuler(truth, rPosThetaOrg, rPosOrg);
Matrix4ToQuat(truth, quatOrg);
double quat[4];
double rPos[3];
double rPosTheta[3];
bool initial = true;
cout<<"starting all convergence"<<endl;
while ((*inputFile).good()) {
try {
(*inputFile) >> transMat >> type;
Matrix4ToEuler(transMat, rPosTheta, rPos);
Matrix4ToQuat(transMat, quat);
if((initial || type != Scan::INVALID) && type != Scan::ICPINACTIVE) {
initial = false;
(*outputFile) << sqrt(Dist2(rPosOrg, rPos))/100.0 << " " << quat_dist(quatOrg, quat) << " " << type << endl;
}
//(*outputFile) << sqrt(Dist2(rPosOrg, rPos))/100.0 << " " << quat_dist(quatOrg, quat) << " " << type << endl;
}
catch (const exception &e) {
break;
}
}
}
void getGlobalConvergence(ifstream *inputFile, ofstream *outputFile)
{
double transMat[16];
int type;
bool lumYetFound = false;
double rPos[3];
double rPosTheta[3];
cout<<"starting global convergence"<<endl;
while ((*inputFile).good()) {
try {
(*inputFile) >> transMat >> type;
if(type == Scan::LUM)
{
lumYetFound = true;
Matrix4ToEuler(transMat, rPosTheta, rPos);
(*outputFile)<<rPos[0]<<" "<<rPos[1]<<" "<<rPos[2]<<endl;
} else
{
if(lumYetFound) //we only want to write the last lum-correction into the file
{
lumYetFound = false;
outputFile->close();
outputFile->open("xyz.con", ios::trunc);
}
}
}
catch (const exception &e) {
break;
}
}
}
/*
* A function that read the .frame files created by slam6D
*
* @param dir the directory
* @param frameNr frame number that should be read
*/
void readFrames(string dir, int frameNr, int convType)
{
ifstream frame_in;
ofstream xyz_out;
xyz_out.open("xyz.con");
string frameFileName;
frameFileName = dir + "scan" + to_string(frameNr,3) + ".frames";
cout << "Reading Frame for convergence data " << frameFileName << "..."<<endl;
frame_in.open(frameFileName.c_str());
// read frame
if (!frame_in.good()) cout<<"could not open file!"<<endl; // no more files in the directory
else
{
if(convType == CONV_LOCAL)
{
getLocalConvergence(&frame_in, &xyz_out);
} else if (convType == CONV_GLOBAL)
{
getGlobalConvergence(&frame_in, &xyz_out);
} else if (convType == CONV_ALL)
{
getAllConvergence(&frame_in, &xyz_out, frameNr);
}
frame_in.close();
frame_in.clear();
}
xyz_out.close();
}
//-----------------------------------------------------------------------------------
/**
* Main function.
* Reads a frames file (scan000.frames, ...) from the data directory.
* The frame is used for generating the convergencedata of a scan.
*/
int main(int argc, char **argv){
cout << "(c) University of Osnabrueck, 2008" << endl << endl
<< "Restricted Usage" << endl
<< "Don't use without permission" << endl;
if(argc <= 1){
usage(argv[0]);
}
int convT;
int frameNumber = 0;
string dir;
parseArgs(argc, argv, dir, frameNumber, convT);
// scandir = dir;
// Get frame-data
readFrames(dir, frameNumber, convT);
}

@ -0,0 +1,152 @@
/*
* graphToro implementation
*
* Copyright (C) Jochen Sprickerhof
*
* Released under the GPL version 3.
*
*/
/**
* @file TORO wrapper
* @author Jochen Sprickerhof. Institute of Computer Science, University of Osnabrueck, Germany.
*/
#include "slam6d/graphToro.h"
#include "slam6d/metaScan.h"
#include "slam6d/lum6Deuler.h"
#include "slam6d/globals.icc"
#include <fstream>
using std::ofstream;
using std::ifstream;
#include <cfloat>
#include <cstring>
using namespace NEWMAT;
/**
* This function is used to match a set of laser scans with any minimally
* connected Graph.
*
* @param gr Some Graph with no real subgraphs except for itself
* @param allScans Contains all laser scans
* @param nrIt The number of iterations the LUM-algorithm will run
* @return Euclidian distance of all pose shifts
*/
double graphToro::doGraphSlam6D(Graph gr, vector <Scan *> allScans, int nrIt)
{
Matrix C(6, 6);
double invers[16], rela[16], rPos[3], rPosTheta[3], rPosQuat[4];
double Pl0[16];
ofstream outFile("toro.graph");
int n = gr.getNrScans();
for(int i = 0; i < n; i++) {
QuatRPYEuler(allScans[i]->get_rPosQuat(), rPosTheta);
outFile << "VERTEX3" << " " << i <<
" " << (allScans[i]->get_rPos()[0]/100) <<
" " << (allScans[i]->get_rPos()[1]/100) <<
" " << (allScans[i]->get_rPos()[2]/100) <<
" " << rPosTheta[0] <<
" " << rPosTheta[1] <<
" " << rPosTheta[2] << endl;
}
for(int i = 0; i < gr.getNrLinks(); i++){
int first = gr.getLink(i,0);
int last = gr.getLink(i,1);
if(first != last-1) {
vector <Scan *> meta_start;
for(int i = first - 2; i <= first + 2; i++) {
if(i >= 0) {
meta_start.push_back(allScans[i]);
}
}
MetaScan *start = new MetaScan(meta_start, false, false);
//static size of metascan
int offset_last_start = 2;
int offset_last_end = 0;
vector <Scan *> meta_end;
for(int i = last - offset_last_start; i <= last + offset_last_end && i < n; i++) {
if(i >= 0) {
meta_end.push_back(allScans[i]);
}
}
MetaScan *end = new MetaScan(meta_end, false, false);
memcpy(Pl0, allScans[last]->get_transMat(), 16 * sizeof(double));
my_icp->match(start, end);
delete start;
delete end;
}
M4inv(allScans[last]->get_transMat(), invers);
MMult(invers, allScans[first]->get_transMat(), rela);
Matrix4ToQuat(rela, rPosQuat, rPos);
QuatRPYEuler(rPosQuat, rPosTheta);
lum6DEuler::covarianceEuler(allScans[first], allScans[last], my_icp->get_nns_method(), my_icp->get_rnd(), my_icp->get_max_dist_match2(), &C);
outFile << "EDGE3" << " " << last << " " << first << " " <<
(rPos[0]/100) << " " <<
(rPos[1]/100) << " " <<
(rPos[2]/100) << " " <<
rPosTheta[0] << " " <<
rPosTheta[1] << " " <<
rPosTheta[2] << " ";
for(int i = 1; i < 7; i++)
for(int j = i; j < 7; j++)
outFile << C(i, j) << " ";
outFile << endl;
if(first != last-1) {
allScans[last]->transformToMatrix(Pl0,Scan::INVALID);
}
}
outFile.close();
system("sort toro.graph > toro2.graph && mv toro2.graph toro.graph && ./bin/toro3d toro.graph");
ifstream inFile("toro-treeopt-final.graph");
string tag;
int id;
double dd;
double rPosN[3], rPosThetaN[3];
while(inFile) {
inFile >> tag;
if(tag == "VERTEX3") {
inFile >> id;
if(id == n-1) {
inFile >> rPosN[0] >> rPosN[1] >> rPosN[2] >> rPosThetaN[0] >> rPosThetaN[1] >> rPosThetaN[2];
rPosN[0] *= 100;
rPosN[1] *= 100;
rPosN[2] *= 100;
} else {
inFile >> rPos[0] >> rPos[1] >> rPos[2] >> rPosTheta[0] >> rPosTheta[1] >> rPosTheta[2];
rPos[0] *= 100;
rPos[1] *= 100;
rPos[2] *= 100;
RPYEulerQuat(rPosTheta, rPosQuat);
if(id != 0) {
allScans[id]->transformToQuat(rPos, rPosQuat, Scan::GRAPHTORO, 1);
}
}
}
else if(tag == "EDGE3") {
inFile >> id >> id;
for(int i=0; i < 22; i++) {
inFile >> dd;
}
}
}
RPYEulerQuat(rPosThetaN, rPosQuat);
allScans[n-1]->transformToQuat(rPosN, rPosQuat, Scan::GRAPHTORO, 2);
inFile.close();
return DBL_MAX;
}

@ -0,0 +1,22 @@
inline char *ConfigFileHough::Get_CfgFileName(){return CfgFileName;}
inline double ConfigFileHough::Get_MaxDist(){return MaxDist;}
inline double ConfigFileHough::Get_MinDist(){return MinDist;}
inline unsigned int ConfigFileHough::Get_AccumulatorMax(){return AccumulatorMax;}
inline unsigned int ConfigFileHough::Get_MinSizeAllPoints(){return MinSizeAllPoints;}
inline unsigned int ConfigFileHough::Get_RhoNum(){return RhoNum;}
inline unsigned int ConfigFileHough::Get_ThetaNum(){return ThetaNum;}
inline unsigned int ConfigFileHough::Get_PhiNum(){return PhiNum;}
inline unsigned int ConfigFileHough::Get_RhoMax(){return RhoMax;}
inline double ConfigFileHough::Get_MaxPointPlaneDist(){return MaxPointPlaneDist;}
inline unsigned int ConfigFileHough::Get_MaxPlanes(){return MaxPlanes;}
inline unsigned int ConfigFileHough::Get_MinPlaneSize(){return MinPlaneSize;}
inline double ConfigFileHough::Get_MinPlanarity(){return MinPlanarity;}
inline double ConfigFileHough::Get_PlaneRatio(){return PlaneRatio;}
inline double ConfigFileHough::Get_PointDist(){return PointDist;}
inline bool ConfigFileHough::Get_PeakWindow(){return PeakWindow;}
inline unsigned int ConfigFileHough::Get_WindowSize(){return WindowSize;}
inline unsigned int ConfigFileHough::Get_TrashMax(){return TrashMax;}
inline unsigned int ConfigFileHough::Get_AccumulatorType(){return AccumulatorType;}
inline char* ConfigFileHough::Get_PlaneDir(){return PlaneDir;}

@ -0,0 +1,19 @@
Code for PMD camera.
pmdaccess2/* PMD-camera access lib
cvpmd & pmdWrap libpmdaccess2 wrapper, PMD -> OpenCV marshalling and a bit of math.
calibrate/* PMD calibration tool
pose/* 3D Tracking, pose estimation
offline/* Grab data for offline processing
*xml cameras matrices
Depends on OpenCV (2.0), GLFW, FTGL, libconfig, xmlrpc-c
installing opencv on ubuntu: http://ivkin.net/2009/11/installing-opencv-2-0-on-ubuntu-9-10-karmic-koala/
to compile just run:
$ make
Ubuntu issues:
# fix GLFW /usr/lib/libglfw.so symlink
# obtain libconfig somewhere (i.e. from debian repos or install from source)

@ -0,0 +1,200 @@
//$$ solution.cpp // solve routines
// Copyright (C) 1994: R B Davies
#define WANT_STREAM // include.h will get stream fns
#define WANT_MATH // include.h will get math fns
#include "include.h"
#include "boolean.h"
#include "myexcept.h"
#include "solution.h"
#ifdef use_namespace
namespace RBD_COMMON {
#endif
void R1_R1::Set(Real X)
{
if ((!minXinf && X <= minX) || (!maxXinf && X >= maxX))
Throw(SolutionException("X value out of range"));
x = X; xSet = true;
}
R1_R1::operator Real()
{
if (!xSet) Throw(SolutionException("Value of X not set"));
Real y = operator()();
return y;
}
unsigned long SolutionException::Select;
SolutionException::SolutionException(const char* a_what) : BaseException()
{
Select = BaseException::Select;
AddMessage("Error detected by solution package\n");
AddMessage(a_what); AddMessage("\n");
if (a_what) Tracer::AddTrace();
};
inline Real square(Real x) { return x*x; }
void OneDimSolve::LookAt(int V)
{
lim--;
if (!lim) Throw(SolutionException("Does not converge"));
Last = V;
Real yy = function(x[V]) - YY;
Finish = (fabs(yy) <= accY) || (Captured && fabs(x[L]-x[U]) <= accX );
y[V] = vpol*yy;
}
void OneDimSolve::HFlip() { hpol=-hpol; State(U,C,L); }
void OneDimSolve::VFlip()
{ vpol = -vpol; y[0] = -y[0]; y[1] = -y[1]; y[2] = -y[2]; }
void OneDimSolve::Flip()
{
hpol=-hpol; vpol=-vpol; State(U,C,L);
y[0] = -y[0]; y[1] = -y[1]; y[2] = -y[2];
}
void OneDimSolve::State(int I, int J, int K) { L=I; C=J; U=K; }
void OneDimSolve::Linear(int I, int J, int K)
{
x[J] = (x[I]*y[K] - x[K]*y[I])/(y[K] - y[I]);
// cout << "Linear\n";
}
void OneDimSolve::Quadratic(int I, int J, int K)
{
// result to overwrite I
Real YJK, YIK, YIJ, XKI, XKJ;
YJK = y[J] - y[K]; YIK = y[I] - y[K]; YIJ = y[I] - y[J];
XKI = (x[K] - x[I]);
XKJ = (x[K]*y[J] - x[J]*y[K])/YJK;
if ( square(YJK/YIK)>(x[K] - x[J])/XKI ||
square(YIJ/YIK)>(x[J] - x[I])/XKI )
{
x[I] = XKJ;
// cout << "Quadratic - exceptional\n";
}
else
{
XKI = (x[K]*y[I] - x[I]*y[K])/YIK;
x[I] = (XKJ*y[I] - XKI*y[J])/YIJ;
// cout << "Quadratic - normal\n";
}
}
Real OneDimSolve::Solve(Real Y, Real X, Real Dev, int Lim)
{
enum Loop { start, captured1, captured2, binary, finish };
Tracer et("OneDimSolve::Solve");
lim=Lim; Captured = false;
if (Dev==0.0) Throw(SolutionException("Dev is zero"));
L=0; C=1; U=2; vpol=1; hpol=1; y[C]=0.0; y[U]=0.0;
if (Dev<0.0) { hpol=-1; Dev = -Dev; }
YY=Y; // target value
x[L] = X; // initial trial value
if (!function.IsValid(X))
Throw(SolutionException("Starting value is invalid"));
Loop TheLoop = start;
for (;;)
{
switch (TheLoop)
{
case start:
LookAt(L); if (Finish) { TheLoop = finish; break; }
if (y[L]>0.0) VFlip(); // so Y[L] < 0
x[U] = X + Dev * hpol;
if (!function.maxXinf && x[U] > function.maxX)
x[U] = (function.maxX + X) / 2.0;
if (!function.minXinf && x[U] < function.minX)
x[U] = (function.minX + X) / 2.0;
LookAt(U); if (Finish) { TheLoop = finish; break; }
if (y[U] > 0.0) { TheLoop = captured1; Captured = true; break; }
if (y[U] == y[L])
Throw(SolutionException("Function is flat"));
if (y[U] < y[L]) HFlip(); // Change direction
State(L,U,C);
for (i=0; i<20; i++)
{
// cout << "Searching for crossing point\n";
// Have L C then crossing point, Y[L]<Y[C]<0
x[U] = x[C] + Dev * hpol;
if (!function.maxXinf && x[U] > function.maxX)
x[U] = (function.maxX + x[C]) / 2.0;
if (!function.minXinf && x[U] < function.minX)
x[U] = (function.minX + x[C]) / 2.0;
LookAt(U); if (Finish) { TheLoop = finish; break; }
if (y[U] > 0) { TheLoop = captured2; Captured = true; break; }
if (y[U] < y[C])
Throw(SolutionException("Function is not monotone"));
Dev *= 2.0;
State(C,U,L);
}
if (TheLoop != start ) break;
Throw(SolutionException("Cannot locate a crossing point"));
case captured1:
// cout << "Captured - 1\n";
// We have 2 points L and U with crossing between them
Linear(L,C,U); // linear interpolation
// - result to C
LookAt(C); if (Finish) { TheLoop = finish; break; }
if (y[C] > 0.0) Flip(); // Want y[C] < 0
if (y[C] < 0.5*y[L]) { State(C,L,U); TheLoop = binary; break; }
case captured2:
// cout << "Captured - 2\n";
// We have L,C before crossing, U after crossing
Quadratic(L,C,U); // quad interpolation
// - result to L
State(C,L,U);
if ((x[C] - x[L])*hpol <= 0.0 || (x[C] - x[U])*hpol >= 0.0)
{ TheLoop = captured1; break; }
LookAt(C); if (Finish) { TheLoop = finish; break; }
// cout << "Through first stage\n";
if (y[C] > 0.0) Flip();
if (y[C] > 0.5*y[L]) { TheLoop = captured2; break; }
else { State(C,L,U); TheLoop = captured1; break; }
case binary:
// We have L, U around crossing - do binary search
// cout << "Binary\n";
for (i=3; i; i--)
{
x[C] = 0.5*(x[L]+x[U]);
LookAt(C); if (Finish) { TheLoop = finish; break; }
if (y[C]>0.0) State(L,U,C); else State(C,L,U);
}
if (TheLoop != binary) break;
TheLoop = captured1; break;
case finish:
return x[Last];
}
}
}
bool R1_R1::IsValid(Real X)
{
Set(X);
return (minXinf || x > minX) && (maxXinf || x < maxX);
}
#ifdef use_namespace
}
#endif

@ -0,0 +1,141 @@
/**
* @file
* @brief Implementation of reading 3D scans
* @author Kai Lingemann. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Andreas Nuechter. Institute of Computer Science, University of Osnabrueck, Germany.
*/
#include "slam6d/scan_io_uos_rgb.h"
#include "slam6d/globals.icc"
#include <fstream>
using std::ifstream;
#include <iostream>
using std::cout;
using std::cerr;
using std::endl;
#ifdef _MSC_VER
#include <windows.h>
#endif
/**
* Reads specified scans from given directory.
*
* Scan poses will NOT be initialized after a call
* to this function.
*
* This function actually implements loading of 3D scans
* in UOS file format including color information and will be compiled as
* shared lib.
*
* @param start Starts to read with this scan
* @param end Stops with this scan
* @param dir The directory from which to read
* @param maxDist Reads only Points up to this Distance
* @param minDist Reads only Points from this Distance
* @param euler Initital pose estimates (will not be applied to the points
* @param ptss Vector containing the read points
*/
int ScanIO_uos_rgb::readScans(int start, int end, string &dir, int maxDist, int minDist,
double *euler, vector<Point> &ptss)
{
static int fileCounter = start;
string scanFileName;
string poseFileName;
ifstream scan_in, pose_in;
double maxDist2 = sqr(maxDist);
double minDist2 = sqr(minDist);
int my_fileNr = fileCounter;
if (end > -1 && fileCounter > end) return -1; // 'nuf read
scanFileName = dir + "scan" + to_string(fileCounter,3) + ".3d";
poseFileName = dir + "scan" + to_string(fileCounter,3) + ".pose";
scan_in.open(scanFileName.c_str());
pose_in.open(poseFileName.c_str());
// read 3D scan
if (!pose_in.good() && !scan_in.good()) return -1; // no more files in the directory
if (!pose_in.good()) { cerr << "ERROR: Missing file " << poseFileName << endl; exit(1); }
if (!scan_in.good()) { cerr << "ERROR: Missing file " << scanFileName << endl; exit(1); }
cout << "Processing Scan " << scanFileName;
for (unsigned int i = 0; i < 6; pose_in >> euler[i++]);
cout << " @ pose (" << euler[0] << "," << euler[1] << "," << euler[2]
<< "," << euler[3] << "," << euler[4] << "," << euler[5] << ")" << endl;
// convert angles from deg to rad
for (unsigned int i = 3; i <= 5; i++) euler[i] = rad(euler[i]);
// overread the first line
char dummy[255];
scan_in.getline(dummy, 255);
int r, g, b;
while (scan_in.good()) {
Point p;
try {
scan_in >> p;
scan_in >> r >> g >> b;
p.rgb[0] = (char)r;
p.rgb[1] = (char)g;
p.rgb[2] = (char)b;
} catch (...) {
break;
}
// load points up to a certain distance only
// maxDist2 = -1 indicates no limitation
if (maxDist == -1 || sqr(p.x) + sqr(p.y) + sqr(p.z) < maxDist2)
if (minDist == -1 || sqr(p.x) + sqr(p.y) + sqr(p.z) > minDist2)
ptss.push_back(p);
}
scan_in.close();
scan_in.clear();
pose_in.close();
pose_in.clear();
fileCounter++;
return my_fileNr;
}
/**
* class factory for object construction
*
* @return Pointer to new object
*/
#ifdef _MSC_VER
extern "C" __declspec(dllexport) ScanIO* create()
#else
extern "C" ScanIO* create()
#endif
{
return new ScanIO_uos_rgb;
}
/**
* class factory for object construction
*
* @return Pointer to new object
*/
#ifdef _MSC_VER
extern "C" __declspec(dllexport) void destroy(ScanIO *sio)
#else
extern "C" void destroy(ScanIO *sio)
#endif
{
delete sio;
}
#ifdef _MSC_VER
BOOL APIENTRY DllMain(HANDLE hModule, DWORD dwReason, LPVOID lpReserved)
{
return TRUE;
}
#endif

@ -0,0 +1,194 @@
/*
* PMD implementation
*
* Copyright (C) Stanislav Serebryakov
*
* Released under the GPL version 3.
*
*/
#include <cv.h> /* IplImage, cvCreateImage */
#include "pmdsdk2.h"
#include <stdlib.h>
#include <stdio.h>
#include "cvpmd.h"
#include <inttypes.h>
/** TODO
* inten max amplitude
* error handling
*/
PMD *initPMD(const char* plugin, const char *ip) {
PMD *io = (PMD*)malloc(sizeof(PMD));
if(0 != pmdOpen (&io->hnd, plugin, ip, plugin, "")) {
fprintf(stderr, "ERROR: could not connect!\n");
exit(1);
}
//pmdUpdate(io->hnd);
//pmdGetSourceDataDescription(io->hnd, &io->dd);
io->dd.std.numColumns = 64;
io->dd.std.numRows = 50; //FIXME!
io->data = (float*)malloc(io->dd.std.numColumns * io->dd.std.numRows * sizeof(float));
return io;
}
float *pmdDataPtr(PMD *p) {
return p->data;
}
void releasePMD(PMD **pmd) {
pmdClose((*pmd)->hnd);
free((*pmd)->data);
free(*pmd);
*pmd = 0;
}
static float max(const PMD *p) {
float max = 0.0f;
for(unsigned int k = 0; k < p->dd.std.numRows*p->dd.std.numColumns; k++) {
if(p->data[k] > max) max = p->data[k];
}
//printf("max = %f\n", max);
return max;
}
//static inline void setPix(const IplImage *m, const int c, const int r, const char v) { m->imageData[r*m->width + c] = v; }
CvSize pmdGetSize(const PMD *p) {
return cvSize(p->dd.std.numColumns, p->dd.std.numRows);
}
IplImage *toIplImage(const PMD *p, IplImage *img = 0) {
int cols = p->dd.std.numColumns;
int rows = p->dd.std.numRows;
IplImage *imgp;
if(!img) imgp = cvCreateImage(pmdGetSize(p), 8, 1);
else imgp = img;
//FIXME: scaled!
float m = max(p);
for(int r = 0; r < rows; r++) {
for(int c = 0; c < cols; c++) {
//FIXME: mess with the rows and colums
CV_IMAGE_ELEM(imgp, uint8_t, r, c) = (uint8_t) 255.0f * p->data[r*cols + c] / m;
}
}
return imgp;
}
/*CvPoint3D32f unionVec(const CvPoint uv, const CvMat *intrinsic) {
//TODO: not defined yet
// with this function pmdProjectToCartesian would look like:
// pmdProjectToCartesian pt depth mat = depth * unionVec pt mat
return cvPoint3D32f(0,0,0);
}*/
static inline CvPoint3D32f pmdProjectToCartesian(const CvMat *intrinsicMatrix, const CvPoint2D32f uv, const float dist) {
/* Lukas Dierks and Jan Wuelfing's projectToCartesian */
float fx = cvmGet(intrinsicMatrix, 0, 0);
float cx = cvmGet(intrinsicMatrix, 0, 2);
float fy = cvmGet(intrinsicMatrix, 1, 1);
float cy = cvmGet(intrinsicMatrix, 1, 2);
float u = uv.x;
float v = uv.y;
float r = dist;
float u2 = u*u;
float v2 = v*v;
float cx2 = cx*cx;
float cy2 = cy*cy;
float fx2 = fx*fx;
float fy2 = fy*fy;
// Reverse Projection
float squareroot = sqrt(
cy2 * fx2 +
cx2 * fy2 +
fx2 * fy2 -
2 * cx * fy2 * u +
fy2 * u2 -
2 * cy * fx2 * v +
fx2 * v2
);
return cvPoint3D32f((fy * r * (cx - u)) / squareroot,
(fx * r * (cy - v)) / squareroot,
(fx * fy * r) / squareroot);
}
CvPoint3D32f *cvProjectArrayToCartesian( const CvMat *intrinsicMatrix
, const CvPoint2D32f *pts, const int ptsCnt
, CvPoint3D32f *unitVs) {
for(int i = 0; i < ptsCnt; i++)
unitVs[i] = pmdProjectToCartesian(intrinsicMatrix, pts[i], 1.0);
return unitVs;
}
CvPoint3D32f **pmdProjectArrayToCartesian(const PMD *p, const CvMat *intrinsicMatrix, CvPoint3D32f **pts) {
for(unsigned int i = 0; i < p->dd.std.numRows; i++)
for(unsigned int j = 0; j < p->dd.std.numColumns; j++)
pts[i][j] = pmdProjectToCartesian(intrinsicMatrix, cvPoint2D32f(i,j), p->data[j*p->dd.std.numColumns + i]);
return pts;
}
IplImage *pmdQueryImage(PMD *p, IplImage *img = 0) {
pmdGetIntensities(p->hnd, p->data, p->dd.std.numColumns * p->dd.std.numRows * sizeof(float));
return toIplImage(p, img);
}
IplImage *pmdQueryImageAsync(PMD *p, IplImage *img = 0) {
pmdGetIntensitiesAsync(p->hnd, p->data, p->dd.std.numColumns * p->dd.std.numRows * sizeof(float));
return toIplImage(p, img);
}
void pmdRetriveDistances(PMD *p) {
pmdGetDistances(p->hnd, p->data, p->dd.std.numColumns * p->dd.std.numRows * sizeof(float));
return;
}
void pmdRetriveDistancesAsync(PMD *p) {
pmdGetDistancesAsync(p->hnd, p->data, p->dd.std.numColumns * p->dd.std.numRows * sizeof(float));
return;
}
IplImage *pmdQueryDistances(PMD *p, IplImage *img = 0) {
pmdGetDistances(p->hnd, p->data, p->dd.std.numColumns * p->dd.std.numRows * sizeof(float));
return toIplImage(p, img);
}
IplImage *pmdQueryDistancesAsync(PMD *p, IplImage *img = 0) {
pmdGetDistancesAsync(p->hnd, p->data, p->dd.std.numColumns * p->dd.std.numRows * sizeof(float));
return toIplImage(p, img);
}
IplImage *pmdQueryAmplitudes(PMD *p, IplImage *img = 0) {
pmdGetAmplitudesAsync(p->hnd, p->data, p->dd.std.numColumns * p->dd.std.numRows * sizeof(float));
return toIplImage(p, img);
}
IplImage *pmdQueryAmplitudesAsync(PMD *p, IplImage *img = 0) {
pmdGetAmplitudes(p->hnd, p->data, p->dd.std.numColumns * p->dd.std.numRows * sizeof(float));
return toIplImage(p, img);
}

@ -0,0 +1,96 @@
#include <string.h>
#include <stdlib.h>
#include "show/viewcull.h"
#include "show/scancolormanager.h"
//#include "show/colormanager.h"
/*
#include "limits.h"
#include <vector>
using std::vector;
#include <string>
#include <string.h>
using std::string;
#include <stdlib.h>
#include <stdio.h>
#include <glut.h>
#include <GL/glut.h>
#include <glu.h>
*/
#ifndef __DISPLAY_H__
#define __DISPLAY_H__
using namespace std;
class SDisplay {
public:
//inline void setColorManager(ColorManager *_cm) { cm = _cm; }
//virtual SDisplay* readFromFile(string &filename) = 0;
virtual const char *getName() { return "Unnamed display"; }
virtual void display(double detail) { displayAll(); }
virtual void displayAll();
virtual void displayObject() = 0;
static void readDisplays(string &filename, vector<SDisplay*> &displays);
protected:
static double mirror[16];
//ColorManager *cm;
};
class PointDisplay : public SDisplay {
public:
static SDisplay* readFromFile(string &filename);
virtual void displayObject();
private:
PointDisplay(vector<float*> &p, vector<string> &l);
vector<float *> points;
vector<string> labels;
};
class LineDisplay : public SDisplay {
public:
static SDisplay* readFromFile(string &filename);
virtual void displayObject();
private:
LineDisplay(vector<float*> &l);
vector<float *> lines;
};
class PlaneDisplay : public SDisplay {
public:
static SDisplay* readFromFile(string &filename, float* color);
virtual void displayObject();
private:
PlaneDisplay(vector<float*> &p, float* c);
vector<float *> points;
float * color;
};
class GroupPlaneDisplay : public SDisplay {
public:
static SDisplay* readFromFile(string &filename);
virtual void displayObject();
private:
GroupPlaneDisplay(vector<PlaneDisplay*> &p);
vector<PlaneDisplay*> planes;
};
#endif

@ -0,0 +1,76 @@
//$$ newmat9.cpp Input and output
// Copyright (C) 1991,2,3,4: R B Davies
#define WANT_FSTREAM
#include "include.h"
#include "newmat.h"
#include "newmatio.h"
#include "newmatrc.h"
#ifdef use_namespace
namespace NEWMAT {
#endif
#ifdef DO_REPORT
#define REPORT { static ExeCounter ExeCount(__LINE__,9); ++ExeCount; }
#else
#define REPORT {}
#endif
// for G++ 3.01
#ifndef ios_format_flags
#define ios_format_flags long
#endif
ostream& operator<<(ostream& s, const BaseMatrix& X)
{
GeneralMatrix* gm = ((BaseMatrix&)X).Evaluate(); operator<<(s, *gm);
gm->tDelete(); return s;
}
ostream& operator<<(ostream& s, const GeneralMatrix& X)
{
MatrixRow mr((GeneralMatrix*)&X, LoadOnEntry);
int w = s.width(); int nr = X.Nrows(); ios_format_flags f = s.flags();
s.setf(ios::fixed, ios::floatfield);
for (int i=1; i<=nr; i++)
{
int skip = mr.skip; int storage = mr.storage;
Real* store = mr.data; skip *= w+1;
while (skip--) s << " ";
while (storage--) { s.width(w); s << *store++ << " "; }
// while (storage--) s << setw(w) << *store++ << " ";
mr.Next(); s << "\n";
}
s << flush; s.flags(f); return s;
}
// include this stuff if you are using an old version of G++
// with an incomplete io library
/*
ostream& operator<<(ostream& os, Omanip_precision i)
{ os.precision(i.x); return os; }
Omanip_precision setprecision(int i) { return Omanip_precision(i); }
ostream& operator<<(ostream& os, Omanip_width i)
{ os.width(i.x); return os; }
Omanip_width setw(int i) { return Omanip_width(i); }
*/
#ifdef use_namespace
}
#endif

@ -0,0 +1,98 @@
/**
* @file
* @brief Implementation of 3D scan matching with ICP
* @author Kai Lingemann. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Andreas Nuechter. Institute of Computer Science, University of Osnabrueck, Germany.
*/
/**
* Will return the maximal number of randomization
*
* @return the maximal number of iterations
*/
inline int icp6D::get_rnd()
{
return rnd;
}
/**
* Will return weather to use the meta scan
*
* @return the maximal number of iterations
*/
inline bool icp6D::get_meta()
{
return meta;
}
/**
* Will return the anim flag
*
* @return the anim flag
*/
inline int icp6D::get_anim() {
return anim;
}
/**
* Will return the used nearest neigbor search method
*
* @return the nns_method number
*/
inline int icp6D::get_nns_method()
{
return nns_method;
}
/**
* Set the anim flag
*
* @param anim Animate which frames?
*/
inline void icp6D::set_anim(int anim) {
this->anim = anim;
}
/**
* Get the maximal distance for matching
*
* @return the maximal distance for matching
*/
inline double icp6D::get_max_dist_match2() {
return max_dist_match2;
}
/**
* Set the maximal distance for matching
*
* @param max_dist_match2 the maximal distance (^2 !!!) for matching
*/
inline void icp6D::set_max_dist_match2(double max_dist_match2) {
this->max_dist_match2 = max_dist_match2;
}
/**
* Set the Maximum number of iterations
*
* @param max_num_iterations Maximum number of iterations
*/
inline void icp6D::set_max_num_iterations(int max_num_iterations) {
this->max_num_iterations = max_num_iterations;
}
/**
* @brief Enable / Disable CAD matching (i.e. matching only against first scan)
*
* @param cad_matching The new value to determine if CAD matching should
* be done
*/
inline void icp6D::set_cad_matching (bool cad_matching)
{
this->cad_matching = cad_matching;
}
inline bool icp6D::get_cad_matching (void)
{
return this->cad_matching;
}

@ -0,0 +1,4 @@
modified by Deyuan Qiu:
.../include/ANN.h line779
.../src/kd_tree.h line87 line155
.../MAKEFILE line94

@ -0,0 +1,131 @@
//----------------------------------------------------------------------
// File: rand.h
// Programmer: Sunil Arya and David Mount
// Description: Basic include file for random point generators
// Last modified: 08/04/06 (Version 1.1.1)
//----------------------------------------------------------------------
// Copyright (c) 1997-2005 University of Maryland and Sunil Arya and
// David Mount. All Rights Reserved.
//
// This software and related documentation is part of the Approximate
// Nearest Neighbor Library (ANN). This software is provided under
// the provisions of the Lesser GNU Public License (LGPL). See the
// file ../ReadMe.txt for further information.
//
// The University of Maryland (U.M.) and the authors make no
// representations about the suitability or fitness of this software for
// any purpose. It is provided "as is" without express or implied
// warranty.
//----------------------------------------------------------------------
// History:
// Revision 0.1 03/04/98
// Initial release
// Revision 1.0 04/01/05
// Added annClusOrthFlats distribution
// Changed procedure names to avoid namespace conflicts
// Added annClusFlats distribution
// Revision 1.1.1 08/04/06
// Added planted distribution
//----------------------------------------------------------------------
#ifndef rand_H
#define rand_H
//----------------------------------------------------------------------
// Basic includes
//----------------------------------------------------------------------
#include <cstdlib> // standard includes (rand/random)
#include <cmath> // math routines
#include <ANN/ANN.h> // basic ANN includes
//----------------------------------------------------------------------
// Although random/srandom is a more reliable random number generator,
// many systems do not have it. If it is not available, set the
// preprocessor symbol ANN_NO_RANDOM, and this will substitute the use
// of rand/srand for them.
//----------------------------------------------------------------------
#ifdef ANN_NO_RANDOM // for systems not having random()
#define ANN_RAND rand
#define ANN_SRAND srand
#define ANN_RAND_MAX RAND_MAX
#else // otherwise use rand()
#define ANN_RAND random
#define ANN_SRAND srandom
#define ANN_RAND_MAX 2147483647UL // 2**{31} - 1
// #define ANN_RAND_MAX 1073741824UL // 2**{30}
#endif
//----------------------------------------------------------------------
// Globals
//----------------------------------------------------------------------
extern int annIdum; // random number seed
//----------------------------------------------------------------------
// External entry points
//----------------------------------------------------------------------
void annUniformPts( // uniform distribution
ANNpointArray pa, // point array (modified)
int n, // number of points
int dim); // dimension
void annGaussPts( // Gaussian distribution
ANNpointArray pa, // point array (modified)
int n, // number of points
int dim, // dimension
double std_dev); // standard deviation
void annCoGaussPts( // correlated-Gaussian distribution
ANNpointArray pa, // point array (modified)
int n, // number of points
int dim, // dimension
double correlation); // correlation
void annLaplacePts( // Laplacian distribution
ANNpointArray pa, // point array (modified)
int n, // number of points
int dim); // dimension
void annCoLaplacePts( // correlated-Laplacian distribution
ANNpointArray pa, // point array (modified)
int n, // number of points
int dim, // dimension
double correlation); // correlation
void annClusGaussPts( // clustered-Gaussian distribution
ANNpointArray pa, // point array (modified)
int n, // number of points
int dim, // dimension
int n_clus, // number of colors (clusters)
ANNbool new_clust, // generate new cluster centers
double std_dev); // standard deviation within clusters
void annClusOrthFlats( // clustered along orthogonal flats
ANNpointArray pa, // point array (modified)
int n, // number of points
int dim, // dimension
int n_clus, // number of colors
ANNbool new_clust, // generate new clusters.
double std_dev, // standard deviation within clusters
int max_dim); // maximum dimension of the flats
void annClusEllipsoids( // clustered around ellipsoids
ANNpointArray pa, // point array (modified)
int n, // number of points
int dim, // dimension
int n_clus, // number of colors
ANNbool new_clust, // generate new clusters.
double std_dev_small, // small standard deviation
double std_dev_lo, // low standard deviation for ellipses
double std_dev_hi, // high standard deviation for ellipses
int max_dim); // maximum dimension of the flats
void annPlanted( // planted nearest neighbors
ANNpointArray pa, // point array (modified)
int n, // number of points
int dim, // dimension
ANNpointArray src, // source point array
int n_src, // source size
double std_dev); // standard deviation about source
#endif

@ -0,0 +1,21 @@
-10 -2.15443
-9 -2.08008
-8 -2
-7 -1.91293
-6 -1.81712
-5 -1.70998
-4 -1.5874
-3 -1.44225
-2 -1.25992
-1 -1.00001
0 0
1 1.00001
2 1.25992
3 1.44225
4 1.58741
5 1.70998
6 1.81712
7 1.91293
8 2
9 2.08008
10 2.15443

@ -0,0 +1,28 @@
/**
@file
@brief Displaying of a matched 3D scene
@author Kai Lingemann. Institute of Computer Science, University of Osnabrueck, Germany.
@author Andreas Nuechter. Institute of Computer Science, University of Osnabrueck, Germany.
*/
/**
sets the OpenGL point,
(z axis is inverted in OpenGL)
*/
void setGLPoint(GLdouble pX, GLdouble pY, GLdouble pZ)
{
// pZ *= -1.0;
glVertex3d(pX, pY, pZ);
}
/**
sets the OpenGL point,
(z axis is inverted in OpenGL)
*/
void setGLPoint(GLdouble* p)
{
GLdouble pZ = 1.0 * p[2];
glVertex3d(p[0], p[1], pZ);
}

@ -0,0 +1,358 @@
/////////////////////////////////////////////////////////////////////////////
// Name: filebrws.h
// Purpose: A file browser widget with tree and/or list control views
// Author: John Labenski
// Created: 07/01/02
// Copyright: John Labenski, 2002
// License: wxWidgets
/////////////////////////////////////////////////////////////////////////////
#ifndef __WX_FILEBROWSER_H__
#define __WX_FILEBROWSER_H__
#if defined(__GNUG__) && !defined(NO_GCC_PRAGMA)
#pragma interface "filebrws.h"
#endif
#include "wx/listctrl.h"
#include "wx/dirctrl.h"
#include "wx/filedlg.h"
#include "wx/textdlg.h"
#include "wx/generic/filedlgg.h"
#include "wx/things/thingdef.h"
class WXDLLEXPORT wxCheckBox;
class WXDLLEXPORT wxComboBox;
class WXDLLEXPORT wxTreeEvent;
class WXDLLEXPORT wxSplitterWindow;
class WXDLLEXPORT wxGenericDirCtrl;
class WXDLLEXPORT wxListCtrl;
class WXDLLEXPORT wxListEvent;
class WXDLLEXPORT wxToolBar;
class WXDLLEXPORT wxBitmapButton;
class WXDLLEXPORT wxConfigBase;
class WXDLLEXPORT wxFileCtrl;
class WXDLLEXPORT wxFileName;
class WXDLLIMPEXP_THINGS wxFileBrowser;
#include "wx/dynarray.h"
WX_DECLARE_OBJARRAY_WITH_DECL(wxFileData, wxArrayFileData, class WXDLLIMPEXP_THINGS);
//----------------------------------------------------------------------------
// MultilineTextDialog : wxTextEntryDialog for multiple lines
//----------------------------------------------------------------------------
class WXDLLIMPEXP_THINGS MultilineTextDialog : public wxTextEntryDialog
{
public:
MultilineTextDialog(wxWindow *parent,
const wxString& message,
const wxString& caption = wxGetTextFromUserPromptStr,
const wxString& value = wxEmptyString,
long style = 0,
const wxPoint& pos = wxDefaultPosition);
};
//----------------------------------------------------------------------------
// wxFileBrowserEvent : events for the wxFileBrowser
//----------------------------------------------------------------------------
// wxEVT_FILEBROWSER_FILE_SELECTED - a file has been selected (single click)
// wxEVT_FILEBROWSER_FILE_ACTIVATED - a file has been double clicked or enter pressed
// wxEVT_FILEBROWSER_DIR_SELECTED - a dir has been selected (single click)
// wxEVT_FILEBROWSER_DIR_ACTIVATED - a dir has been double clicked or enter pressed
BEGIN_DECLARE_EVENT_TYPES()
DECLARE_EXPORTED_EVENT_TYPE(WXDLLIMPEXP_THINGS, wxEVT_FILEBROWSER_FILE_SELECTED, wxEVT_USER_FIRST + 1000)
DECLARE_EXPORTED_EVENT_TYPE(WXDLLIMPEXP_THINGS, wxEVT_FILEBROWSER_FILE_ACTIVATED, wxEVT_USER_FIRST + 1001)
DECLARE_EXPORTED_EVENT_TYPE(WXDLLIMPEXP_THINGS, wxEVT_FILEBROWSER_DIR_SELECTED, wxEVT_USER_FIRST + 1002)
DECLARE_EXPORTED_EVENT_TYPE(WXDLLIMPEXP_THINGS, wxEVT_FILEBROWSER_DIR_ACTIVATED, wxEVT_USER_FIRST + 1003)
END_DECLARE_EVENT_TYPES()
class WXDLLIMPEXP_THINGS wxFileBrowserEvent : public wxCommandEvent
{
public:
wxFileBrowserEvent( wxEventType commandType = wxEVT_NULL,
wxFileBrowser *fileBrowser = NULL,
wxWindowID id = wxID_ANY );
wxFileBrowserEvent( const wxFileBrowserEvent &event ) : wxCommandEvent(event) {}
// Get the full path + filename
wxString GetFilePath() const { return GetString(); }
void SetFilePath(const wxString &filepath) { SetString(filepath); }
virtual wxEvent *Clone() const { return new wxFileBrowserEvent(*this); }
private:
DECLARE_ABSTRACT_CLASS(wxFileBrowserEvent)
};
typedef void (wxEvtHandler::*wxFileBrowserEventFunction)(wxFileBrowserEvent&);
#define wxFileBrowserEventHandler(func) \
(wxObjectEventFunction)(wxEventFunction)wxStaticCastEvent(wxFileBrowserEventFunction, &func)
#define wx__DECLARE_FILEBROWSEREVT(evt, id, fn) wx__DECLARE_EVT1( evt, id, wxFileBrowserEventHandler(fn))
#define EVT_FILEBROWSER_FILE_SELECTED(id, fn) wx__DECLARE_FILEBROWSEREVT( wxEVT_FILEBROWSER_FILE_SELECTED, id, fn )
#define EVT_FILEBROWSER_FILE_ACTIVATED(id, fn) wx__DECLARE_FILEBROWSEREVT( wxEVT_FILEBROWSER_FILE_ACTIVATED, id, fn )
#define EVT_FILEBROWSER_DIR_SELECTED(id, fn) wx__DECLARE_FILEBROWSEREVT( wxEVT_FILEBROWSER_DIR_SELECTED, id, fn )
#define EVT_FILEBROWSER_DIR_ACTIVATED(id, fn) wx__DECLARE_FILEBROWSEREVT( wxEVT_FILEBROWSER_DIR_ACTIVATED, id, fn )
//----------------------------------------------------------------------------
// wxFileBrowser
//----------------------------------------------------------------------------
enum wxFileBrowserStyles_Type
{
// note: these are wxListCtrl styles to allow normal wxWindow styles to work
wxFILEBROWSER_TREE = wxLC_SORT_DESCENDING, // treectrl view
wxFILEBROWSER_LIST = wxLC_LIST, // listctrl view
wxFILEBROWSER_DETAILS = wxLC_REPORT, // listctrl details view
wxFILEBROWSER_SMALL_ICON = wxLC_SMALL_ICON, // listctrl icon view
wxFILEBROWSER_LARGE_ICON = wxLC_ICON, // NOT IMPL listctrl large icon
wxFILEBROWSER_PREVIEW = wxLC_SORT_ASCENDING, // NOT implemented
wxFILEBROWSER_SPLIT_VERTICAL = wxLC_NO_HEADER, // tree and listctrl are
// split vertically else horizontal
wxFILEBROWSER_SHOW_FOLDERS = wxLC_NO_SORT_HEADER, // when showing listview also show
// the folders in the treectrl
wxFILEBROWSER_VIEW_MASK = wxFILEBROWSER_TREE|wxFILEBROWSER_LIST|wxFILEBROWSER_DETAILS|wxFILEBROWSER_SMALL_ICON|wxFILEBROWSER_LARGE_ICON|wxFILEBROWSER_PREVIEW,
wxFILEBROWSER_STYLE_MASK = wxFILEBROWSER_VIEW_MASK|wxFILEBROWSER_SPLIT_VERTICAL|wxFILEBROWSER_SHOW_FOLDERS
};
class WXDLLIMPEXP_THINGS wxFileBrowser : public wxControl
{
public :
wxFileBrowser() : wxControl() { Init(); }
wxFileBrowser( wxWindow* parent, const wxWindowID id,
const wxString& dir = wxDirDialogDefaultFolderStr,
const wxPoint& pos = wxDefaultPosition,
const wxSize& size = wxDefaultSize,
long style = wxFILEBROWSER_DETAILS,
const wxString& filter = wxFileSelectorDefaultWildcardStr,
int defaultFilter = 0,
const wxString& name = wxT("wxFileBrowser")) : wxControl()
{
Init();
Create(parent, id, dir, pos, size, style, filter, defaultFilter, name);
}
virtual ~wxFileBrowser();
bool Create( wxWindow* parent, const wxWindowID id,
const wxString& dir = wxDirDialogDefaultFolderStr,
const wxPoint& pos = wxDefaultPosition,
const wxSize& size = wxDefaultSize,
long style = wxFILEBROWSER_DETAILS,
const wxString& filter = wxFileSelectorDefaultWildcardStr,
int defaultFilter = 0,
const wxString& name = wxT("wxFileBrowser") );
// Get the current dir (not file), optionally add a trailing platform dependent '/' or '\'
wxString GetPath(bool add_wxFILE_SEP_PATH = false) const;
// Go to a directory, returns sucess
bool SetPath(const wxString &dirName);
// go to a dir or send an EVT_FILEBROWSER_FILE_ACTIVATED if a filename
bool OpenFilePath(const wxString &filePath);
// Go to a higher directory, returns sucess
bool CanGoUpDir() const;
bool GoUpDir();
// Go to your "Home" folder "~/" in unix, "My Documents" in MSW
bool GoToHomeDir();
// Go forwards and backwards through the recent dir history
bool CanGoPathHistoryForward();
bool CanGoPathHistoryBackward();
bool GoPathHistoryForward();
bool GoPathHistoryBackward();
// Add a new path to the history paths at the current index
void AddPathHistory(const wxString& path);
// Set the file filter to one of the filter combobox items
bool SetFilter(int comboItem);
// Set all the file filters, deleting previous and select one
bool SetFilters(const wxString &filters, int select = 0);
// Add or set the file filter, "All Files (*)|*", it must have a "|" in it
bool AddFilter(const wxString &filter);
// Get the current file filter
wxString GetFilter() const { return m_filter; }
// Get the wild card used for the filter
wxString GetWild() const { return m_filter.AfterLast(wxT('|')); }
// Set how the files are displayed - see enum wxFileBrowserStyles_Type
void SetBrowserStyle(long style);
long GetBrowserStyle() const { return m_browser_style; }
bool HasBrowserStyle(int style_mask) const { return (m_browser_style & style_mask) != 0; }
// Show or hide hidden files
void ShowHidden(bool show_hidden);
bool GetShowHidden() const { return m_show_hidden; }
// When showing the files in a listctrl also show the folders in the treectrl
// also don't let them unsplit it
void ShowFolders(bool show_folders);
bool GetShowFolders() const { return HasBrowserStyle(wxFILEBROWSER_SHOW_FOLDERS); }
// When splitting, split vertically or horizontally
void SplitVertical(bool split_vertically);
bool GetSplitVertical() const { return HasBrowserStyle(wxFILEBROWSER_SPLIT_VERTICAL); }
// -----------------------------------------------------------------------
// implementation
// utility function, returns the dir part of the filepath w/ trailing wxFILE_SEP_PATH
bool GetPathFromFilePath(const wxString &filepath, wxString &path) const;
// Delete all selected items in the wxFileCtrl
bool DeleteSelectedListItems(bool ask_ok = true);
// Store a list of selected items that you'll copy/cut when you paste them
bool CopyCutSelectedListItems(bool copy_them);
// Paste the stored CopyCutSelectedListItems - based on CopyCutSelectedListItems list
bool PasteCopyCutSelectedListItems();
// Get a list of all the selected items in the list control
wxArrayInt GetSelectedListItems() const;
// Get the wxFileData items that are selected in the list control
wxArrayFileData GetSelectedListFileData() const;
// Get the currently focused list item or NULL if none selected
wxFileData *GetFocusedListItem() const;
// Create a wxFileData from a wxFileName
wxFileData CreateFileData(const wxFileName& fileName) const;
// Get the last or currently focused path + filename
wxString GetLastFocusedFilePath();
// Show a simple dialog that contains the properties of the file/dir
void ShowPropertiesDialog(const wxFileData &fileData) const;
// returns a string with the name of a program to run the file
wxString GetOpenWithFileCmd(wxFileData* fd) const;
// Get a pointer to the path history combo, can change its contents
wxComboBox *GetPathCombo() const { return m_pathCombo; }
// Get a pointer to the filter combo
// don't delete selections less than the # of filters passed in
// ie. check for items with GetClientData() !NULL
wxComboBox *GetFilterCombo() const { return m_filterCombo; }
// Can this file be read/opened?
bool CanRead(const wxString& filePath) const;
// Can this file be written to, deleted, moved, cut...
bool CanWrite(const wxString& filePath) const;
// Update the menu/toolbar items
void UpdateMenu(wxMenu *menu);
void UpdateToolBar(wxToolBar *toolBar);
// Update the state of the toolbar and menu items
void UpdateItems();
#if wxUSE_CONFIG
// Load the recent paths/filters, max = 20
void LoadConfig(wxConfigBase& config,
bool paths=true, bool filters=true,
const wxString &configPath = wxT("/wxFileBrowser"));
// Save the recent paths, filters, if n_xxx < 0 then don't save it
void SaveConfig(wxConfigBase& config,
int n_paths=10, int n_filters=10,
const wxString &configPath = wxT("/wxFileBrowser"));
#endif // wxUSE_CONFIG
protected :
void OnSize( wxSizeEvent& event );
void DoSize();
virtual wxSize DoGetBestSize() const;
// toolbar tools events
void OnViewButtons(wxCommandEvent &event);
void OnPathCombo(wxCommandEvent &event);
void OnPathComboEnter(wxCommandEvent &event);
void OnFilterCombo(wxCommandEvent &event);
void OnFilterComboEnter(wxCommandEvent &event);
// wxDirCtrl events - a wxTreeCtrl
void OnTreeItemSelection(wxTreeEvent &event);
void OnTreeItemActivation(wxTreeEvent &event);
void OnTreeRightClick(wxTreeEvent& event);
// wxFileCtrl events - a wxListCtrl
void OnListColClick(wxListEvent &event);
void OnListItemActivated(wxListEvent &event);
void OnListItemSelected(wxListEvent &event);
void OnListRightClick(wxListEvent &event);
void OnTreeMenu(wxCommandEvent &event);
void OnListMenu(wxCommandEvent &event);
void OnIdle( wxIdleEvent &event );
//for delayed set path from combo
void OnSetPath( wxCommandEvent &event );
void OnSetFilter( wxCommandEvent &event );
// (re)inserts the item at pos, deleting it if it existed after pos
// keeps recent items at top
bool InsertComboItem(wxComboBox *combo, const wxString &item, int pos = 0) const;
// Send an event, returns false if event.Veto() called
bool DoSendEvent(wxFileBrowserEvent &event) const;
int FBStyleToLCStyle(int fb_style) const; // wxFileBrowserStyles_Type to wxLC_XXX
int FBStyleToMenuID(int fb_style) const; // wxFileBrowserStyles_Type menu id
int MenuIDToFBStyle(int menuID) const; // menu id to wxFileBrowserStyles_Type
// Windows
wxToolBar *m_viewToolBar;
wxToolBar *m_pathToolBar;
wxBitmapButton *m_viewButton;
wxComboBox *m_filterCombo;
wxComboBox *m_pathCombo;
wxSplitterWindow *m_splitterWin;
wxGenericDirCtrl *m_dirCtrl;
wxFileCtrl *m_fileCtrl;
wxMenu *m_listMenu; // popup menu in listctrl
wxMenu *m_treeMenu; // popup menu in treectrl
wxMenu *m_viewMenu; // popup menu in for changing view
// data
wxString m_filter; // current filter
wxString m_path; // current path
wxString m_lastFocusedFilePath; // path + filename of last focused item
wxArrayString m_pathHistory; // recently used paths
int m_path_history_index; // current index in recently used paths
wxArrayFileData m_copycutFiles; // list of names when copying or cutting
bool m_last_copy; // last CopyCutSelectedListItems was a copy, else cut
int m_init_filters; // # of filters initially passed in
bool m_ignore_tree_event; // temporarily ignore m_dirCtrl events
long m_browser_style;
int m_filterComboSelection; // last selection of the filter/path combo
int m_pathComboSelection;
bool m_show_hidden; // show hidden files
private :
void Init();
DECLARE_EVENT_TABLE()
DECLARE_DYNAMIC_CLASS(wxFileBrowser)
};
#endif // __WX_FILEBROWSER_H__

@ -0,0 +1,341 @@
/****************************************************************************
GLUI User Interface Toolkit
---------------------------
glui_radio.cpp - GLUI_RadioGroup and GLUI_RadioButton control classes
--------------------------------------------------
Copyright (c) 1998 Paul Rademacher
This program is freely distributable without licensing fees and is
provided without guarantee or warrantee expressed or implied. This
program is -not- in the public domain.
*****************************************************************************/
#include "glui.h"
#include "stdinc.h"
/****************************** GLUI_RadioGroup::draw() **********/
void GLUI_RadioGroup::draw( int x, int y )
{
if ( NOT can_draw() )
return;
draw_group(false);
}
/********************* GLUI_RadioGroup::draw_group(int translate) **********/
void GLUI_RadioGroup::draw_group( int translate )
{
GLUI_RadioButton *button;
int state = 0, orig;
if ( NOT can_draw() )
return;
orig = set_to_glut_window();
if ( translate )
state = glui->set_front_draw_buffer();
this->int_val = int_val;
glMatrixMode(GL_MODELVIEW );
button = (GLUI_RadioButton*) first_child();
while( button != NULL ) {
if ( translate ) {
glPushMatrix();
button->translate_to_origin();
}
if ( button->int_val )
button->draw_checked();
else
button->draw_unchecked();
if ( translate )
glPopMatrix();
button = (GLUI_RadioButton*) button->next();
}
if ( translate )
glui->restore_draw_buffer(state);
restore_window(orig);
}
/****************************** GLUI_RadioGroup::set_name() **********/
void GLUI_RadioGroup::set_name( char *text )
{
strncpy(name,text,sizeof(GLUI_String));
if ( glui )
glui->refresh();
}
/********************************* GLUI_RadioGroup::set_selected() **********/
void GLUI_RadioGroup::set_selected( int int_val )
{
GLUI_RadioButton *button;
this->int_val = int_val;
button = (GLUI_RadioButton*) first_child();
while( button != NULL ) {
if ( int_val == -1 ) { /*** All buttons in group are deselected ***/
button->set_int_val(0);
}
else if ( int_val == button->user_id ) { /*** This is selected button ***/
button->set_int_val(1);
}
else { /*** This is NOT selected button ***/
button->set_int_val(0);
}
button = (GLUI_RadioButton*) button->next();
}
}
/************************ GLUI_RadioButton::mouse_down_handler() **********/
int GLUI_RadioButton::mouse_down_handler( int local_x, int local_y )
{
if ( NOT group )
return false;
orig_value = group->int_val;
currently_inside = true;
group->set_selected( this->user_id );
group->draw_group( true );
return false;
}
/*************************** GLUI_RadioButton::mouse_up_handler() **********/
int GLUI_RadioButton::mouse_up_handler( int local_x, int local_y,
int inside )
{
if ( NOT group )
return false;
if ( NOT inside ) {
group->set_selected( orig_value );
group->draw_group( true );
}
else {
/** Now we update the radio button group. We tell the group
handler to set the currently-selected item to this button, which
is reference by its user_id/ordinal number within group **/
group->set_selected( this->user_id );
group->draw_group( true );
/*** Now update the linked variable, and call the callback,
but ONLY if the value of the radio group actually changed ***/
if ( group->int_val != orig_value ) {
group->output_live(true); /** Output live and update gfx ***/
group->execute_callback();
}
}
return false;
}
/********************** GLUI_RadioButton::mouse_held_down_handler() ******/
int GLUI_RadioButton::mouse_held_down_handler( int local_x, int local_y,
int inside)
{
if ( NOT inside AND currently_inside == true ) {
group->set_selected( orig_value );
group->draw_group( true );
}
else if ( inside AND currently_inside == false ) {
group->set_selected( this->user_id );
group->draw_group( true );
}
currently_inside = inside;
return false;
}
/****************************** GLUI_RadioButton::draw() **********/
void GLUI_RadioButton::draw( int x, int y )
{
int orig;
orig = set_to_glut_window();
if ( NOT group OR NOT can_draw() )
return;
/*** See if we're the currently-selected button. If so, draw ***/
if ( group->int_val == this->user_id ) {
if ( enabled )
glui->std_bitmaps.draw( GLUI_STDBITMAP_RADIOBUTTON_ON, 0, 0 );
else
glui->std_bitmaps.draw( GLUI_STDBITMAP_RADIOBUTTON_ON_DIS, 0, 0 );
}
else {
if ( enabled )
glui->std_bitmaps.draw( GLUI_STDBITMAP_RADIOBUTTON_OFF, 0, 0 );
else
glui->std_bitmaps.draw( GLUI_STDBITMAP_RADIOBUTTON_OFF_DIS, 0, 0 );
}
draw_active_area();
draw_name( text_x_offset, 10 );
restore_window(orig);
}
/************************************ GLUI_RadioButton::draw_checked() ******/
void GLUI_RadioButton::draw_checked( void )
{
int orig;
if ( NOT can_draw() )
return;
orig = set_to_glut_window();
if ( enabled )
glui->std_bitmaps.draw( GLUI_STDBITMAP_RADIOBUTTON_ON, 0, 0 );
else
glui->std_bitmaps.draw( GLUI_STDBITMAP_RADIOBUTTON_ON_DIS, 0, 0 );
draw_active_area();
restore_window(orig);
}
/*********************************** GLUI_RadioButton::draw_unchecked() ******/
void GLUI_RadioButton::draw_unchecked( void )
{
int orig;
if ( NOT can_draw() )
return;
orig = set_to_glut_window();
if ( enabled )
glui->std_bitmaps.draw( GLUI_STDBITMAP_RADIOBUTTON_OFF, 0, 0 );
else
glui->std_bitmaps.draw( GLUI_STDBITMAP_RADIOBUTTON_OFF_DIS, 0, 0 );
draw_active_area();
restore_window(orig);
}
/**************************************** GLUI_RadioButton::draw_O() ********/
void GLUI_RadioButton::draw_O( void )
{
int i, j, orig;
if ( NOT can_draw() )
return;
orig = set_to_glut_window();
glBegin( GL_POINTS );
for(i=3; i<=GLUI_RADIOBUTTON_SIZE-3; i++ )
for(j=3; j<=GLUI_RADIOBUTTON_SIZE-3; j++ )
glVertex2i(i,j);
glEnd();
restore_window(orig);
}
/******************************** GLUI_RadioButton::update_size() **********/
void GLUI_RadioButton::update_size( void )
{
int text_size;
if ( NOT glui )
return;
text_size = _glutBitmapWidthString( glui->font, name );
/* if ( w < text_x_offset + text_size + 6 ) */
w = text_x_offset + text_size + 6 ;
}
/************************* GLUI_RadioButton::draw_active_area() **************/
void GLUI_RadioButton::draw_active_area( void )
{
int text_width, left, right, orig;
if ( NOT can_draw() )
return;
orig = set_to_glut_window();
text_width = _glutBitmapWidthString( glui->font, name );
left = text_x_offset-3;
right = left + 7 + text_width;
if ( active ) {
glEnable( GL_LINE_STIPPLE );
glLineStipple( 1, 0x5555 );
glColor3f( 0., 0., 0. );
} else {
glColor3ub( glui->bkgd_color.r, glui->bkgd_color.g, glui->bkgd_color.b );
}
glBegin( GL_LINE_LOOP );
glVertex2i(left,0); glVertex2i( right,0);
glVertex2i(right,h+1); glVertex2i( left,h+1);
glEnd();
glDisable( GL_LINE_STIPPLE );
restore_window(orig);
}
/********************************* GLUI_RadioGroup::set_int_val() **********/
void GLUI_RadioGroup::set_int_val( int new_val )
{
if ( new_val == int_val )
return;
set_selected( new_val );
draw_group( true );
output_live(true);
}

@ -0,0 +1,130 @@
#ifndef _XGETOPT_H
#define _XGETOPT_H
/*
getopt.h - comand line option parsing
Copyright Keristor Systems and Chris Croughton 1997 - 2005
Internet: swdev@keristor.org
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it
freely, subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not
claim that you wrote the original software. If you use this software
in a product, an acknowledgment in the product documentation would be
appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be
misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT,
INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING
IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
*/
/**@file xgetopt.h
*
* This module is designed as a "drop-in" replacement for the GNU
* \c getopt.h module, providing the \c getopt(), \c getopt_long() and
* \c getopt_long_only() functions and the \c option structure. However,
* it is a compile-time replacement not an object one, the actual
* names of the external variables and functions are hidden so that
* namespace clashes don't occur (some linkers object if they find
* the same symbol in more than one library).
*
* It was written originally because of systems which don't have the GNU
* C library installed.
*
* It also provides a few functions to help create a string of short
* (single-character) options given an array of long option structures.
*
* This is a "clean-room" implementation, no GPL or proprietary code
* was looked at when creating it. The only things used were the
* descriptions of the interfaces in the \c man pages (and the POSIX
* specification), and some "black box" testing to determine error
* conditions and messages not specified in the interface description.
*/
#if defined(_cplusplus) || defined(__cplusplus)
extern "C" {
#endif
/*
* This bit of faffing about is because some systems don't like the same
* functions defined in more than one library, they get confused. So what
* we do is to redefine the variables to the names in the interface but
* fool the linker. This only makes a difference if you try to debug the
* getopt code. Note that we don't have to do it with the structure name
* or enums, since it's only linkage that's affected.
*/
#define optarg _XLIB_optarg
#define optind _XLIB_optind
#define opterr _XLIB_opterr
#define optopt _XLIB_optopt
#define getopt _XLIB_getopt
#define getopt_long _XLIB_getopt_long
#define getopt_long_only _XLIB_getopt_long_only
/** holds a pointer to an option argument */
extern char *optarg;
/** index to te first non-option argument */
extern int optind;
/** allow error messages if non-zero (default) */
extern int opterr;
/** holds the option character in error, if any */
extern int optopt;
enum
{
/** this option has no argument */
no_argument,
/** an argument is required with this option */
required_argument,
/** an argument to this option is optional */
optional_argument
};
/**
* Structure to describe a long option.
* The last item in the array of these descriptors must have all elements
* set to zero
*/
struct option
{
/** long option name */
const char *name;
/** argument type, if any */
int has_arg;
/** pointer to a flag to be set if the option is present */
int *flag;
/** value to be returned if the option is present */
int val;
};
/** Scan the command-line parameters for options in the form {\em -x}. */
int getopt(int argc, char * const argv[], const char *optstring);
/** Scan the command-line parameters for options, allowing both the short
* (single character) options and long (string) options.
*/
int getopt_long(int argc, char * const argv[], const char *optstring,
const struct option *longopts, int *longindex);
/** Scan the command-line parameters for long options only */
int getopt_long_only(int argc, char * const argv[], const char *optstring,
const struct option *longopts, int *longindex);
#if defined(_cplusplus) || defined(__cplusplus)
}
#endif
#endif

@ -0,0 +1,95 @@
/*
* grabFramesCam implementation
*
* Copyright (C) Stanislav Serebryakov
*
* Released under the GPL version 3.
*
*/
#include <stdio.h>
#include <stdlib.h>
#include <cv.h>
#include <highgui.h>
//TODO: flip image flag
void usage(char *progName) {
printf("%s <board-size-x> <board-size-y> <camera-id>\n", progName);
printf("i.e.: %s 6 4 0\n", progName);
printf("press space to detect chessboard and (again) to proceed.\n");
}
int main(int argc, char **argv)
{
/* TODO:
* flags:
* subpixel
* camera id
* flip x and y
* pmd mode?
*/
if(argc < 4) {
usage(argv[0]);
exit(1);
}
CvCapture *capture = cvCaptureFromCAM(atoi(argv[3]));
IplImage *imgColor = cvQueryFrame(capture);
IplImage *img = cvCreateImage(cvGetSize(imgColor), 8, 1);
int patx = atoi(argv[1]);
int paty = atoi(argv[2]);
CvSize patternSize = cvSize(patx, paty);
int cornersTotal = patternSize.width * patternSize.height;
CvPoint2D32f *corners = (CvPoint2D32f*) malloc(cornersTotal * sizeof(CvPoint2D32f));
cvNamedWindow("Camera", 0);
int imageCnt = 0;
bool grabFrame = false;
while(1) {
imgColor = cvQueryFrame(capture);
cvFlip(imgColor, 0, -1); // flips image around the x and y axes
cvCvtColor(imgColor, img, CV_BGR2GRAY);
if(grabFrame) {
/* ----- Chessboard detection -----
-------------------------------- */
int cornersCount; // should be the same for wcam and pmd and equal totalCorners
int found = cvFindChessboardCorners(img, patternSize, corners,
&cornersCount, CV_CALIB_CB_ADAPTIVE_THRESH | CV_CALIB_CB_FILTER_QUADS);
cvFindCornerSubPix(img, corners, cornersCount, cvSize(11,11), cvSize(-1,-1),
cvTermCriteria(CV_TERMCRIT_EPS | CV_TERMCRIT_ITER, 30, 0.1));
if(found && (cornersCount == cornersTotal)) {
cvDrawChessboardCorners(imgColor, patternSize, corners, cornersCount, found);
cvShowImage("Camera", imgColor);
printf("grab?\n");
int k = cvWaitKey(0);
if(k == (int)' ') {
imageCnt++;
char *filename = (char*) malloc(11 * sizeof(char));
sprintf(filename, "image%02i.jpg", imageCnt);
printf("saved %s.\n", filename);
cvSaveImage(filename, img);
grabFrame = false;
continue;
}
}
}
cvShowImage("Camera", imgColor);
if((int)' ' == cvWaitKey(5)) grabFrame = true;
}
return 0;
}

@ -0,0 +1,213 @@
//#define WANT_STREAM
#include "include.h"
#include "newmatap.h"
#include "tmt.h"
#ifdef use_namespace
using namespace NEWMAT;
#endif
/**************************** test program ******************************/
void trymat9()
{
Tracer et("Ninth test of Matrix package");
Tracer::PrintTrace();
int i; int j;
Matrix A(7,7); Matrix X(7,3);
for (i=1;i<=7;i++) for (j=1;j<=7;j++) A(i,j)=i*i+j+((i==j) ? 1 : 0);
for (i=1;i<=7;i++) for (j=1;j<=3;j++) X(i,j)=i-j;
Matrix B = A.i(); DiagonalMatrix D(7); D=1.0;
{
Tracer et1("Stage 1");
Matrix Q = B*A-D; Clean(Q, 0.000000001); Print(Q);
Q=A; Q = Q.i() * X; Q = A*Q - X; Clean(Q, 0.000000001); Print(Q);
Q=X; Q = A.i() * Q; Q = A*Q - X; Clean(Q, 0.000000001); Print(Q);
}
for (i=1;i<=7;i++) D(i,i)=i*i+1;
DiagonalMatrix E(3); for (i=1;i<=3;i++) E(i,i)=i+23;
{
Tracer et1("Stage 2");
Matrix DXE = D.i() * X * E;
DXE = E.i() * DXE.t() * D - X.t(); Clean(DXE, 0.00000001); Print(DXE);
E=D; for (i=1;i<=7;i++) E(i,i)=i*3+1;
}
DiagonalMatrix F=D;
{
Tracer et1("Stage 3");
F=E.i()*F; F=F*E-D; Clean(F,0.00000001); Print(F);
F=E.i()*D; F=F*E-D; Clean(F,0.00000001); Print(F);
}
{
Tracer et1("Stage 4");
F=E; F=F.i()*D; F=F*E-D; Clean(F,0.00000001); Print(F);
}
{
Tracer et1("Stage 5");
// testing equal
ColumnVector A(18), B(18);
Matrix X(3,3);
X << 3 << 5 << 7 << 5 << 8 << 2 << 7 << 2 << 9;
SymmetricMatrix S; S << X;
B(1) = S == X; A(1) = true;
B(2) = S == (X+1); A(2) = false;
B(3) = (S+2) == (X+2); A(3) = true;
Matrix Y = X;
B(4) = X == Y; A(4) = true;
B(5) = (X*2) == (Y*2); A(5) = true;
Y(3,3) = 10;
B(6) = X == Y; A(6) = false;
B(7) = (X*2) == (Y*2); A(7) = false;
B(8) = S == Y; A(8) = false;
B(9) = S == S; A(9) = true;
Matrix Z = X.SubMatrix(1,2,2,3);
B(10) = X == Z; A(10) = false;
GenericMatrix GS = S;
GenericMatrix GX = X;
GenericMatrix GY = Y;
B(11) = GS == GX; A(11) = true;
B(12) = GS == GY; A(12) = false;
CroutMatrix CS = S;
CroutMatrix CX = X;
CroutMatrix CY = Y;
B(13) = CS == CX; A(13) = true;
B(14) = CS == CY; A(14) = false;
B(15) = X == CX; A(15) = false;
B(16) = X == A; A(16) = false;
B(17) = X == (X | X); A(17) = false;
B(18) = CX == X; A(18) = false;
A = A - B; Print(A);
}
{
Tracer et1("Stage 6");
// testing equal
ColumnVector A(22), B(22);
BandMatrix X(6,2,1);
X(1,1)=23; X(1,2)=21;
X(2,1)=12; X(2,2)=17; X(2,3)=45;
X(3,1)=35; X(3,2)=19; X(3,3)=24; X(3,4)=29;
X(4,2)=17; X(4,3)=11; X(4,4)=19; X(4,5)=35;
X(5,3)=10; X(5,4)=44; X(5,5)=23; X(5,6)=31;
X(6,4)=49; X(6,5)=41; X(6,6)=17;
SymmetricBandMatrix S1(6,2); S1.Inject(X);
BandMatrix U(6,2,3); U = 0.0; U.Inject(X);
B(1) = U == X; A(1) = true;
B(2) = U == (X*3); A(2) = false;
B(3) = (U*5) == (X*5); A(3) = true;
Matrix Y = X;
B(4) = X == Y; A(4) = true;
B(5) = (X*2) == (Y*2); A(5) = true;
Y(6,6) = 10;
B(6) = X == Y; A(6) = false;
B(7) = (X*2) == (Y*2); A(7) = false;
B(8) = U == Y; A(8) = false;
B(9) = U == U; A(9) = true;
Matrix Z = X.SubMatrix(1,2,2,3);
B(10) = X == Z; A(10) = false;
GenericMatrix GU = U;
GenericMatrix GX = X;
GenericMatrix GY = Y;
B(11) = GU == GX; A(11) = true;
B(12) = GU == GY; A(12) = false;
X = X + X.t(); U = U + U.t();
SymmetricBandMatrix S(6,2); S.Inject(X);
Matrix D = S-X; Print(D);
BandLUMatrix BS = S;
BandLUMatrix BX = X;
BandLUMatrix BU = U;
CroutMatrix CX = X;
B(13) = BS == BX; A(13) = true;
B(14) = BX == BU; A(14) = false;
B(15) = X == BX; A(15) = false;
B(16) = X != BX; A(16) = true;
B(17) = BX != BS; A(17) = false;
B(18) = (2*X) != (X*2);A(18) = false;
B(19) = (X*2) != (X+2);A(19) = true;
B(20) = BX == CX; A(20) = false;
B(21) = CX == BX; A(21) = false;
B(22) = BX == X; A(22) = false;
A = A - B; Print(A);
DiagonalMatrix I(6); I=1.0;
D = BS.i() * X - I; Clean(D,0.00000001); Print(D);
D = BX.i() * X - I; Clean(D,0.00000001); Print(D);
D = BU.i() * X - I; Clean(D,0.00000001); Print(D);
// test row wise load
SymmetricBandMatrix X1(6,2);
X1.Row(1) << 23;
X1.Row(2) << 12 << 17;
X1.Row(3) << 35 << 19 << 24;
X1.Row(4) << 17 << 11 << 19;
X1.Row(5) << 10 << 44 << 23;
X1.Row(6) << 49 << 41 << 17;
Matrix M = X1 - S1; Print(M);
// check out submatrix
SymmetricBandMatrix X2(20,3); X2 = 0.0;
X2.SubMatrix(2,7,2,7) = X1; X2.SymSubMatrix(11,16) = 2 * X1;
Matrix MX1 = X1;
Matrix MX2(20,20); MX2 = 0;
MX2.SymSubMatrix(2,7) = MX1; MX2.SubMatrix(11,16,11,16) = MX1 * 2;
MX2 -= X2; Print(MX2);
BandMatrix X4(20,3,3); X4 = 0.0;
X4.SubMatrix(2,7,3,8) = X1; X4.SubMatrix(11,16,10,15) = 2 * X1;
MX1 = X1;
Matrix MX4(20,20); MX4 = 0;
MX4.SubMatrix(2,7,3,8) = MX1; MX4.SubMatrix(11,16,10,15) = MX1 * 2;
MX4 -= X4; Print(MX4);
MX1 = X1.i() * X1 - IdentityMatrix(6);
Clean(MX1,0.00000001); Print(MX1);
}
{
Tracer et1("Stage 7");
// testing equal
ColumnVector A(12), B(12);
BandMatrix X(6,2,1);
X(1,1)=23; X(1,2)=21;
X(2,1)=12; X(2,2)=17; X(2,3)=45;
X(3,1)=35; X(3,2)=19; X(3,3)=24; X(3,4)=29;
X(4,2)=17; X(4,3)=11; X(4,4)=19; X(4,5)=35;
X(5,3)=10; X(5,4)=44; X(5,5)=23; X(5,6)=31;
X(6,4)=49; X(6,5)=41; X(6,6)=17;
Matrix Y = X;
LinearEquationSolver LX = X;
LinearEquationSolver LY = Y;
CroutMatrix CX = X;
CroutMatrix CY = Y;
BandLUMatrix BX = X;
B(1) = LX == CX; A(1) = false;
B(2) = LY == CY; A(2) = true;
B(3) = X == Y; A(3) = true;
B(4) = BX == LX; A(4) = true;
B(5) = CX == CY; A(5) = true;
B(6) = LX == LY; A(6) = false;
B(7) = BX == BX; A(7) = true;
B(8) = CX == CX; A(8) = true;
B(9) = LX == LX; A(9) = true;
B(10) = LY == LY; A(10) = true;
CroutMatrix CX1 = X.SubMatrix(1,4,1,4);
B(11) = CX == CX1; A(11) = false;
BandLUMatrix BX1 = X.SymSubMatrix(1,4); // error with SubMatrix
B(12) = BX == BX1; A(12) = false;
A = A - B; Print(A);
DiagonalMatrix I(6); I=1.0; Matrix D;
D = LX.i() * X - I; Clean(D,0.00000001); Print(D);
D = LY.i() * X - I; Clean(D,0.00000001); Print(D);
I.ReSize(4); I = 1;
D = CX1.i() * X.SymSubMatrix(1,4) - I; Clean(D,0.00000001); Print(D);
D = BX1.i() * X.SubMatrix(1,4,1,4) - I; Clean(D,0.00000001); Print(D);
}
// cout << "\nEnd of ninth test\n";
}

@ -0,0 +1,155 @@
//#define WANT_STREAM
#define WANT_MATH
#include "include.h"
#include "newmatap.h"
#include "tmt.h"
#ifdef use_namespace
using namespace NEWMAT;
#endif
/**************************** test program ******************************/
// slow sort program
static void SimpleSortDescending(Real* first, const int length)
{
int i = length;
while (--i)
{
Real x = *first; Real* f = first; Real* g = f;
int j = i;
while (j--) if (x < *(++f)) { g = f; x = *g; }
*g = *first; *first++ = x;
}
}
static void TestSort(int n)
{
// make some data
RowVector X(n);
int i;
for (i = 1; i <= n; i++)
X(i) = sin((Real)i) + 0.3 * cos(i/5.0) - 0.6 * sin(i/7.0) + 0.2 * sin(2.0 * i);
RowVector X_Sorted = X; SimpleSortDescending(X_Sorted.Store(), n);
RowVector A = X + X.Reverse(); SimpleSortDescending(A.Store(), n);
// test descending sort
RowVector Y = X; SortDescending(Y); Y -= X_Sorted; Print(Y);
Y = X_Sorted; SortDescending(Y); Y -= X_Sorted; Print(Y);
Y = X_Sorted.Reverse(); SortDescending(Y); Y -= X_Sorted; Print(Y);
Y = X + X.Reverse(); SortDescending(Y); Y -= A; Print(Y);
// test ascending sort
Y = X; SortAscending(Y); Y -= X_Sorted.Reverse(); Print(Y);
Y = X_Sorted; SortAscending(Y); Y -= X_Sorted.Reverse(); Print(Y);
Y = X_Sorted.Reverse(); SortAscending(Y); Y -= X_Sorted.Reverse(); Print(Y);
Y = X + X.Reverse(); SortAscending(Y); Y -= A.Reverse(); Print(Y);
}
void trymat6()
{
Tracer et("Sixth test of Matrix package");
Tracer::PrintTrace();
int i,j;
DiagonalMatrix D(6);
UpperTriangularMatrix U(6);
for (i=1;i<=6;i++) { for (j=i;j<=6;j++) U(i,j)=i*i*i-50; D(i,i)=i*i+i-10; }
LowerTriangularMatrix L=(U*3.0).t();
SymmetricMatrix S(6);
for (i=1;i<=6;i++) for (j=i;j<=6;j++) S(i,j)=i*i+2.0+j;
Matrix MD=D; Matrix ML=L; Matrix MU=U; Matrix MS=S;
Matrix M(6,6);
for (i=1;i<=6;i++) for (j=1;j<=6;j++) M(i,j)=i*j+i*i-10.0;
{
Tracer et1("Stage 1");
Print(Matrix(MS+(-MS)));
Print(Matrix((S+M)-(MS+M)));
Print(Matrix((M+U)-(M+MU)));
Print(Matrix((M+L)-(M+ML)));
}
{
Tracer et1("Stage 2");
Print(Matrix((M+D)-(M+MD)));
Print(Matrix((U+D)-(MU+MD)));
Print(Matrix((D+L)-(ML+MD)));
Print(Matrix((-U+D)+MU-MD));
Print(Matrix((-L+D)+ML-MD));
}
{
Tracer et1("Stage 3 - concatenate");
RowVector A(5);
A << 1 << 2 << 3 << 4 << 5;
RowVector B(5);
B << 3 << 1 << 4 << 1 << 5;
Matrix C(3,5);
C << 2 << 3 << 5 << 7 << 11
<< 13 << 17 << 19 << 23 << 29
<< 31 << 37 << 41 << 43 << 47;
Matrix X1 = A & B & C;
Matrix X2 = (A.t() | B.t() | C.t()).t();
Matrix X3(5,5);
X3.Row(1)=A; X3.Row(2)=B; X3.Rows(3,5)=C;
Print(Matrix(X1-X2));
Print(Matrix(X1-X3));
LowerTriangularMatrix LT1; LT1 << (A & B & C);
UpperTriangularMatrix UT1; UT1 << (A.t() | B.t() | C.t());
Print(LowerTriangularMatrix(LT1-UT1.t()));
DiagonalMatrix D1; D1 << (A.t() | B.t() | C.t());
ColumnVector At = A.t();
ColumnVector Bt = B.t();
Matrix Ct = C.t();
LowerTriangularMatrix LT2; LT2 << (At | Bt | Ct);
UpperTriangularMatrix UT2; UT2 << (At.t() & Bt.t() & Ct.t());
Matrix ABt = At | Bt;
DiagonalMatrix D2; D2 << (ABt | Ct);
Print(LowerTriangularMatrix(LT2-UT2.t()));
Print(DiagonalMatrix(D1-D2));
Print(Matrix(LT1+UT2-D2-X1));
Matrix M1 = LT1 | UT2; Matrix M2 = UT1 & LT2;
Print(Matrix(M1-M2.t()));
M1 = UT2 | LT1; M2 = LT2 & UT1;
Print(Matrix(M1-M2.t()));
M1 = (LT1 | UT2) & (UT2 | LT1);
M2 = (UT1 & LT2) | (LT2 & UT1);
Print(Matrix(M1-M2.t()));
SymmetricMatrix SM1; SM1 << (M1 + M1.t());
SymmetricMatrix SM2; SM2 << ((SM1 | M1) & (M1.t() | SM1));
Matrix M3(20,20);
M3.SubMatrix(1,10,1,10) = SM1;
M3.SubMatrix(1,10,11,20) = M1;
M3.SubMatrix(11,20,1,10) = M2;
M3.SubMatrix(11,20,11,20) = SM1;
Print(Matrix(M3-SM2));
SymmetricMatrix SM(15); SM = 0; SM.SymSubMatrix(1,10) = SM1;
M3.ReSize(15,15); M3 = 0; M3.SubMatrix(1,10,1,10) = SM1;
M3 -= SM; Print(M3);
SM = 0; SM.SymSubMatrix(6,15) = SM1;
M3.ReSize(15,15); M3 = 0; M3.SubMatrix(6,15,6,15) = SM1;
M3 = M3.t() - SM; Print(M3);
}
{
Tracer et1("Stage 4 - sort");
TestSort(1); TestSort(2); TestSort(3); TestSort(4);
TestSort(15); TestSort(16); TestSort(17); TestSort(18);
TestSort(99); TestSort(100); TestSort(101);
}
// cout << "\nEnd of sixth test\n";
}

@ -0,0 +1,137 @@
/** @file
* @brief Representation of the optimized k-d tree. MetaScan variant.
* @author Andreas Nuechter. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Kai Lingemann. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Thomas Escher
*/
#ifndef __KD_META_H__
#define __KD_META_H__
#include "kdparams.h"
#include "searchTree.h"
#include "data_types.h"
#include <boost/thread/mutex.hpp>
#include <boost/thread/locks.hpp>
#ifdef _MSC_VER
#if !defined _OPENMP && defined OPENMP
#define _OPENMP
#endif
#endif
#ifdef _OPENMP
#include <omp.h>
#endif
class Scan;
/**
* @brief The optimized k-d tree.
*
* A kD tree for points, with limited
* capabilities (find nearest point to
* a given point, or to a ray).
**/
class KDtreeMeta : public SearchTree {
protected:
class Index {
public:
unsigned int s, i;
inline void set(unsigned int _s, unsigned int _i) { s = _s; i = _i; }
};
public:
KDtreeMeta();
virtual ~KDtreeMeta();
void create(const DataXYZ* const* pts, Index* indices, unsigned int n);
virtual double *FindClosest(double *_p, double maxdist2, int threadNum = 0) const { return 0; }
protected:
/**
* storing the parameters of the k-d tree, i.e., the current closest point,
* the distance to the current closest point and the point itself.
* These global variable are needed in this search.
*
* Padded in the parallel case.
*/
#ifdef _OPENMP
#ifdef __INTEL_COMPILER
__declspec (align(16)) static KDParams params[MAX_OPENMP_NUM_THREADS];
#else
static KDParams params[MAX_OPENMP_NUM_THREADS];
#endif //__INTEL_COMPILER
#else
static KDParams params[MAX_OPENMP_NUM_THREADS];
#endif
/**
* number of points. If this is 0: intermediate node. If nonzero: leaf.
*/
int npts;
/**
* Cue the standard rant about anon unions but not structs in C++
*/
union {
/**
* in case of internal node...
*/
struct {
double center[3]; ///< storing the center of the voxel (R^3)
double dx, ///< defining the voxel itself
dy, ///< defining the voxel itself
dz, ///< defining the voxel itself
r2; ///< defining the voxel itself
int splitaxis; ///< defining the kind of splitaxis
KDtreeMeta *child1; ///< pointers to the childs
KDtreeMeta *child2; ///< pointers to the childs
} node;
/**
* in case of leaf node ...
*/
struct {
//! Content is an array of indices to be put into the dynamically aquired data array
Index* p;
} leaf;
};
inline double* point(const DataXYZ* const* pts, const Index& i) const {
return (*pts[i.s])[i.i];
}
void _FindClosest(const DataXYZ* const* pts, int threadNum) const;
};
class KDtreeMetaManaged : public KDtreeMeta {
public:
KDtreeMetaManaged(const vector<Scan*>& scans);
virtual ~KDtreeMetaManaged();
virtual void lock();
virtual void unlock();
//! Aquires cached data first to pass on to the usual KDtree to process
virtual double* FindClosest(double *_p, double maxdist2, int threadNum = 0) const;
private:
Scan** m_scans;
DataXYZ** m_data;
unsigned int m_size;
//! Mutex for safely reducing points just once in a multithreaded environment
boost::mutex m_mutex_locking;
volatile unsigned int m_count_locking;
// constructor initializer list hacks
Index* m_temp_indices;
Index* prepareTempIndices(const vector<Scan*>& scans);
unsigned int getPointsSize(const vector<Scan*>& scans);
};
#endif

@ -0,0 +1,62 @@
/** @file
* @brief The global correction based upon APX transform
*
* @author Andreas Nuechter. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Jan Elseberg. Institute of Computer Science, University of Osnabrueck, Germany.
*/
#ifndef __GAPX6D_H__
#define __GAPX6D_H__
#include <vector>
using std::vector;
#include "graphSlam6D.h"
#include "icp6D.h"
#include "graph.h"
#include "newmat/newmatio.h"
//typedef vector <PtPair> vPtPair; ///< just a typedef: vPtPair = vector of type PtPair
/*
* @brief
*
*/
class gapx6D : public graphSlam6D {
public:
/**
* Constructor (default)
*/
gapx6D() {};
gapx6D(icp6Dminimizer *my_icp6Dminimizer,
double mdm = 25.0,
double max_dist_match = 25.0,
int max_num_iterations = 50,
bool quiet = false,
bool meta = false,
int rnd = 1,
bool eP = true,
int anim = -1,
double epsilonICP = 0.0000001,
int nns_method = simpleKD,
double epsilonLUM = 0.5);
virtual ~gapx6D();
double doGraphSlam6D(Graph gr, vector <Scan*> MetaScan, int nrIt);
static double LUM[4];
private:
double genBArotForLinkedPair(int firstScanNum, int secondScanNum, vPtPair *ptpairs,
double *centroids_m, double *centroids_d, NEWMAT::Matrix *B, NEWMAT::ColumnVector *A);
double genBAtransForLinkedPair(int firstScanNum, int secondScanNum,
double *centroids_m, double *centroids_d,
NEWMAT::SymmetricMatrix *B, NEWMAT::ColumnVector *A, NEWMAT::ColumnVector &X);
};
#endif

@ -0,0 +1,175 @@
#define WANT_STREAM
#define WANT_MATH
#define WANT_FSTREAM
#include "newmatap.h"
#include "newmatio.h"
#include "newmatnl.h"
#ifdef use_namespace
using namespace RBD_LIBRARIES;
#endif
// This is a demonstration of a special case of the Garch model
// Observe two series X and Y of length n
// and suppose
// Y(i) = beta * X(i) + epsilon(i)
// where epsilon(i) is normally distributed with zero mean and variance =
// h(i) = alpha0 + alpha1 * square(epsilon(i-1)) + beta1 * h(i-1).
// Then this program is supposed to estimate beta, alpha0, alpha1, beta1
// The Garch model is supposed to model something like an instability
// in the stock or options market following an unexpected result.
// alpha1 determines the size of the instability and beta1 determines how
// quickly is dies away.
// We should, at least, have an X of several columns and beta as a vector
inline Real square(Real x) { return x*x; }
// the class that defines the GARCH log-likelihood
class GARCH11_LL : public LL_D_FI
{
ColumnVector Y; // Y values
ColumnVector X; // X values
ColumnVector D; // derivatives of loglikelihood
SymmetricMatrix D2; // - approximate second derivatives
int n; // number of observations
Real beta, alpha0, alpha1, beta1;
// the parameters
public:
GARCH11_LL(const ColumnVector& y, const ColumnVector& x)
: Y(y), X(x), n(y.Nrows()) {}
// constructor - load Y and X values
void Set(const ColumnVector& p) // set parameter values
{
para = p;
beta = para(1); alpha0 = para(2);
alpha1 = para(3); beta1 = para(4);
}
bool IsValid(); // are parameters valid
Real LogLikelihood(); // return the loglikelihood
ReturnMatrix Derivatives(); // derivatives of log-likelihood
ReturnMatrix FI(); // Fisher Information matrix
};
bool GARCH11_LL::IsValid()
{ return alpha0>0 && alpha1>0 && beta1>0 && (alpha1+beta1)<1.0; }
Real GARCH11_LL::LogLikelihood()
{
// cout << endl << " ";
// cout << setw(10) << setprecision(5) << beta;
// cout << setw(10) << setprecision(5) << alpha0;
// cout << setw(10) << setprecision(5) << alpha1;
// cout << setw(10) << setprecision(5) << beta1;
// cout << endl;
ColumnVector H(n); // residual variances
ColumnVector U = Y - X * beta; // the residuals
ColumnVector LH(n); // derivative of log-likelihood wrt H
// each row corresponds to one observation
LH(1)=0;
Matrix Hderiv(n,4); // rectangular matrix of derivatives
// of H wrt parameters
// each row corresponds to one observation
// each column to one of the parameters
// Regard Y(1) as fixed and don't include in likelihood
// then put in an expected value of H(1) in place of actual value
// which we don't know. Use
// E{H(i)} = alpha0 + alpha1 * E{square(epsilon(i-1))} + beta1 * E{H(i-1)}
// and E{square(epsilon(i-1))} = E{H(i-1)} = E{H(i)}
Real denom = (1-alpha1-beta1);
H(1) = alpha0/denom; // the expected value of H
Hderiv(1,1) = 0;
Hderiv(1,2) = 1.0 / denom;
Hderiv(1,3) = alpha0 / square(denom);
Hderiv(1,4) = Hderiv(1,3);
Real LL = 0.0; // the log likelihood
Real sum1 = 0; // for forming derivative wrt beta
Real sum2 = 0; // for forming second derivative wrt beta
for (int i=2; i<=n; i++)
{
Real u1 = U(i-1); Real h1 = H(i-1);
Real h = alpha0 + alpha1*square(u1) + beta1*h1; // variance of this obsv.
H(i) = h; Real u = U(i);
LL += log(h) + square(u) / h; // -2 * log likelihood
// Hderiv are derivatives of h with respect to the parameters
// need to allow for h1 depending on parameters
Hderiv(i,1) = -2*u1*alpha1*X(i-1) + beta1*Hderiv(i-1,1); // beta
Hderiv(i,2) = 1 + beta1*Hderiv(i-1,2); // alpha0
Hderiv(i,3) = square(u1) + beta1*Hderiv(i-1,3); // alpha1
Hderiv(i,4) = h1 + beta1*Hderiv(i-1,4); // beta1
LH(i) = -0.5 * (1/h - square(u/h));
sum1 += u * X(i)/ h;
sum2 += square(X(i)) / h;
}
D = Hderiv.t()*LH; // derivatives of likelihood wrt parameters
D(1) += sum1; // add on deriv wrt beta from square(u) term
// cout << setw(10) << setprecision(5) << D << endl;
// do minus expected value of second derivatives
if (wg) // do only if second derivatives wanted
{
Hderiv.Row(1) = 0.0;
Hderiv = H.AsDiagonal().i() * Hderiv;
D2 << Hderiv.t() * Hderiv; D2 = D2 / 2.0;
D2(1,1) += sum2;
// cout << setw(10) << setprecision(5) << D2 << endl;
// DiagonalMatrix DX; EigenValues(D2,DX);
// cout << setw(10) << setprecision(5) << DX << endl;
}
return -0.5 * LL;
}
ReturnMatrix GARCH11_LL::Derivatives()
{ return D; }
ReturnMatrix GARCH11_LL::FI()
{
if (!wg) cout << endl << "unexpected call of FI" << endl;
return D2;
}
int main()
{
// get data
ifstream fin("garch.dat");
if (!fin) { cout << "cannot find garch.dat\n"; exit(1); }
int n; fin >> n; // series length
// Y contains the dependant variable, X the predictor variable
ColumnVector Y(n), X(n);
int i;
for (i=1; i<=n; i++) fin >> Y(i) >> X(i);
cout << "Read " << n << " data points - begin fit\n\n";
// now do the fit
ColumnVector H(n);
GARCH11_LL garch11(Y,X); // loglikehood "object"
MLE_D_FI mle_d_fi(garch11,100,0.0001); // mle "object"
ColumnVector Para(4); // to hold the parameters
Para << 0.0 << 0.1 << 0.1 << 0.1; // starting values
// (Should change starting values to a more intelligent formula)
mle_d_fi.Fit(Para); // do the fit
ColumnVector SE;
mle_d_fi.GetStandardErrors(SE);
cout << "\n\n";
cout << "estimates and standard errors\n";
cout << setw(15) << setprecision(5) << (Para | SE) << endl << endl;
SymmetricMatrix Corr;
mle_d_fi.GetCorrelations(Corr);
cout << "correlation matrix\n";
cout << setw(10) << setprecision(2) << Corr << endl << endl;
cout << "inverse of correlation matrix\n";
cout << setw(10) << setprecision(2) << Corr.i() << endl << endl;
return 0;
}

@ -0,0 +1,152 @@
/*
* frames2riegl implementation
*
* Copyright (C) Dorit Borrmann
*
* Released under the GPL version 3.
*
*/
#include <fstream>
#include <iostream>
using std::cout;
using std::cerr;
using std::endl;
using std::ifstream;
using std::ofstream;
#include "slam6d/globals.icc"
#include <string.h>
#ifndef _MSC_VER
#include <unistd.h>
#else
#include "XGetopt.h"
#endif
#if WIN32
#define snprintf sprintf_s
#endif
int parseArgs(int argc,char **argv, char dir[255], int& start, int& end){
start = 0;
end = -1; // -1 indicates no limitation
int c;
// from unistd.h
extern char *optarg;
extern int optind;
cout << endl;
while ((c = getopt (argc, argv, "s:e:")) != -1)
switch (c)
{
case 's':
start = atoi(optarg);
if (start < 0) { cerr << "Error: Cannot start at a negative scan number.\n"; exit(1); }
break;
case 'e':
end = atoi(optarg);
if (end < 0) { cerr << "Error: Cannot end at a negative scan number.\n"; exit(1); }
if (end < start) { cerr << "Error: <end> cannot be smaller than <start>.\n"; exit(1); }
break;
}
if (optind != argc-1) {
cerr << "\n*** Directory missing ***\n" << endl;
cout << endl
<< "Usage: " << argv[0] << " [-s NR] [-e NR] directory" << endl << endl;
cout << " -s NR start at scan NR (i.e., neglects the first NR scans)" << endl
<< " [ATTENTION: counting starts with 0]" << endl
<< " -e NR end after scan NR" << "" << endl
<< endl;
cout << "Reads frame files from directory/scan???.frames and converts them to directory/scan???.4x4 in the RIEGL pose file format." << endl;
abort();
}
strncpy(dir,argv[optind],255);
#ifndef _MSC_VER
if (dir[strlen(dir)-1] != '/') strcat(dir,"/");
#else
if (dir[strlen(dir)-1] != '\\') strcat(dir,"\\");
#endif
return 0;
}
int main(int argc, char **argv)
{
int start = 0, end = -1;
char dir[255];
parseArgs(argc, argv, dir, start, end);
int fileCounter = start;
char poseFileName[255];
char frameFileName[255];
ifstream pose_in;
ofstream pose_out;
double inMatrix[16];
double tMatrix[17];
for (;;) {
if (end > -1 && fileCounter > end) break; // 'nuf read
snprintf(frameFileName,255,"%sscan%.3d.frames",dir,fileCounter);
snprintf(poseFileName,255,"%sscan%.3d.4x4",dir,fileCounter++);
pose_in.open(frameFileName);
if (!pose_in.good()) break; // no more files in the directory
// read 3D scan
cout << "Reading frame " << frameFileName << "..." << endl;
while(pose_in.good()) {
for (unsigned int i = 0; i < 17; pose_in >> tMatrix[i++]);
}
inMatrix[5] = tMatrix[0];
inMatrix[9] = -tMatrix[1];
inMatrix[1] = -tMatrix[2];
inMatrix[13] = -tMatrix[3];
inMatrix[6] = -tMatrix[4];
inMatrix[10] = tMatrix[5];
inMatrix[2] = tMatrix[6];
inMatrix[14] = tMatrix[7];
inMatrix[4] = -tMatrix[8];
inMatrix[8] = tMatrix[9];
inMatrix[0] = tMatrix[10];
inMatrix[12] = tMatrix[11];
inMatrix[7] = -tMatrix[12];
inMatrix[11] = tMatrix[13];
inMatrix[3] = tMatrix[14];
inMatrix[15] = tMatrix[15];
inMatrix[3] /= 100;
inMatrix[7] /= 100;
inMatrix[11] /= 100;
pose_in.close();
pose_in.clear();
pose_out.open(poseFileName);
cout << "Writing Riegl pose... " << poseFileName << endl;
for (int i=0; i < 16; i++) {
pose_out << inMatrix[i] << " ";
if((i % 4) == 3) pose_out << endl;
}
pose_out.close();
pose_out.clear();
cout << " done." << endl;
}
}

@ -0,0 +1,49 @@
SET(SHOW_LIBS ${OPENGL_LIBRARIES} glui scan ANN)
IF(WIN32)
IF( CMAKE_SIZEOF_VOID_P EQUAL 8 )
SET(SHOW_LIBS ${SHOW_LIBS} ${CMAKE_SOURCE_DIR}/3rdparty/windows/x64/freeglut.lib XGetopt)
ELSE( CMAKE_SIZEOF_VOID_P EQUAL 8 )
SET(SHOW_LIBS ${SHOW_LIBS} ${CMAKE_SOURCE_DIR}/3rdparty/windows/freeglut.lib XGetopt)
ENDIF(CMAKE_SIZEOF_VOID_P EQUAL 8 )
ENDIF(WIN32)
IF (UNIX)
SET(SHOW_LIBS newmat dl ${GLUT_LIBRARIES} ${SHOW_LIBS})
ENDIF(UNIX)
IF(WITH_VELOSLAM)
add_executable(veloslam veloslam.cc veloscan.cc debugview.cc pcddump.cc tracker.cc
trackermanager.cc drawtrackers.cc kalmanfilter.cc matrix.cc lap.cc)
IF(UNIX)
target_link_libraries(veloslam dl scan newmat sparse ANN ${Boost_LIBRARIES} ${SHOW_LIBS})
ENDIF(UNIX)
IF(WIN32)
target_link_libraries(veloslam scan newmat sparse ANN XGetopt ${Boost_LIBRARIES} ${SHOW_LIBS})
ENDIF(WIN32)
ENDIF(WITH_VELOSLAM)
#IF(WITH_VELOSLAM)
# SET(SHOW_SRCS ../show/NurbsPath.cc ../show/PathGraph.cc ../show/vertexarray.cc
# ../show/viewcull.cc ../show/colormanager.cc ../show/compacttree.cc
# ../show/scancolormanager.cc ../show/display.cc)
# add_executable(veloshow veloshow.cc veloscan.cc
# debugview.cc pcddump.cc cluster_classification.cc
# tracker.cc trackermanager.cc drawtrackers.cc
# svm.cc clusterboundingbox.cc multiscan_random_field.cc
# kalmanfilter.cc matrix.cc lap.cc
# intersection_detection.cc SegIter.model ${SHOW_SRCS})
#IF(UNIX)
# target_link_libraries(veloshow dl scan newmat sparse ANN ${SHOW_LIBS})
#ENDIF(UNIX)
#IF(WIN32)
# target_link_libraries(veloshow scan newmat sparse ANN XGetopt ${Boost_LIBRARIES} ${SHOW_LIBS})
#ENDIF(WIN32)
#ENDIF(WITH_VELOSLAM)

@ -0,0 +1,46 @@
// =====================================================================================
//
// Filename: sickday.h
//
// Description:
//
// Version: 1.0
// Created: 09/26/2010 02:08:25 AM
// Revision: none
// Compiler: g++
//
// Author: Jan Elseberg (), jelseber@uos.de
// Company: Universitaet Osnabrueck
//
// =====================================================================================
const int MIN_NR_PTS = 1200;
const double IMG_RES = 2.0; // in cm
const int BOARD_SIZE_X = 59.40 / IMG_RES; // number of pixels wide
const int BOARD_SIZE_Z = 84.10 / IMG_RES; // number of pixels high
const int WHITE_BORDER = 4; // number of pixels on the border to whiten. 10 cm ?
const double MINREFL = -10.0;
const double MAXREFL = 10.0;
const double REFL_THRESHOLD = (0.0 - MINREFL ) / ( MAXREFL - MINREFL); // threshold for binarizing image
const double MAX_DIST_TO_PLANE = 10.0; // RANSAC max distance to plane
const double MIN_SCORE = 0.65; // minimal score for accepting the board hypothesis (between 0 and 1)
const double SCORE_SCALE = 0.50; // score is scaled so that SCORE_SCALE is probability 0
/////////////// constants for OCR
const string OCRRESULT = "/tmp/ocrresult.txt";
const string OCRERROR = "/tmp/ocrerr.txt";
/////////////// number (except 1) are usually 17,27 pixel wide,high
//
const int MIN_NR_WIDTH = 28.0 / IMG_RES; // 14 pixel ? All Numbers except 1 must at least be this wide
const int MIN_1_WIDTH = 16.0 / IMG_RES; // 8 pixel ? Number 1 must at least be this wide
const int MIN_NR_HEIGHT = 46.0 / IMG_RES; // 23 pixel ? Numbers must at least be this high
const int MAX_NR_WIDTH = 42.0 / IMG_RES; // 21 pixel ? All Numbers must at most be this wide
const int MAX_NR_HEIGHT = 62.0 / IMG_RES; // 31 pixel ? Numbers must at most be this high

@ -0,0 +1,220 @@
/*
* scan_io_riegl_rgb implementation
*
* Copyright (C) Thomas Escher, Kai Lingemann, Andreas Nuechter
*
* Released under the GPL version 3.
*
*/
/**
* @file
* @brief Implementation of reading 3D scans
* @author Kai Lingemann. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Andreas Nuechter. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Thomas Escher
*/
#include "scanio/scan_io_riegl_rgb.h"
#include <iostream>
using std::cout;
using std::cerr;
using std::endl;
#include <vector>
#ifdef _MSC_VER
#include <windows.h>
#endif
#include <boost/filesystem/operations.hpp>
#include <boost/filesystem/fstream.hpp>
using namespace boost::filesystem;
#include "slam6d/globals.icc"
#define DATA_PATH_PREFIX "scan"
#define DATA_PATH_SUFFIX ".rgb"
#define POSE_PATH_PREFIX "scan"
#define POSE_PATH_SUFFIX ".dat"
std::list<std::string> ScanIO_riegl_rgb::readDirectory(const char* dir_path, unsigned int start, unsigned int end)
{
std::list<std::string> identifiers;
for(unsigned int i = start; i <= end; ++i) {
// identifier is /d/d/d (000-999)
std::string identifier(to_string(i,3));
// scan consists of data (.3d) and pose (.pose) files
path data(dir_path);
data /= path(std::string(DATA_PATH_PREFIX) + identifier + DATA_PATH_SUFFIX);
path pose(dir_path);
pose /= path(std::string(POSE_PATH_PREFIX) + identifier + POSE_PATH_SUFFIX);
// stop if part of a scan is missing or end by absence is detected
if(!exists(data) || !exists(pose))
break;
identifiers.push_back(identifier);
}
return identifiers;
}
void ScanIO_riegl_rgb::readPose(const char* dir_path, const char* identifier, double* pose)
{
unsigned int i;
path pose_path(dir_path);
pose_path /= path(std::string(POSE_PATH_PREFIX) + identifier + POSE_PATH_SUFFIX);
if(!exists(pose_path))
throw std::runtime_error(std::string("There is no pose file for [") + identifier + "] in [" + dir_path + "]");
// open pose file
ifstream pose_file(pose_path);
// if the file is open, read contents
if(pose_file.good()) {
double rPos[3], rPosTheta[16];
double inMatrix[16], tMatrix[16];
for (i = 0; i < 16; ++i)
pose_file >> inMatrix[i];
pose_file.close();
// transform input pose
tMatrix[0] = inMatrix[5];
tMatrix[1] = -inMatrix[9];
tMatrix[2] = -inMatrix[1];
tMatrix[3] = -inMatrix[13];
tMatrix[4] = -inMatrix[6];
tMatrix[5] = inMatrix[10];
tMatrix[6] = inMatrix[2];
tMatrix[7] = inMatrix[14];
tMatrix[8] = -inMatrix[4];
tMatrix[9] = inMatrix[8];
tMatrix[10] = inMatrix[0];
tMatrix[11] = inMatrix[12];
tMatrix[12] = -inMatrix[7];
tMatrix[13] = inMatrix[11];
tMatrix[14] = inMatrix[3];
tMatrix[15] = inMatrix[15];
Matrix4ToEuler(tMatrix, rPosTheta, rPos);
pose[0] = 100*rPos[0];
pose[1] = 100*rPos[1];
pose[2] = 100*rPos[2];
pose[3] = rPosTheta[0];
pose[4] = rPosTheta[1];
pose[5] = rPosTheta[2];
} else {
throw std::runtime_error(std::string("Pose file could not be opened for [") + identifier + "] in [" + dir_path + "]");
}
}
bool ScanIO_riegl_rgb::supports(IODataType type)
{
return !!(type & (DATA_XYZ | DATA_RGB | DATA_REFLECTANCE));
}
void ScanIO_riegl_rgb::readScan(const char* dir_path, const char* identifier, PointFilter& filter, std::vector<double>* xyz, std::vector<unsigned char>* rgb, std::vector<float>* reflectance, std::vector<float>* amplitude, std::vector<int>* type, std::vector<float>* deviation)
{
unsigned int i;
// error handling
path data_path(dir_path);
data_path /= path(std::string(DATA_PATH_PREFIX) + identifier + DATA_PATH_SUFFIX);
if(!exists(data_path))
throw std::runtime_error(std::string("There is no scan file for [") + identifier + "] in [" + dir_path + "]");
if(xyz != 0 || rgb != 0 || reflectance != 0) {
// open data file
ifstream data_file(data_path);
data_file.exceptions(ifstream::eofbit|ifstream::failbit|ifstream::badbit);
// read the point count
unsigned int count;
data_file >> count;
// reserve enough space for faster reading
if(xyz != 0) xyz->reserve(3*count);
if(rgb != 0) rgb->reserve(3*count);
// read points
// z x y range theta phi r g b reflectance
double point[7];
unsigned int color[3];
double tmp;
while(data_file.good()) {
try {
for(i = 0; i < 6; ++i) data_file >> point[i];
for(i = 0; i < 3; ++i) data_file >> color[i];
data_file >> point[6];
} catch(std::ios_base::failure& e) {
break;
}
// the enemy's x/y/z is mapped to slam's z/x/y, shuffle time!
// invert x axis
// convert coordinate to cm
tmp = point[2];
point[2] = 100.0 * point[0];
point[0] = -100.0 * point[1];
point[1] = 100.0 * tmp;
// apply filter and insert point
if(filter.check(point)) {
if(xyz != 0) {
for(i = 0; i < 3; ++i) xyz->push_back(point[i]);
}
if(rgb != 0) {
for(i = 0; i < 3; ++i) rgb->push_back(
static_cast<unsigned char>(color[i]));
}
if(reflectance != 0) {
reflectance->push_back(point[6]);
}
}
}
data_file.close();
}
}
/**
* class factory for object construction
*
* @return Pointer to new object
*/
#ifdef _MSC_VER
extern "C" __declspec(dllexport) ScanIO* create()
#else
extern "C" ScanIO* create()
#endif
{
return new ScanIO_riegl_rgb;
}
/**
* class factory for object construction
*
* @return Pointer to new object
*/
#ifdef _MSC_VER
extern "C" __declspec(dllexport) void destroy(ScanIO *sio)
#else
extern "C" void destroy(ScanIO *sio)
#endif
{
delete sio;
}
#ifdef _MSC_VER
BOOL APIENTRY DllMain(HANDLE hModule, DWORD dwReason, LPVOID lpReserved)
{
return TRUE;
}
#endif

@ -0,0 +1,132 @@
#
# Makefile for ./src path, used by configure
#
EXEEXT = @EXEEXT@
PROGRAM = gocr$(EXEEXT)
# lib removed for simplification (v0.46)
# but Igor from OSRA an optical chemical structure recognition software
# wants it (v0.47 Mar09)
PGMASCLIB = Pgm2asc
#LIBPGMASCLIB = lib$(PGMASCLIB).a
# ToDo: need a better pgm2asc.h for lib users
#INCLUDEFILES = gocr.h
# avoid german compiler messages
LANG=C
LIBOBJS=pgm2asc.o \
box.o \
database.o \
detect.o \
barcode.o \
lines.o \
list.o \
ocr0.o \
ocr0n.o \
ocr1.o \
otsu.o \
output.o \
pixel.o \
unicode.o \
remove.o \
pnm.o \
pcx.o \
progress.o \
job.o
# these two lines are for cross-compiling, not tested
#srcdir = @srcdir@
#VPATH = @srcdir@
bindir = @bindir@
# lib removed for simplification
#libdir = @libdir@
#includedir = @includedir@
CC=@CC@
# lib removed for simplification
# ar,ranlib detection removed from configure (simplicity)
# but needed by some developpers (linux only) for for (make libs)
# RANLIB = @RANLIB@
# AR = @AR@
RANLIB = ranlib
AR = ar
INSTALL=@INSTALL@
# shell is needed for OS/2 to let if test -r $(PROGRAM) ... work
SHELL=@SHELL@
DEFS=@DEFS@
CPPFLAGS=@CPPFLAGS@
# to see the config.h
CFLAGS=@CFLAGS@ $(CPPFLAGS) -I../include $(DEFS)
LDFLAGS=@LDFLAGS@
LIBS=@LIBS@
DESTDIR=@prefix@
.SUFFIXES: .s .o .c .h
# do not look for files if help (etc) is given
.PHONY : doc clean install libs default
.c.o: gocr.h pgm2asc.h ../include/config.h
$(CC) $(CFLAGS) -c -o $*.o $<
default: all
# all: $(PROGRAM) lib$(PGMASCLIB).a
all: $(PROGRAM)
gocr.o: gocr.h Makefile ../include/version.h
.c.h:
#$(PROGRAM): lib$(PGMASCLIB).a gocr.o
$(PROGRAM): $(LIBOBJS) gocr.o
# make it conform to ld --as-needed
#$(CC) -o $@ $(LDFLAGS) gocr.o ./lib$(PGMASCLIB).a $(LIBS)
$(CC) -o $@ $(LDFLAGS) gocr.o $(LIBOBJS) $(LIBS)
if test -r $(PROGRAM); then cp $@ ../bin; fi
libs: lib$(PGMASCLIB).a lib$(PGMASCLIB).@PACKAGE_VERSION@.so
lib$(PGMASCLIB).@PACKAGE_VERSION@.so: $(LIBOBJS)
$(CC) -fPIC -shared -Wl,-h$@ -o $@ $(LIBOBJS)
-ln -s $@ lib$(PGMASCLIB).so
lib$(PGMASCLIB).a: $(LIBOBJS)
# -rm -f $@
$(AR) cru $@ $(LIBOBJS)
$(RANLIB) $@
$(LIBOBJS): Makefile
# PHONY = don't look at file clean, -rm = start rm and ignore errors
.PHONY : clean proper install uninstall
install: all
#$(INSTALL) -d $(DESTDIR)$(bindir) $(DESTDIR)$(libdir) $(DESTDIR)$(includedir)
$(INSTALL) -d $(DESTDIR)$(bindir)
$(INSTALL) ../bin/$(PROGRAM) $(DESTDIR)$(bindir)
$(INSTALL) ../bin/gocr.tcl $(DESTDIR)$(bindir) # better X11/bin?
if test -f lib$(PGMASCLIB).a; then\
$(INSTALL) lib$(PGMASCLIB).a $(DESTDIR)$(libdir);\
$(INSTALL) lib$(PGMASCLIB).@PACKAGE_VERSION@.so $(DESTDIR)$(libdir);\
$(INSTALL) lib$(PGMASCLIB).so $(DESTDIR)$(libdir);\
fi
# ToDo: not sure that the link will be installed correctly
#$(INSTALL) $(INCLUDEFILES) $(DESTDIR)$(includedir)
# directories are not removed
uninstall:
-rm -f $(DESTDIR)$(bindir)/$(PROGRAM)
-rm -f $(DESTDIR)$(bindir)/gocr.tcl
-rm -f $(DESTDIR)$(libdir)/lib$(PGMASCLIB).a
-rm -f $(DESTDIR)$(libdir)/lib$(PGMASCLIB).@PACKAGE_VERSION@.so
-rm -f $(DESTDIR)$(libdir)/lib$(PGMASCLIB).so
# ToDo: set to old version.so ?
#for X in $(INCLUDEFILES); do rm -f $(DESTDIR)$(includedir)/$$X; done
clean:
-rm -f *.o *~
proper: clean
-rm -f gocr libPgm2asc.*
-rm -f gocr

@ -0,0 +1,144 @@
svm_type c_svc
kernel_type rbf
gamma 0.0625
nr_class 2
total_sv 133
rho -0.261596
label 1 -1
probA -5.01585
probB 0.275821
nr_sv 80 53
SV
0.4753545542788266 1:0.1667 2:0.1667 3:0.1667 4:0.1833 5:0.1833 6:0.1833 7:0.1833 8:0.1833 9:0.2 10:0.2 11:0.2 12:0.25 13:0.25 14:0.3333 15:0.3333 16:0.3833 17:0.4167 18:0.55 19:0.5833 20:0.5833 21:0.5833 22:0.45 23:0.45 24:0.45 25:0.45 26:0.45 27:0.45 28:0.4167 29:0.3667 30:0.3667 31:0.35 32:0.3333 33:0.3333 34:0.3167 35:0.3333 36:0.3333 37:0.3167 38:0.3333 39:0.3333 40:0.3167 41:0.3333 42:0.3167 43:0.3167 44:0.3167 45:0.3167 46:0.1667 47:0.15 48:0.1667 49:0.1667 50:0.1667 51:0.1667 52:0.1667 53:0.1667 54:0.15 55:0.15 56:0.1333 57:0.1333 58:0.1333 59:0.1333 60:0.1333 61:0.1333 62:0.1333 63:0.15 64:0.15 65:0.1333 66:0.1333 67:0.1333 68:0.1333 69:0.15 70:0.15 71:0.15 72:0.1333 73:0.1333 74:0.1333 75:0.15 76:0.15 77:0.15 78:0.1333 79:0.1333 80:0.1333 81:0.1333 82:0.1333 83:0.1333 84:0.1333 85:0.1333 86:0.1333 87:0.1333 88:0.15 89:0.3 90:0.4667 91:1 92:1 93:1 94:1 95:1 96:1 97:0.9833 98:0.75 99:0.7333 100:0.6167 101:0.5167 102:0.5167 103:0.5167 104:0.4 105:0.4 106:0.4 107:0.4 108:0.4 109:0.4 110:0.4 111:0.2667 112:0.25 113:0.25 114:0.25 115:0.25 116:0.25 117:0.25 118:0.25 119:0.25 120:0.25 121:0.25 122:0.25 123:0.25 124:0.25 125:0.25 126:0.25 127:0.25 128:0.25 129:0.25 130:0.25 131:0.25 132:0.2667 133:0.1333 134:0.1333 135:0.1333 136:0.1333 137:0.1333 138:0.1333 139:0.1333 140:0.15 141:0.1333 142:0.087684211 143:0.087684211 144:0.087684211 145:0.10526316 146:0.10526316 147:0.10526316 148:0.087684211 149:0.087684211 150:0.087684211 151:0.087684211 152:0.10526316 153:0.10526316 154:0.087684211 155:0.087684211 156:0.087684211 157:0.071389541 158:0.071389541 159:0.071389541 160:0.071389541 161:0.071389541 162:0.071389541 163:0.071389541 164:0.071389541 165:0.089282462 166:0.089282462 167:0.14285408 168:0.14285408 169:0.14285408 170:0.14285408 171:0.14285408 172:0.12496116 173:0.089282462 174:0.089282462 175:0.089282462 176:0.089282462 177:0.089282462 178:0.089282462 179:0.089282462 180:0.089282462 181:0.089282462 182:0.089282462 183:0.089282462 184:0.089282462 185:0.053603763 186:0.053603763 187:0.053603763 188:0.053603763 189:0.053603763 190:0.053603763 191:0.053603763 192:0.053603763 193:0.053603763 194:0.053603763 195:0.053603763 196:0.071389541 197:0.071389541 198:0.071389541 199:0.071389541 200:0.053603763 201:0.053603763 202:0.071389541 203:0.071389541 204:0.071389541 205:0.071389541 206:0.071389541 207:0.053603763 208:0.053603763 209:0.053603763 210:0.071389541 211:0.071389541 212:0.071389541 213:0.053603763 214:0.053603763 215:0.053603763 216:0.053603763 217:0.053603763 218:0.053603763 219:0.053603763 220:0.071389541 221:0.1333 222:0.1333 223:0.2167 224:0.2167 225:0.2333 226:0.2333 227:0.2333 228:0.2667 229:0.2667 230:0.2667 231:0.2667 232:0.2667 233:0.2667 234:0.2667 235:0.2667 236:0.2667 237:0.2667 238:0.2667 239:0.2667 240:0.2667 241:0.2667 242:0.2667 243:0.2667 244:0.2667 245:0.2667 246:0.2667 247:0.2667 248:0.2667 249:0.2667 250:0.2667 251:0.2667 252:0.2833 253:0.4167 254:0.4167 255:0.4167 256:0.55 257:0.55 258:0.55 259:0.55 260:0.5667 261:0.7167 262:0.7167 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:0.9833 272:0.4667 273:0.4667 274:0.15 275:0.1333 276:0.1333 277:0.1333 278:0.1333 279:0.1333 280:0.1333 281:0.1333 282:0.1333 283:0.1333 284:0.1333 285:0.15 286:0.15 287:0.15 288:0.1333 289:0.1333 290:0.1333 291:0.1167 292:0.1167 293:0.1167 294:0.1167 295:0.1333 296:0.1333 297:0.1333 298:0.1167 299:0.1167 300:0.1167 301:0.1167 302:0.1167 303:0.1167 304:0.1167 305:0.1167 306:0.1167 307:0.1167 308:0.1167 309:0.1167 310:0.1167 311:0.1333 312:0.1333 313:0.1167 314:0.1167 315:0.1167 316:0.1167 317:0.1167 318:0.1333 319:0.1167 320:0.1167 321:0.1167 322:0.1167 323:0.1167 324:0.1167 325:0.1167 326:0.1333 327:0.1167 328:0.1167 329:0.1167 330:0.1167 331:0.1167 332:0.1167 333:0.1167 334:0.1333 335:0.1333 336:0.1333 337:0.1333 338:0.1333 339:0.1333 340:0.1333 341:0.1333 342:0.1333 343:0.1333 344:0.1333 345:0.15 346:0.15 347:0.15 348:0.15 349:0.15 350:0.15 351:0.1333 352:0.15 353:0.15 354:0.15 355:0.15 356:0.15 357:0.15 358:0.15 359:0.1667 360:0.1667
2 1:0.2167 2:0.2167 3:0.2167 4:0.2333 5:0.2333 6:0.2333 7:0.2667 8:0.2667 9:0.2667 10:0.3667 11:0.3667 12:0.3667 13:0.3833 14:0.3833 15:0.4667 16:0.6167 17:0.6167 18:0.4833 19:0.4667 20:0.4667 21:0.4667 22:0.4667 23:0.4667 24:0.4667 25:0.4667 26:0.3667 27:0.3667 28:0.35 29:0.3333 30:0.35 31:0.35 32:0.35 33:0.1667 34:0.1667 35:0.1667 36:0.1667 37:0.1667 38:0.1667 39:0.1667 40:0.1667 41:0.1667 42:0.1667 43:0.1667 44:0.1667 45:0.1667 46:0.1667 47:0.15 48:0.15 49:0.15 50:0.15 51:0.15 52:0.15 53:0.15 54:0.15 55:0.15 56:0.15 57:0.15 58:0.15 59:0.1667 60:0.15 61:0.15 62:0.15 63:0.15 64:0.15 65:0.15 66:0.15 67:0.15 68:0.15 69:0.15 70:0.15 71:0.15 72:0.15 73:0.15 74:0.15 75:0.15 76:0.15 77:0.1667 78:0.3 79:0.3 80:0.3 81:0.3 82:0.3 83:0.3 84:0.3667 85:0.45 86:0.6 87:0.6 88:0.9333 89:1 90:1 91:1 92:1 93:1 94:1 95:0.95 96:0.7 97:0.5833 98:0.6 99:0.5833 100:0.3833 101:0.3833 102:0.3833 103:0.3833 104:0.3833 105:0.2333 106:0.2167 107:0.2167 108:0.2167 109:0.2167 110:0.2167 111:0.2167 112:0.2167 113:0.2167 114:0.2333 115:0.2167 116:0.2167 117:0.2167 118:0.2333 119:0.2167 120:0.2167 121:0.2167 122:0.2167 123:0.2167 124:0.2167 125:0.1 126:0.1 127:0.1 128:0.1 129:0.1 130:0.1 131:0.1 132:0.1 133:0.1 134:0.1 135:0.1 136:0.1 137:0.1 138:0.1 139:0.1 140:0.1 141:0.1 142:0.052631579 143:0.052631579 144:0.052631579 145:0.052631579 146:0.052631579 147:0.052631579 148:0.052631579 149:0.052631579 150:0.052631579 151:0.052631579 152:0.052631579 153:0.052631579 154:0.052631579 155:0.052631579 156:0.052631579 157:0.035710842 158:0.035710842 159:0.035710842 160:0.035710842 161:0.035710842 162:0.035710842 163:0.035710842 164:0.035710842 165:0.035710842 166:0.035710842 167:0.035710842 168:0.035710842 169:0.053603763 170:0.089282462 171:0.089282462 172:0.089282462 173:0.089282462 174:0.089282462 175:0.089282462 176:0.089282462 177:0.089282462 178:0.089282462 179:0.089282462 180:0.089282462 181:0.089282462 182:0.089282462 183:0.089282462 184:0.089282462 185:0.089282462 186:0.089282462 187:0.089282462 188:0.089282462 189:0.089282462 190:0.089282462 191:0.089282462 192:0.089282462 193:0.089282462 194:0.035710842 195:0.035710842 196:0.035710842 197:0.035710842 198:0.035710842 199:0.035710842 200:0.035710842 201:0.035710842 202:0.035710842 203:0.035710842 204:0.035710842 205:0.035710842 206:0.035710842 207:0.035710842 208:0.035710842 209:0.035710842 210:0.035710842 211:0.035710842 212:0.035710842 213:0.035710842 214:0.035710842 215:0.035710842 216:0.035710842 217:0.035710842 218:0.035710842 219:0.035710842 220:0.035710842 221:0.1 222:0.1 223:0.1 224:0.1 225:0.1 226:0.1 227:0.1 228:0.1 229:0.1 230:0.1 231:0.1 232:0.1 233:0.1 234:0.1 235:0.1 236:0.1 237:0.1 238:0.2167 239:0.2167 240:0.2 241:0.2667 242:0.2667 243:0.2 244:0.2 245:0.2667 246:0.2667 247:0.2667 248:0.2667 249:0.2667 250:0.2667 251:0.2667 252:0.2667 253:0.2667 254:0.2667 255:0.2667 256:0.2667 257:0.2667 258:0.2667 259:0.4167 260:0.4167 261:0.5667 262:0.5667 263:0.5667 264:0.7167 265:0.7167 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:0.9833 274:0.8333 275:0.6667 276:0.4833 277:0.4833 278:0.4833 279:0.4833 280:0.4667 281:0.4333 282:0.3833 283:0.3667 284:0.1833 285:0.1667 286:0.1667 287:0.1667 288:0.1667 289:0.1667 290:0.1667 291:0.1667 292:0.1667 293:0.1667 294:0.1667 295:0.1667 296:0.1667 297:0.1667 298:0.1667 299:0.1667 300:0.15 301:0.15 302:0.15 303:0.1667 304:0.1667 305:0.1667 306:0.15 307:0.15 308:0.15 309:0.15 310:0.15 311:0.1667 312:0.15 313:0.1667 314:0.15 315:0.1667 316:0.1667 317:0.15 318:0.15 319:0.1667 320:0.15 321:0.1667 322:0.15 323:0.15 324:0.15 325:0.15 326:0.15 327:0.1667 328:0.1667 329:0.1667 330:0.15 331:0.15 332:0.15 333:0.1667 334:0.1667 335:0.1667 336:0.1667 337:0.1667 338:0.1667 339:0.15 340:0.1667 341:0.1667 342:0.1667 343:0.1667 344:0.1667 345:0.1667 346:0.1667 347:0.1667 348:0.1833 349:0.1833 350:0.1833 351:0.1833 352:0.1667 353:0.1667 354:0.2 355:0.2 356:0.2 357:0.2 358:0.2 359:0.2167 360:0.2167
2 1:0.2833 2:0.2833 3:0.3833 4:0.3833 5:0.3833 6:0.3833 7:0.4 8:0.4 9:0.4 10:0.4833 11:0.4833 12:0.5333 13:0.5667 14:0.6 15:0.45 16:0.4333 17:0.45 18:0.4333 19:0.45 20:0.3333 21:0.1167 22:0.1167 23:0.1167 24:0.1167 25:0.1333 26:0.1333 27:0.1333 28:0.1167 29:0.1167 30:0.1167 31:0.1167 32:0.1167 33:0.1167 34:0.1167 35:0.1 36:0.1 37:0.1167 38:0.1167 39:0.1167 40:0.1167 41:0.1167 42:0.1167 43:0.1167 44:0.1167 45:0.1167 46:0.1167 47:0.1167 48:0.1167 49:0.1167 50:0.1167 51:0.1167 52:0.1167 53:0.1167 54:0.1167 55:0.1167 56:0.1167 57:0.1167 58:0.1167 59:0.1167 60:0.1167 61:0.1167 62:0.1167 63:0.1167 64:0.1167 65:0.1167 66:0.1167 67:0.1 68:0.1 69:0.1167 70:0.1167 71:0.1167 72:0.25 73:0.25 74:0.25 75:0.25 76:0.25 77:0.25 78:0.25 79:0.25 80:0.25 81:0.25 82:0.2667 83:0.25 84:0.25 85:0.25 86:0.3167 87:0.8833 88:0.8833 89:1 90:1 91:1 92:1 93:1 94:1 95:0.9 96:0.6667 97:0.55 98:0.55 99:0.55 100:0.3667 101:0.35 102:0.35 103:0.35 104:0.35 105:0.35 106:0.35 107:0.35 108:0.35 109:0.1833 110:0.1833 111:0.1833 112:0.35 113:0.35 114:0.1833 115:0.1833 116:0.2 117:0.3833 118:0.4 119:0.1833 120:0.2 121:0.2 122:0.3833 123:0.1833 124:0.1833 125:0.1833 126:0.4 127:0.3833 128:0.1833 129:0.1833 130:0.1833 131:0.2167 132:0.2167 133:0.2167 134:0.1833 135:0.1833 136:0.1833 137:0.1833 138:0.1833 139:0.1667 140:0.08333 141:0.08333 142:0.035084211 143:0.035084211 144:0.035084211 145:0.035084211 146:0.035084211 147:0.035084211 148:0.035084211 149:0.035084211 150:0.035084211 151:0.035084211 152:0.035084211 153:0.035084211 154:0.035084211 155:0.035084211 156:0.035084211 157:0.017850064 158:0.017850064 159:0.017850064 160:0.017850064 161:0.017850064 162:0.017850064 163:0.017850064 164:0.017850064 165:0.017850064 166:0.017850064 167:0.017850064 168:0.017850064 169:0.017850064 170:0.017850064 171:0.017850064 172:0.017850064 173:0.017850064 174:0.017850064 175:0.017850064 176:0.017850064 177:0.017850064 178:0.017850064 179:0.017850064 180:0.017850064 181:0.017850064 182:0.017850064 183:0.017850064 184:0.017850064 185:0.017850064 186:0.017850064 187:0.017850064 188:0.017850064 189:0.017850064 190:0.017850064 191:0.017850064 192:0.017850064 193:0.017850064 194:0.017850064 195:0.089282462 196:0.089282462 197:0.089282462 198:0.089282462 199:0.089282462 200:0.089282462 201:0.089282462 202:0.089282462 203:0.089282462 204:0.089282462 205:0.089282462 206:0.089282462 207:0.089282462 208:0.089282462 209:0.089282462 210:0.089282462 211:0.089282462 212:0.089282462 213:0.089282462 214:0.089282462 215:0.089282462 216:0.089282462 217:0.089282462 218:0.089282462 219:0.089282462 220:0.089282462 221:0.15 222:0.15 223:0.15 224:0.15 225:0.15 226:0.15 227:0.15 228:0.15 229:0.15 230:0.15 231:0.15 232:0.15 233:0.15 234:0.15 235:0.15 236:0.15 237:0.15 238:0.15 239:0.15 240:0.15 241:0.15 242:0.15 243:0.2 244:0.2 245:0.3 246:0.3 247:0.3 248:0.3 249:0.3 250:0.3 251:0.3 252:0.3 253:0.3 254:0.3 255:0.3 256:0.3 257:0.3 258:0.3667 259:0.3667 260:0.3833 261:0.45 262:0.4667 263:0.6 264:0.6167 265:0.7333 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:0.8 275:0.7 276:0.5333 277:0.5333 278:0.5333 279:0.5333 280:0.4667 281:0.4333 282:0.2167 283:0.2 284:0.2 285:0.2 286:0.2 287:0.2 288:0.2 289:0.2 290:0.2 291:0.2 292:0.2 293:0.2 294:0.1833 295:0.1833 296:0.1833 297:0.1833 298:0.1833 299:0.1833 300:0.1833 301:0.1833 302:0.1833 303:0.1833 304:0.1833 305:0.1833 306:0.1833 307:0.1833 308:0.1833 309:0.1833 310:0.1833 311:0.1833 312:0.1833 313:0.1833 314:0.1833 315:0.1833 316:0.1833 317:0.1833 318:0.1833 319:0.1833 320:0.2 321:0.2 322:0.2 323:0.2 324:0.2 325:0.1833 326:0.1833 327:0.2 328:0.2 329:0.2 330:0.2 331:0.2 332:0.1833 333:0.2 334:0.2 335:0.2 336:0.2 337:0.2 338:0.2 339:0.2 340:0.2 341:0.2 342:0.2 343:0.2 344:0.2 345:0.2 346:0.2167 347:0.2167 348:0.2167 349:0.2167 350:0.2167 351:0.2333 352:0.2333 353:0.2333 354:0.2333 355:0.2333 356:0.25 357:0.25 358:0.25 359:0.25 360:0.2833
0.1962220074588565 1:0.2 2:0.2 3:0.2 4:0.2167 5:0.2167 6:0.2167 7:0.2167 8:0.25 9:0.25 10:0.2833 11:0.2833 12:0.2833 13:0.3833 14:0.3833 15:0.4 16:0.4333 17:0.4833 18:0.5667 19:0.6333 20:0.6667 21:0.4667 22:0.4833 23:0.4667 24:0.4833 25:0.4833 26:0.4833 27:0.4333 28:0.35 29:0.3667 30:0.35 31:0.35 32:0.35 33:0.35 34:0.35 35:0.35 36:0.3333 37:0.3333 38:0.15 39:0.15 40:0.15 41:0.1667 42:0.1667 43:0.1667 44:0.15 45:0.1667 46:0.1667 47:0.15 48:0.15 49:0.15 50:0.15 51:0.15 52:0.15 53:0.15 54:0.15 55:0.15 56:0.15 57:0.15 58:0.15 59:0.1667 60:0.15 61:0.15 62:0.15 63:0.15 64:0.15 65:0.15 66:0.15 67:0.15 68:0.15 69:0.15 70:0.15 71:0.15 72:0.15 73:0.15 74:0.15 75:0.15 76:0.15 77:0.1667 78:0.3 79:0.3 80:0.3 81:0.3 82:0.3 83:0.3 84:0.3833 85:0.3833 86:0.3833 87:0.3833 88:0.9333 89:0.95 90:1 91:1 92:1 93:1 94:1 95:1 96:0.7167 97:0.6 98:0.6 99:0.4167 100:0.4 101:0.4 102:0.4 103:0.4 104:0.4 105:0.2333 106:0.2333 107:0.2333 108:0.2333 109:0.2333 110:0.2333 111:0.2333 112:0.2333 113:0.2333 114:0.2333 115:0.2333 116:0.2333 117:0.2333 118:0.2333 119:0.2333 120:0.2333 121:0.2333 122:0.2333 123:0.2333 124:0.1333 125:0.1 126:0.1 127:0.1 128:0.1 129:0.1 130:0.1 131:0.1 132:0.1 133:0.1 134:0.1 135:0.1 136:0.1 137:0.1 138:0.1 139:0.1 140:0.1 141:0.1 142:0.052631579 143:0.052631579 144:0.052631579 145:0.052631579 146:0.052631579 147:0.052631579 148:0.052631579 149:0.052631579 150:0.052631579 151:0.052631579 152:0.052631579 153:0.052631579 154:0.052631579 155:0.052631579 156:0.052631579 157:0.035710842 158:0.035710842 159:0.035710842 160:0.035710842 161:0.035710842 162:0.035710842 163:0.035710842 164:0.035710842 165:0.035710842 166:0.035710842 167:0.035710842 168:0.035710842 169:0.053603763 170:0.089282462 171:0.089282462 172:0.089282462 173:0.089282462 174:0.089282462 175:0.089282462 176:0.089282462 177:0.089282462 178:0.089282462 179:0.089282462 180:0.089282462 181:0.089282462 182:0.089282462 183:0.089282462 184:0.089282462 185:0.089282462 186:0.089282462 187:0.089282462 188:0.089282462 189:0.089282462 190:0.089282462 191:0.089282462 192:0.089282462 193:0.053603763 194:0.053603763 195:0.053603763 196:0.053603763 197:0.053603763 198:0.053603763 199:0.053603763 200:0.053603763 201:0.053603763 202:0.053603763 203:0.053603763 204:0.053603763 205:0.053603763 206:0.053603763 207:0.053603763 208:0.053603763 209:0.053603763 210:0.053603763 211:0.053603763 212:0.053603763 213:0.053603763 214:0.053603763 215:0.053603763 216:0.053603763 217:0.053603763 218:0.053603763 219:0.053603763 220:0.053603763 221:0.1167 222:0.1167 223:0.1167 224:0.1167 225:0.1167 226:0.1167 227:0.1167 228:0.1167 229:0.1167 230:0.1167 231:0.1167 232:0.1167 233:0.1167 234:0.2 235:0.1833 236:0.1833 237:0.25 238:0.25 239:0.25 240:0.25 241:0.25 242:0.25 243:0.25 244:0.25 245:0.25 246:0.25 247:0.25 248:0.2667 249:0.2667 250:0.25 251:0.2667 252:0.2667 253:0.25 254:0.25 255:0.3167 256:0.3167 257:0.3167 258:0.35 259:0.35 260:0.4 261:0.55 262:0.55 263:0.55 264:0.7 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:0.9833 274:0.8333 275:0.65 276:0.4833 277:0.4833 278:0.4833 279:0.3 280:0.3167 281:0.3167 282:0.3167 283:0.3167 284:0.25 285:0.1667 286:0.15 287:0.15 288:0.15 289:0.15 290:0.15 291:0.15 292:0.15 293:0.15 294:0.15 295:0.15 296:0.15 297:0.15 298:0.15 299:0.15 300:0.15 301:0.15 302:0.15 303:0.1667 304:0.15 305:0.15 306:0.15 307:0.15 308:0.15 309:0.15 310:0.15 311:0.15 312:0.15 313:0.15 314:0.15 315:0.1667 316:0.1667 317:0.15 318:0.15 319:0.1667 320:0.15 321:0.1667 322:0.15 323:0.15 324:0.15 325:0.15 326:0.15 327:0.1667 328:0.1667 329:0.1667 330:0.15 331:0.15 332:0.15 333:0.1667 334:0.1667 335:0.1667 336:0.1667 337:0.1667 338:0.1667 339:0.15 340:0.1667 341:0.1667 342:0.1667 343:0.1667 344:0.1667 345:0.1667 346:0.1667 347:0.1667 348:0.1833 349:0.1833 350:0.1833 351:0.1833 352:0.1667 353:0.1667 354:0.1833 355:0.1833 356:0.1833 357:0.1833 358:0.1833 359:0.2 360:0.2
0.5750544513633736 1:0.25 2:0.25 3:0.2833 4:0.2833 5:0.2833 6:0.3167 7:0.3167 8:0.3167 9:0.3667 10:0.4 11:0.4 12:0.4 13:0.4167 14:0.4 15:0.4167 16:0.4 17:0.4 18:0.4167 19:0.4167 20:0.4167 21:0.4167 22:0.3 23:0.2833 24:0.2833 25:0.2833 26:0.1 27:0.1 28:0.08333 29:0.08333 30:0.08333 31:0.08333 32:0.08333 33:0.08333 34:0.08333 35:0.08333 36:0.08333 37:0.08333 38:0.08333 39:0.1 40:0.08333 41:0.08333 42:0.08333 43:0.08333 44:0.08333 45:0.08333 46:0.08333 47:0.08333 48:0.08333 49:0.08333 50:0.08333 51:0.08333 52:0.08333 53:0.08333 54:0.08333 55:0.08333 56:0.1 57:0.08333 58:0.1 59:0.08333 60:0.08333 61:0.08333 62:0.08333 63:0.08333 64:0.08333 65:0.08333 66:0.08333 67:0.08333 68:0.08333 69:0.08333 70:0.08333 71:0.08333 72:0.08333 73:0.08333 74:0.08333 75:0.08333 76:0.08333 77:0.1 78:0.1 79:0.1 80:0.08333 81:0.08333 82:0.08333 83:0.08333 84:0.08333 85:0.08333 86:0.08333 87:0.2333 88:0.2333 89:0.2333 90:0.2333 91:0.2333 92:0.2333 93:1 94:1 95:1 96:1 97:1 98:1 99:0.9167 100:0.6833 101:0.6667 102:0.5667 103:0.55 104:0.55 105:0.55 106:0.55 107:0.45 108:0.3667 109:0.35 110:0.35 111:0.35 112:0.35 113:0.35 114:0.35 115:0.35 116:0.35 117:0.35 118:0.35 119:0.35 120:0.2167 121:0.2167 122:0.2167 123:0.2 124:0.2 125:0.2 126:0.2 127:0.2167 128:0.2 129:0.2 130:0.2167 131:0.2167 132:0.2 133:0.2 134:0.2 135:0.2167 136:0.2167 137:0.2 138:0.2 139:0.2167 140:0.2167 141:0.2 142:0.15789474 143:0.15789474 144:0.17547368 145:0.17547368 146:0.17547368 147:0.087684211 148:0.087684211 149:0.087684211 150:0.087684211 151:0.087684211 152:0.087684211 153:0.087684211 154:0.087684211 155:0.087684211 156:0.087684211 157:0.053603763 158:0.053603763 159:0.053603763 160:0.053603763 161:0.053603763 162:0.053603763 163:0.053603763 164:0.053603763 165:0.053603763 166:0.053603763 167:0.053603763 168:0.053603763 169:0.053603763 170:0.053603763 171:0.053603763 172:0.053603763 173:0.053603763 174:0.053603763 175:0.053603763 176:0.053603763 177:0.053603763 178:0.053603763 179:0.053603763 180:0.053603763 181:0.053603763 182:0.053603763 183:0.053603763 184:0.053603763 185:0.053603763 186:0.053603763 187:0.053603763 188:0.053603763 189:0.053603763 190:0.053603763 191:0.053603763 192:0.14285408 193:0.14285408 194:0.14285408 195:0.14285408 196:0.14285408 197:0.14285408 198:0.14285408 199:0.14285408 200:0.14285408 201:0.14285408 202:0.14285408 203:0.14285408 204:0.14285408 205:0.14285408 206:0.14285408 207:0.14285408 208:0.14285408 209:0.14285408 210:0.14285408 211:0.14285408 212:0.14285408 213:0.14285408 214:0.14285408 215:0.17853278 216:0.17853278 217:0.17853278 218:0.17853278 219:0.17853278 220:0.17853278 221:0.2333 222:0.2333 223:0.25 224:0.25 225:0.25 226:0.25 227:0.25 228:0.2333 229:0.2333 230:0.25 231:0.25 232:0.25 233:0.2667 234:0.2667 235:0.2667 236:0.3 237:0.3 238:0.3 239:0.3 240:0.3 241:0.3 242:0.3 243:0.3 244:0.3 245:0.3 246:0.3 247:0.3 248:0.3 249:0.3 250:0.3 251:0.3167 252:0.3167 253:0.3167 254:0.3167 255:0.3333 256:0.35 257:0.3667 258:0.4 259:0.4 260:0.4 261:0.6167 262:0.6167 263:0.7667 264:0.7833 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:0.3667 274:0.1833 275:0.1833 276:0.1833 277:0.1833 278:0.1833 279:0.1833 280:0.1833 281:0.1833 282:0.1833 283:0.1833 284:0.1833 285:0.1667 286:0.1667 287:0.1667 288:0.1667 289:0.1667 290:0.1667 291:0.1667 292:0.1667 293:0.1667 294:0.1667 295:0.1667 296:0.1667 297:0.1667 298:0.1667 299:0.1667 300:0.1667 301:0.1667 302:0.1667 303:0.1667 304:0.1667 305:0.1667 306:0.1667 307:0.1667 308:0.1667 309:0.1667 310:0.1667 311:0.1667 312:0.1667 313:0.1667 314:0.1667 315:0.1667 316:0.1667 317:0.1667 318:0.1667 319:0.1667 320:0.1667 321:0.1667 322:0.1667 323:0.1667 324:0.1667 325:0.1667 326:0.1667 327:0.1667 328:0.1667 329:0.1667 330:0.1667 331:0.1667 332:0.1667 333:0.1667 334:0.1667 335:0.1667 336:0.2 337:0.2167 338:0.2167 339:0.2167 340:0.2167 341:0.2 342:0.2167 343:0.2167 344:0.2167 345:0.2167 346:0.2167 347:0.2167 348:0.2167 349:0.2 350:0.2167 351:0.2167 352:0.2 353:0.2 354:0.2 355:0.2167 356:0.2167 357:0.2167 358:0.2167 359:0.2333 360:0.25
0.310011314534733 1:0.1333 2:0.1333 3:0.1333 4:0.1333 5:0.1333 6:0.1333 7:0.1333 8:0.1333 9:0.1333 10:0.1333 11:0.1333 12:0.1333 13:0.1333 14:0.1333 15:0.1333 16:0.1333 17:0.1333 18:0.1333 19:0.1333 20:0.1333 21:0.1333 22:0.1333 23:0.1333 24:0.1333 25:0.1333 26:0.1333 27:0.1333 28:0.1333 29:0.1333 30:0.1667 31:0.1667 32:0.1667 33:0.1667 34:0.1667 35:0.1667 36:0.1833 37:0.1833 38:0.1667 39:0.1667 40:0.1667 41:0.1833 42:0.1833 43:0.1667 44:0.1667 45:0.1667 46:0.1833 47:0.1667 48:0.1667 49:0.1667 50:0.1667 51:0.1667 52:0.1833 53:0.1833 54:0.1833 55:0.45 56:0.45 57:0.2667 58:0.45 59:0.45 60:0.2667 61:0.2667 62:0.5167 63:0.2667 64:0.2667 65:0.4 66:0.2667 67:0.2667 68:0.3833 69:0.3833 70:0.3833 71:0.3833 72:0.3833 73:0.3833 74:0.3833 75:0.3833 76:0.3833 77:0.3833 78:0.4 79:0.5167 80:0.5167 81:0.5167 82:0.7 83:0.7 84:0.7 85:0.8667 86:0.8667 87:0.8667 88:1 89:0.5667 90:0.5667 91:0.5667 92:0.5667 93:0.5667 94:0.5667 95:0.5667 96:0.5 97:0.5 98:0.5 99:0.5 100:0.5 101:0.5 102:0.5 103:0.5 104:0.5 105:0.5 106:0.5167 107:0.6667 108:0.6667 109:0.5667 110:0.5833 111:0.5667 112:0.5667 113:0.5667 114:0.5667 115:0.4333 116:0.4167 117:0.4333 118:0.4167 119:0.4333 120:0.4167 121:0.3167 122:0.3 123:0.3 124:0.3 125:0.3 126:0.3 127:0.3 128:0.1833 129:0.1833 130:0.1833 131:0.1833 132:0.1833 133:0.1833 134:0.1833 135:0.1833 136:0.1833 137:0.1833 138:0.1833 139:0.1833 140:0.1833 141:0.1833 142:0.14031579 143:0.14031579 144:0.14031579 145:0.14031579 146:0.14031579 147:0.14031579 148:0.14031579 149:0.14031579 150:0.14031579 151:0.14031579 152:0.14031579 153:0.14031579 154:0.14031579 155:0.14031579 156:0.14031579 157:0.12496116 158:0.12496116 159:0.12496116 160:0.12496116 161:0.12496116 162:0.12496116 163:0.12496116 164:0.12496116 165:0.12496116 166:0.12496116 167:0.12496116 168:0.12496116 169:0.12496116 170:0.12496116 171:0.12496116 172:0.12496116 173:0.12496116 174:0.12496116 175:0.12496116 176:0.12496116 177:0.12496116 178:0.12496116 179:0.12496116 180:0.12496116 181:0.12496116 182:0.12496116 183:0.12496116 184:0.75003482 185:1 186:1 187:1 188:1 189:1 190:1 191:0.91074968 192:0.75003482 193:0.75003482 194:0.55353412 195:0.55353412 196:0.55353412 197:0.41071218 198:0.41071218 199:0.41071218 200:0.41071218 201:0.41071218 202:0.30356894 203:0.30356894 204:0.30356894 205:0.30356894 206:0.30356894 207:0.30356894 208:0.30356894 209:0.35714056 210:0.30356894 211:0.30356894 212:0.30356894 213:0.17853278 214:0.17853278 215:0.17853278 216:0.160747 217:0.160747 218:0.160747 219:0.160747 220:0.160747 221:0.2167 222:0.2167 223:0.2167 224:0.2167 225:0.2167 226:0.2 227:0.2 228:0.2167 229:0.2167 230:0.2167 231:0.2 232:0.2167 233:0.2167 234:0.2167 235:0.2 236:0.2167 237:0.2167 238:0.2167 239:0.2167 240:0.2 241:0.2167 242:0.2167 243:0.2 244:0.2 245:0.2167 246:0.2167 247:0.2167 248:0.2167 249:0.2167 250:0.2167 251:0.2167 252:0.2667 253:0.25 254:0.25 255:0.2667 256:0.2667 257:0.2667 258:0.2667 259:0.2667 260:0.2833 261:0.2667 262:0.2667 263:0.2667 264:0.2667 265:0.2667 266:0.3167 267:0.3167 268:0.3167 269:0.3167 270:0.3833 271:0.3833 272:0.3833 273:0.4 274:0.4 275:0.9333 276:0.95 277:0.95 278:1 279:1 280:1 281:1 282:0.3 283:0.2833 284:0.25 285:0.2333 286:0.2167 287:0.2 288:0.2 289:0.1833 290:0.1833 291:0.1833 292:0.2 293:0.2 294:0.1833 295:0.1833 296:0.2 297:0.2 298:0.2 299:0.1833 300:0.2 301:0.2 302:0.2 303:0.1833 304:0.1833 305:0.1833 306:0.2 307:0.2 308:0.1833 309:0.1833 310:0.1833 311:0.2 312:0.2 313:0.2 314:0.2 315:0.2 316:0.2 317:0.2167 318:0.2167 319:0.2167 320:0.2167 321:0.2167 322:0.25 323:0.2833 324:0.2833 325:0.2833 326:0.2833 327:0.3 328:0.2833 329:0.2833 330:0.3 331:0.2833 332:0.2833 333:0.3 334:0.2833 335:0.2833 336:0.2833 337:0.2833 338:0.2833 339:0.2833 340:0.2667 341:0.2667 342:0.2667 343:0.2667 344:0.2667 345:0.2667 346:0.2667 347:0.2667 348:0.2667 349:0.2667 350:0.2667 351:0.2667 352:0.1333 353:0.1333 354:0.1333 355:0.1333 356:0.1333 357:0.1333 358:0.1333 359:0.1333 360:0.1333
1.596701576076699 1:0.1333 2:0.1333 3:0.1333 4:0.1333 5:0.1333 6:0.1333 7:0.1333 8:0.1333 9:0.1333 10:0.1333 11:0.1333 12:0.1333 13:0.1333 14:0.1333 15:0.1333 16:0.1333 17:0.1333 18:0.1333 19:0.1333 20:0.1333 21:0.1333 22:0.1333 23:0.15 24:0.1667 25:0.1667 26:0.1667 27:0.1667 28:0.1667 29:0.1667 30:0.1667 31:0.1667 32:0.1667 33:0.1667 34:0.1667 35:0.1667 36:0.1667 37:0.1667 38:0.1667 39:0.1667 40:0.1667 41:0.1667 42:0.1667 43:0.1667 44:0.1667 45:0.15 46:0.1667 47:0.1667 48:0.1667 49:0.1667 50:0.1667 51:0.1667 52:0.25 53:0.25 54:0.25 55:0.25 56:0.25 57:0.25 58:0.25 59:0.25 60:0.25 61:0.25 62:0.25 63:0.25 64:0.25 65:0.25 66:0.25 67:0.25 68:0.25 69:0.25 70:0.25 71:0.3667 72:0.3833 73:0.3667 74:0.3667 75:0.3667 76:0.3667 77:0.3667 78:0.5167 79:0.5167 80:0.5167 81:0.5167 82:0.5167 83:0.5333 84:0.6667 85:0.6667 86:0.6667 87:0.85 88:0.85 89:1 90:1 91:1 92:0.7667 93:0.7667 94:0.7667 95:0.7667 96:0.7667 97:0.7667 98:0.8833 99:0.8833 100:0.4667 101:0.45 102:0.45 103:0.45 104:0.45 105:0.45 106:0.45 107:0.45 108:0.45 109:0.45 110:0.45 111:0.55 112:0.55 113:0.55 114:0.55 115:0.55 116:0.55 117:0.4 118:0.4167 119:0.4 120:0.4167 121:0.4167 122:0.4167 123:0.1667 124:0.1667 125:0.1667 126:0.1667 127:0.1667 128:0.1667 129:0.1667 130:0.1667 131:0.1667 132:0.1667 133:0.1667 134:0.1667 135:0.1667 136:0.1667 137:0.1667 138:0.1667 139:0.1667 140:0.1667 141:0.1667 142:0.12284211 143:0.12284211 144:0.12284211 145:0.12284211 146:0.12284211 147:0.12284211 148:0.12284211 149:0.12284211 150:0.12284211 151:0.12284211 152:0.12284211 153:0.12284211 154:0.12284211 155:0.12284211 156:0.14031579 157:0.12496116 158:0.12496116 159:0.12496116 160:0.12496116 161:0.12496116 162:0.12496116 163:0.12496116 164:0.12496116 165:0.12496116 166:0.12496116 167:0.12496116 168:0.12496116 169:0.12496116 170:0.12496116 171:0.12496116 172:0.12496116 173:0.12496116 174:0.12496116 175:0.12496116 176:0.12496116 177:0.12496116 178:0.12496116 179:0.14285408 180:0.14285408 181:0.14285408 182:0.14285408 183:0.14285408 184:0.14285408 185:0.14285408 186:0.14285408 187:0.14285408 188:1 189:1 190:1 191:1 192:0.91074968 193:0.91074968 194:0.75003482 195:0.75003482 196:0.57142704 197:0.55353412 198:0.55353412 199:0.41071218 200:0.41071218 201:0.41071218 202:0.41071218 203:0.41071218 204:0.32146186 205:0.32146186 206:0.32146186 207:0.32146186 208:0.32146186 209:0.32146186 210:0.32146186 211:0.32146186 212:0.32146186 213:0.32146186 214:0.32146186 215:0.1964257 216:0.1964257 217:0.1964257 218:0.17853278 219:0.17853278 220:0.17853278 221:0.2333 222:0.2333 223:0.2333 224:0.2333 225:0.2333 226:0.2333 227:0.2333 228:0.2167 229:0.2167 230:0.2167 231:0.2333 232:0.2167 233:0.2167 234:0.2167 235:0.2167 236:0.2333 237:0.2167 238:0.2167 239:0.2333 240:0.2333 241:0.2167 242:0.2167 243:0.2333 244:0.2167 245:0.2167 246:0.2167 247:0.2167 248:0.2333 249:0.2333 250:0.2333 251:0.2333 252:0.2833 253:0.2667 254:0.2667 255:0.2667 256:0.2833 257:0.2833 258:0.2833 259:0.2833 260:0.3 261:0.3333 262:0.3333 263:0.3333 264:0.3333 265:0.3333 266:0.3333 267:0.3333 268:0.3333 269:0.3333 270:0.4 271:0.4 272:0.4 273:0.4 274:0.4 275:0.5667 276:0.95 277:0.95 278:1 279:1 280:1 281:1 282:0.3 283:0.2833 284:0.25 285:0.2333 286:0.2167 287:0.2 288:0.2 289:0.2 290:0.2 291:0.2 292:0.2 293:0.2 294:0.2 295:0.2167 296:0.2167 297:0.2 298:0.2 299:0.2167 300:0.2167 301:0.2 302:0.2 303:0.2 304:0.2167 305:0.2 306:0.2 307:0.2 308:0.2 309:0.2167 310:0.2167 311:0.2167 312:0.2167 313:0.2167 314:0.2167 315:0.2333 316:0.2333 317:0.2333 318:0.2667 319:0.2667 320:0.3 321:0.3 322:0.2833 323:0.3 324:0.3 325:0.2833 326:0.3 327:0.3 328:0.2833 329:0.3 330:0.3 331:0.2833 332:0.3 333:0.3 334:0.3 335:0.3 336:0.3 337:0.3167 338:0.3167 339:0.3 340:0.2667 341:0.2667 342:0.2667 343:0.2833 344:0.2667 345:0.2667 346:0.1333 347:0.1333 348:0.1333 349:0.1333 350:0.1333 351:0.1333 352:0.1333 353:0.1333 354:0.1333 355:0.1333 356:0.1333 357:0.1333 358:0.1333 359:0.1333 360:0.1333
0.1681704381692252 1:0.2167 2:0.2167 3:0.2167 4:0.1833 5:0.1833 6:0.1833 7:0.1833 8:0.1833 9:0.1833 10:0.1833 11:0.1833 12:0.1833 13:0.1833 14:0.1833 15:0.1667 16:0.15 17:0.15 18:0.15 19:0.15 20:0.15 21:0.15 22:0.15 23:0.15 24:0.1 25:0.1 26:0.1167 27:0.1167 28:0.1167 29:0.1167 30:0.1167 31:0.1167 32:0.1167 33:0.1167 34:0.1167 35:0.1 36:0.1 37:0.1167 38:0.1167 39:0.1167 40:0.1167 41:0.1167 42:0.1167 43:0.1167 44:0.1167 45:0.1167 46:0.1167 47:0.1167 48:0.1167 49:0.1167 50:0.1167 51:0.1167 52:0.1167 53:0.1167 54:0.1167 55:0.1167 56:0.1 57:0.1 58:0.1167 59:0.1167 60:0.1167 61:0.1167 62:0.1167 63:0.1167 64:0.1167 65:0.1167 66:0.1167 67:0.1 68:0.1 69:0.5 70:0.4833 71:0.4833 72:0.4833 73:0.6667 74:0.6667 75:0.8333 76:0.8333 77:1 78:1 79:0.9667 80:0.9667 81:0.9667 82:0.9667 83:0.9667 84:0.9333 85:0.9333 86:0.8333 87:0.5167 88:0.5167 89:0.5167 90:0.45 91:0.45 92:0.45 93:0.4333 94:0.4333 95:0.4333 96:0.4333 97:0.4333 98:0.4333 99:0.4333 100:0.4333 101:0.4333 102:0.4333 103:0.35 104:0.35 105:0.35 106:0.35 107:0.35 108:0.35 109:0.35 110:0.35 111:0.35 112:0.35 113:0.35 114:0.35 115:0.35 116:0.35 117:0.35 118:0.35 119:0.45 120:0.45 121:0.45 122:0.4833 123:0.45 124:0.4833 125:0.45 126:0.45 127:0.45 128:0.35 129:0.35 130:0.35 131:0.35 132:0.35 133:0.35 134:0.35 135:0.35 136:0.35 137:0.35 138:0.35 139:0.35 140:0.35 141:0.35 142:0.33336842 143:0.33336842 144:0.33336842 145:0.33336842 146:0.33336842 147:0.33336842 148:0.33336842 149:0.33336842 150:0.33336842 151:0.33336842 152:0.33336842 153:0.33336842 154:0.33336842 155:0.33336842 156:0.33336842 157:0.33924764 158:0.35714056 159:0.37503348 160:0.39281926 161:0.6964632 162:0.7321419 163:0.7321419 164:0.87496384 165:0.85717806 166:0.85717806 167:0.87496384 168:1 169:1 170:1 171:1 172:1 173:1 174:1 175:1 176:0.98210708 177:0.98210708 178:0.98210708 179:0.87496384 180:0.87496384 181:0.67857028 182:0.67857028 183:0.67857028 184:0.48217672 185:0.48217672 186:0.48217672 187:0.48217672 188:0.48217672 189:0.26789024 190:0.28567602 191:0.28567602 192:0.160747 193:0.160747 194:0.160747 195:0.160747 196:0.160747 197:0.160747 198:0.160747 199:0.160747 200:0.160747 201:0.160747 202:0.14285408 203:0.14285408 204:0.14285408 205:0.14285408 206:0.14285408 207:0.14285408 208:0.14285408 209:0.14285408 210:0.14285408 211:0.14285408 212:0.14285408 213:0.14285408 214:0.14285408 215:0.14285408 216:0.14285408 217:0.14285408 218:0.14285408 219:0.14285408 220:0.14285408 221:0.1667 222:0.1667 223:0.1667 224:0.1667 225:0.1667 226:0.2 227:0.1667 228:0.1667 229:0.1667 230:0.1667 231:0.1667 232:0.1667 233:0.1667 234:0.1667 235:0.1833 236:0.1833 237:0.1667 238:0.1667 239:0.1667 240:0.1667 241:0.1667 242:0.1667 243:0.1667 244:0.1667 245:0.1667 246:0.1667 247:0.2833 248:0.2833 249:0.1833 250:0.1667 251:0.1667 252:0.2833 253:0.3 254:0.3167 255:0.4667 256:0.4667 257:0.4667 258:0.4667 259:0.4667 260:0.4833 261:0.65 262:0.9667 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:0.9833 273:0.9833 274:0.65 275:0.65 276:0.4833 277:0.4833 278:0.4833 279:0.4833 280:0.4833 281:0.4833 282:0.4833 283:0.35 284:0.35 285:0.35 286:0.35 287:0.35 288:0.35 289:0.35 290:0.35 291:0.35 292:0.35 293:0.35 294:0.35 295:0.35 296:0.3333 297:0.3167 298:0.2 299:0.2 300:0.2167 301:0.2167 302:0.2 303:0.2167 304:0.2167 305:0.2167 306:0.1833 307:0.1833 308:0.1833 309:0.1833 310:0.1833 311:0.1833 312:0.1833 313:0.1833 314:0.1833 315:0.1833 316:0.1833 317:0.1833 318:0.1833 319:0.1833 320:0.1833 321:0.1833 322:0.1833 323:0.1833 324:0.1833 325:0.1833 326:0.1833 327:0.1833 328:0.1833 329:0.1833 330:0.1833 331:0.1833 332:0.1833 333:0.1833 334:0.1833 335:0.1833 336:0.1833 337:0.1833 338:0.1833 339:0.2 340:0.2 341:0.1833 342:0.1833 343:0.1833 344:0.2 345:0.2 346:0.2 347:0.2 348:0.2 349:0.2 350:0.2 351:0.2 352:0.2 353:0.2 354:0.2 355:0.2 356:0.2 357:0.2 358:0.2 359:0.2167 360:0.2167
0.02735137271749791 1:0.03333 2:0.03333 3:0.03333 4:0.03333 5:0.03333 6:0.03333 7:0.03333 8:0.03333 9:0.03333 10:0.03333 11:0.03333 12:0.03333 13:0.03333 14:0.03333 15:0.03333 16:0.03333 17:0.03333 18:0.03333 19:0.03333 20:0.03333 21:0.03333 22:0.03333 23:0.03333 24:0.03333 25:0.03333 26:0.03333 27:0.03333 28:0.03333 29:0.03333 30:0.03333 31:0.03333 32:0.03333 33:0.03333 34:0.03333 35:0.03333 36:0.01667 37:0.01667 38:0.01667 39:0.01667 40:0.01667 41:0.01667 42:0.01667 43:0.01667 44:0.01667 45:0.01667 46:0.01667 47:0.01667 48:0.01667 49:0.01667 50:0.01667 51:0.01667 52:0.01667 53:0.01667 54:0.01667 55:0.01667 56:0.01667 57:0.01667 58:0.01667 59:0.01667 60:0.01667 61:0.01667 62:0.01667 63:0.01667 64:0.01667 65:0.01667 66:0.01667 67:0.01667 68:0.01667 69:0.01667 70:0.01667 71:0.01667 72:0.01667 73:0.01667 74:0.35 75:0.3333 76:0.35 77:0.5167 78:0.5167 79:0.5167 80:0.6667 81:0.8833 82:0.9 83:1 84:0.8 85:0.8 86:0.8 87:0.8 88:0.8 89:0.8 90:0.7833 91:0.7833 92:0.6833 93:0.6833 94:0.55 95:0.55 96:0.55 97:0.4 98:0.35 99:0.35 100:0.3667 101:0.2333 102:0.2167 103:0.2167 104:0.2167 105:0.2167 106:0.2167 107:0.2 108:0.2 109:0.2 110:0.2 111:0.2 112:0.2 113:0.2 114:0.2 115:0.2167 116:0.2167 117:0.2 118:0.2 119:0.2167 120:0.2167 121:0.2 122:0.2 123:0.2 124:0.2167 125:0.2 126:0.2 127:0.2 128:0.2 129:0.2167 130:0.2167 131:0.2167 132:0.2667 133:0.25 134:0.25 135:0.25 136:0.25 137:0.25 138:0.25 139:0.25 140:0.25 141:0.25 142:0.21052632 143:0.22810526 144:0.22810526 145:0.35084211 146:0.33336842 147:0.33336842 148:0.35084211 149:0.36842105 150:0.36842105 151:0.36842105 152:0.386 153:0.36842105 154:0.28073684 155:0.28073684 156:0.28073684 157:0.26789024 158:0.26789024 159:0.26789024 160:0.26789024 161:0.26789024 162:0.26789024 163:0.26789024 164:0.26789024 165:0.26789024 166:0.26789024 167:0.26789024 168:0.30356894 169:0.30356894 170:0.30356894 171:0.30356894 172:0.30356894 173:0.30356894 174:0.30356894 175:0.30356894 176:0.30356894 177:0.30356894 178:0.30356894 179:0.30356894 180:0.35714056 181:0.35714056 182:0.35714056 183:1 184:1 185:1 186:1 187:0.9643213 188:0.94642838 189:0.94642838 190:0.94642838 191:0.94642838 192:0.94642838 193:0.94642838 194:0.75003482 195:0.75003482 196:0.75003482 197:0.75003482 198:0.75003482 199:0.75003482 200:0.57142704 201:0.57142704 202:0.57142704 203:0.57142704 204:0.57142704 205:0.57142704 206:0.57142704 207:0.57142704 208:0.57142704 209:0.51785542 210:0.39281926 211:0.37503348 212:0.39281926 213:0.37503348 214:0.39281926 215:0.37503348 216:0.28567602 217:0.28567602 218:0.28567602 219:0.28567602 220:0.28567602 221:0.35 222:0.3333 223:0.3333 224:0.3333 225:0.3333 226:0.3167 227:0.3333 228:0.2833 229:0.2833 230:0.2833 231:0.2833 232:0.2833 233:0.2833 234:0.2833 235:0.2833 236:0.2833 237:0.2833 238:0.2833 239:0.2833 240:0.2833 241:0.2833 242:0.2833 243:0.2833 244:0.2833 245:0.2833 246:0.3 247:0.3 248:0.3333 249:0.3333 250:0.3333 251:0.3333 252:0.3333 253:0.3833 254:0.35 255:0.3333 256:0.3833 257:0.3833 258:0.3833 259:0.3833 260:0.3833 261:0.8 262:0.8 263:0.9833 264:0.9833 265:0.9833 266:0.9833 267:1 268:1 269:1 270:1 271:1 272:0.8 273:0.8 274:0.6167 275:0.6167 276:0.4667 277:0.4667 278:0.4667 279:0.3 280:0.3167 281:0.3167 282:0.3167 283:0.2833 284:0.2833 285:0.2833 286:0.2833 287:0.2667 288:0.2667 289:0.2667 290:0.2833 291:0.2667 292:0.2667 293:0.2667 294:0.2667 295:0.2667 296:0.25 297:0.25 298:0.2667 299:0.2667 300:0.25 301:0.2667 302:0.2667 303:0.2667 304:0.2667 305:0.25 306:0.01667 307:0.01667 308:0.01667 309:0.01667 310:0.01667 311:0.01667 312:0.01667 313:0.01667 314:0.01667 315:0.01667 316:0.01667 317:0.01667 318:0.01667 319:0.01667 320:0.01667 321:0.01667 322:0.01667 323:0.01667 324:0.01667 325:0.01667 326:0.01667 327:0.01667 328:0.01667 329:0.01667 330:0.01667 331:0.01667 332:0.01667 333:0.01667 334:0.01667 335:0.01667 336:0.01667 337:0.01667 338:0.01667 339:0.01667 340:0.01667 341:0.01667 342:0.01667 343:0.01667 344:0.03333 345:0.03333 346:0.03333 347:0.03333 348:0.03333 349:0.03333 350:0.03333 351:0.03333 352:0.03333 353:0.03333 354:0.03333 355:0.03333 356:0.03333 357:0.03333 358:0.03333 359:0.03333 360:0.03333
0.01952115546713023 1:0.4167 2:0.4167 3:0.4167 4:0.4167 5:0.4167 6:0.4167 7:0.4167 8:0.4167 9:0.4167 10:0.4167 11:0.4333 12:0.3 13:0.2833 14:0.2667 15:0.2667 16:0.2667 17:0.2667 18:0.2667 19:0.2667 20:0.2667 21:0.2667 22:0.25 23:0.25 24:0.25 25:0.25 26:0.25 27:0.25 28:0.2333 29:0.2333 30:0.2167 31:0.2167 32:0.2167 33:0.2 34:0.2 35:0.2 36:0.1833 37:0.1833 38:0.2 39:0.2 40:0.2 41:0.2 42:0.2 43:0.2 44:0.2 45:0.2 46:0.2 47:0.2 48:0.2 49:0.2 50:0.2 51:0.2 52:0.2 53:0.2 54:0.2 55:0.1833 56:0.1833 57:0.2 58:0.2 59:0.2 60:0.2167 61:0.2167 62:0.2167 63:0.2167 64:0.2167 65:0.2167 66:0.2167 67:0.2167 68:0.2167 69:0.2167 70:0.2167 71:0.2167 72:0.2833 73:0.2667 74:0.2667 75:0.2667 76:0.2833 77:0.2833 78:0.2833 79:0.2833 80:0.4333 81:0.4333 82:0.4333 83:0.4333 84:0.4333 85:0.4333 86:0.45 87:0.45 88:0.4667 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:0.9167 97:0.7833 98:0.6333 99:0.6333 100:0.6333 101:0.4333 102:0.4333 103:0.4333 104:0.4333 105:0.4333 106:0.4333 107:0.4333 108:0.4333 109:0.3 110:0.3 111:0.3 112:0.3 113:0.3 114:0.3 115:0.3 116:0.3 117:0.2833 118:0.08333 119:0.08333 120:0.08333 121:0.08333 122:0.08333 123:0.08333 124:0.08333 125:0.08333 126:0.08333 127:0.08333 128:0.08333 129:0.1 130:0.08333 131:0.08333 132:0.08333 133:0.08333 134:0.08333 135:0.08333 136:0.08333 137:0.1 138:0.1 139:0.1 140:0.08333 141:0.08333 142:0.035084211 143:0.035084211 144:0.035084211 145:0.035084211 146:0.052631579 147:0.052631579 148:0.052631579 149:0.035084211 150:0.035084211 151:0.035084211 152:0.035084211 153:0.035084211 154:0.035084211 155:0.035084211 156:0.035084211 157:0.017850064 158:0.017850064 159:0.017850064 160:0.017850064 161:0.017850064 162:0.017850064 163:0.017850064 164:0.017850064 165:0.017850064 166:0.035710842 167:0.035710842 168:0.035710842 169:0.053603763 170:0.053603763 171:0.035710842 172:0.035710842 173:0.035710842 174:0.035710842 175:0.035710842 176:0.035710842 177:0.053603763 178:0.089282462 179:0.089282462 180:0.089282462 181:0.089282462 182:0.089282462 183:0.089282462 184:0.089282462 185:0.089282462 186:0.089282462 187:0.089282462 188:0.089282462 189:0.089282462 190:0.089282462 191:0.089282462 192:0.089282462 193:0.089282462 194:0.089282462 195:0.089282462 196:0.089282462 197:0.089282462 198:0.089282462 199:0.089282462 200:0.089282462 201:0.12496116 202:0.12496116 203:0.1964257 204:0.1964257 205:0.21431862 206:0.21431862 207:0.2321044 208:0.2321044 209:0.2321044 210:0.2321044 211:0.12496116 212:0.12496116 213:0.10717538 214:0.10717538 215:0.10717538 216:0.10717538 217:0.10717538 218:0.10717538 219:0.10717538 220:0.10717538 221:0.1667 222:0.1667 223:0.1667 224:0.1667 225:0.1667 226:0.1667 227:0.1667 228:0.1667 229:0.1667 230:0.1667 231:0.1667 232:0.1667 233:0.1667 234:0.1667 235:0.1667 236:0.1667 237:0.1667 238:0.1667 239:0.1667 240:0.1833 241:0.1833 242:0.3 243:0.3 244:0.3 245:0.3 246:0.3 247:0.3 248:0.3 249:0.3 250:0.3 251:0.3 252:0.3 253:0.3 254:0.4167 255:0.4167 256:0.4167 257:0.4167 258:0.4167 259:0.4333 260:0.55 261:0.55 262:0.6833 263:0.6833 264:0.75 265:1 266:1 267:1 268:1 269:1 270:1 271:0.5833 272:0.5833 273:0.5833 274:0.5833 275:0.5833 276:0.5833 277:0.4167 278:0.4167 279:0.4167 280:0.4167 281:0.2333 282:0.2333 283:0.2333 284:0.2333 285:0.2333 286:0.2333 287:0.2333 288:0.2333 289:0.2333 290:0.2333 291:0.2333 292:0.2333 293:0.2333 294:0.2333 295:0.2333 296:0.2333 297:0.2333 298:0.2333 299:0.2333 300:0.2167 301:0.2167 302:0.2167 303:0.2167 304:0.2167 305:0.2167 306:0.2167 307:0.2167 308:0.2167 309:0.2167 310:0.2167 311:0.2167 312:0.2167 313:0.2167 314:0.2167 315:0.2167 316:0.2167 317:0.2167 318:0.2167 319:0.2167 320:0.2167 321:0.2167 322:0.2167 323:0.2167 324:0.2167 325:0.2167 326:0.2167 327:0.2167 328:0.2167 329:0.2167 330:0.2167 331:0.2167 332:0.2167 333:0.3667 334:0.3667 335:0.3667 336:0.3667 337:0.3667 338:0.3667 339:0.4333 340:0.4333 341:0.4333 342:0.4333 343:0.4333 344:0.4333 345:0.45 346:0.4833 347:0.5333 348:0.55 349:0.55 350:0.5667 351:0.5667 352:1 353:1 354:1 355:1 356:1 357:1 358:0.4333 359:0.4333 360:0.4167
1.121679920396747 1:0.5167 2:0.5167 3:0.5167 4:0.5333 5:0.5333 6:0.5333 7:0.5333 8:0.5833 9:1 10:1 11:1 12:1 13:1 14:1 15:1 16:1 17:1 18:1 19:1 20:1 21:0.7 22:0.7 23:0.6833 24:0.6833 25:0.6833 26:0.6833 27:0.6833 28:0.6833 29:0.6833 30:1 31:1 32:1 33:1 34:1 35:1 36:1 37:0.2667 38:0.2667 39:0.2667 40:0.2667 41:0.2667 42:0.2667 43:0.2667 44:0.2667 45:0.2667 46:0.2667 47:0.2667 48:0.2667 49:0.2667 50:0.2333 51:0.2333 52:0.2333 53:0.2333 54:0.2333 55:0.2167 56:0.2333 57:0.2333 58:0.2333 59:0.2333 60:0.2333 61:0.2333 62:0.2333 63:0.2333 64:0.2333 65:0.2333 66:0.2333 67:0.2333 68:0.2333 69:0.2333 70:0.2333 71:0.2333 72:0.2333 73:0.2333 74:0.4167 75:0.4333 76:0.4167 77:0.3333 78:0.3333 79:0.3333 80:0.3333 81:0.3333 82:0.3333 83:0.3333 84:0.3333 85:0.3333 86:0.2667 87:0.2667 88:0.2667 89:0.2667 90:0.2667 91:0.2667 92:0.2667 93:0.2667 94:0.2667 95:0.2667 96:0.2667 97:0.2667 98:0.2667 99:0.2667 100:0.2667 101:0.2667 102:0.2667 103:0.2833 104:0.2833 105:0.2833 106:0.3 107:0.3 108:0.45 109:0.45 110:0.45 111:0.45 112:0.45 113:0.5833 114:0.5833 115:0.5833 116:0.7833 117:0.7 118:0.8833 119:1 120:1 121:1 122:1 123:1 124:1 125:1 126:1 127:1 128:0.85 129:0.7333 130:0.7333 131:0.5833 132:0.5667 133:0.5167 134:0.5167 135:0.35 136:0.3167 137:0.3333 138:0.25 139:0.25 140:0.2333 141:0.2333 142:0.19294737 143:0.19294737 144:0.19294737 145:0.19294737 146:0.19294737 147:0.19294737 148:0.19294737 149:0.19294737 150:0.19294737 151:0.19294737 152:0.19294737 153:0.19294737 154:0.19294737 155:0.19294737 156:0.19294737 157:0.17853278 158:0.17853278 159:0.1964257 160:0.1964257 161:0.21431862 162:0.1964257 163:0.1964257 164:0.17853278 165:0.17853278 166:0.17853278 167:0.17853278 168:0.17853278 169:0.17853278 170:0.17853278 171:0.17853278 172:0.17853278 173:0.17853278 174:0.17853278 175:0.17853278 176:0.17853278 177:0.17853278 178:0.17853278 179:0.17853278 180:0.17853278 181:0.17853278 182:0.17853278 183:0.17853278 184:0.089282462 185:0.089282462 186:0.089282462 187:0.089282462 188:0.089282462 189:0.089282462 190:0.089282462 191:0.089282462 192:0.089282462 193:0.089282462 194:0.089282462 195:0.10717538 196:0.089282462 197:0.089282462 198:0.089282462 199:0.089282462 200:0.10717538 201:0.10717538 202:0.089282462 203:0.089282462 204:0.089282462 205:0.089282462 206:0.10717538 207:0.089282462 208:0.089282462 209:0.089282462 210:0.089282462 211:0.089282462 212:0.089282462 213:0.089282462 214:0.10717538 215:0.10717538 216:0.1964257 217:0.1964257 218:0.1964257 219:0.1964257 220:0.1964257 221:0.25 222:0.25 223:0.25 224:0.2667 225:0.25 226:0.25 227:0.25 228:0.2667 229:0.2667 230:0.2667 231:0.2833 232:0.2833 233:0.2833 234:0.3 235:0.3 236:0.3 237:0.2333 238:0.2333 239:0.2333 240:0.2333 241:0.2333 242:0.2333 243:0.2333 244:0.2333 245:0.2333 246:0.2333 247:0.2333 248:0.2333 249:0.2333 250:0.2333 251:0.2333 252:0.2333 253:0.2333 254:0.2333 255:0.2333 256:0.2333 257:0.2333 258:0.35 259:0.35 260:0.3667 261:0.3667 262:0.3667 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:0.8667 286:0.8667 287:0.5667 288:0.55 289:0.4 290:0.3833 291:0.3833 292:0.3833 293:0.3833 294:0.3833 295:0.3833 296:0.3833 297:0.3833 298:0.3833 299:0.3667 300:0.3667 301:0.3667 302:0.3667 303:0.3667 304:0.3667 305:0.3667 306:0.3667 307:0.35 308:0.35 309:0.2833 310:0.2833 311:0.2833 312:0.2667 313:0.2833 314:0.2833 315:0.2667 316:0.2833 317:0.2833 318:0.2833 319:0.2833 320:0.2833 321:0.2833 322:0.2833 323:0.2833 324:0.2333 325:0.2167 326:0.2167 327:0.2167 328:0.2167 329:0.2167 330:0.2167 331:0.2167 332:0.2167 333:0.2167 334:0.2167 335:0.2167 336:0.2167 337:0.2167 338:0.2167 339:0.2167 340:0.2167 341:0.2167 342:0.2167 343:0.2167 344:0.2167 345:0.2167 346:0.2167 347:0.2167 348:0.2167 349:0.2167 350:0.2167 351:0.2333 352:1 353:0.5167 354:0.5167 355:0.5167 356:0.5167 357:0.5167 358:0.5167 359:0.5167 360:0.5167
0.3927186106688205 1:0.5167 2:0.5167 3:0.5167 4:0.55 5:0.55 6:1 7:1 8:1 9:1 10:1 11:1 12:1 13:1 14:1 15:1 16:1 17:0.8167 18:0.8167 19:0.6667 20:0.6667 21:0.6667 22:0.6667 23:0.6667 24:0.6667 25:0.6667 26:0.6667 27:0.6667 28:1 29:1 30:1 31:1 32:1 33:0.8 34:0.5333 35:0.25 36:0.25 37:0.25 38:0.25 39:0.25 40:0.25 41:0.25 42:0.25 43:0.25 44:0.25 45:0.25 46:0.25 47:0.25 48:0.25 49:0.25 50:0.25 51:0.2167 52:0.2167 53:0.2167 54:0.2167 55:0.2167 56:0.2167 57:0.2167 58:0.2167 59:0.2167 60:0.2167 61:0.2167 62:0.2167 63:0.2167 64:0.2167 65:0.2167 66:0.2167 67:0.2167 68:0.2167 69:0.2167 70:0.2167 71:0.2167 72:0.3833 73:0.4 74:0.4167 75:0.4167 76:0.4167 77:0.4167 78:0.4167 79:0.4333 80:0.4333 81:0.4333 82:0.4833 83:0.4833 84:0.4833 85:0.4833 86:0.2667 87:0.2667 88:0.2667 89:0.2667 90:0.2667 91:0.2667 92:0.2667 93:0.2667 94:0.2667 95:0.2667 96:0.2667 97:0.2667 98:0.2667 99:0.2667 100:0.2667 101:0.2667 102:0.2667 103:0.2667 104:0.2667 105:0.2667 106:0.2667 107:0.3 108:0.45 109:0.45 110:0.45 111:0.45 112:0.45 113:0.5833 114:0.5833 115:0.7667 116:0.7833 117:0.8667 118:1 119:1 120:1 121:1 122:1 123:1 124:1 125:1 126:1 127:0.75 128:0.75 129:0.75 130:0.5667 131:0.5667 132:0.55 133:0.55 134:0.5 135:0.5 136:0.5 137:0.4333 138:0.4333 139:0.4333 140:0.3667 141:0.25 142:0.21052632 143:0.21052632 144:0.21052632 145:0.21052632 146:0.21052632 147:0.21052632 148:0.21052632 149:0.21052632 150:0.21052632 151:0.21052632 152:0.21052632 153:0.21052632 154:0.21052632 155:0.21052632 156:0.21052632 157:0.1964257 158:0.1964257 159:0.1964257 160:0.1964257 161:0.21431862 162:0.21431862 163:0.21431862 164:0.21431862 165:0.21431862 166:0.21431862 167:0.21431862 168:0.21431862 169:0.1964257 170:0.1964257 171:0.1964257 172:0.1964257 173:0.1964257 174:0.1964257 175:0.1964257 176:0.1964257 177:0.1964257 178:0.1964257 179:0.1964257 180:0.1964257 181:0.1964257 182:0.1964257 183:0.1964257 184:0.1964257 185:0.1964257 186:0.1964257 187:0.1964257 188:0.1964257 189:0.10717538 190:0.10717538 191:0.12496116 192:0.12496116 193:0.12496116 194:0.12496116 195:0.12496116 196:0.12496116 197:0.12496116 198:0.12496116 199:0.12496116 200:0.12496116 201:0.12496116 202:0.12496116 203:0.12496116 204:0.12496116 205:0.12496116 206:0.12496116 207:0.12496116 208:0.12496116 209:0.12496116 210:0.10717538 211:0.10717538 212:0.12496116 213:0.12496116 214:0.12496116 215:0.12496116 216:0.12496116 217:0.12496116 218:0.21431862 219:0.21431862 220:0.24999732 221:0.2833 222:0.2833 223:0.3 224:0.2833 225:0.2833 226:0.3 227:0.2833 228:0.2833 229:0.2833 230:0.3 231:0.3 232:0.3 233:0.25 234:0.25 235:0.25 236:0.25 237:0.25 238:0.25 239:0.25 240:0.25 241:0.25 242:0.25 243:0.25 244:0.25 245:0.25 246:0.25 247:0.25 248:0.25 249:0.25 250:0.25 251:0.3667 252:0.3667 253:0.3667 254:0.3667 255:0.3667 256:0.3667 257:0.3667 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:0.6667 276:0.6667 277:0.65 278:0.65 279:0.65 280:0.65 281:0.65 282:0.65 283:0.55 284:0.4 285:0.3833 286:0.3833 287:0.3833 288:0.3833 289:0.3833 290:0.3833 291:0.3833 292:0.3833 293:0.3833 294:0.3667 295:0.3667 296:0.3667 297:0.3667 298:0.3667 299:0.3667 300:0.3667 301:0.3667 302:0.2833 303:0.2667 304:0.2667 305:0.2667 306:0.2667 307:0.2667 308:0.2667 309:0.2667 310:0.2667 311:0.2167 312:0.2167 313:0.2167 314:0.2167 315:0.2167 316:0.2 317:0.2 318:0.2 319:0.2 320:0.2 321:0.2 322:0.2 323:0.2 324:0.2 325:0.2 326:0.2 327:0.2 328:0.2 329:0.2 330:0.2 331:0.2 332:0.2 333:0.2 334:0.2 335:0.2 336:0.2 337:0.2 338:0.2 339:0.2 340:0.2 341:0.2167 342:1 343:1 344:1 345:1 346:0.5167 347:0.5 348:0.5 349:0.5 350:0.5 351:0.5 352:0.5 353:0.5 354:0.5 355:0.5 356:0.5 357:0.5 358:0.5 359:0.5167 360:0.5167
0.5590978160550186 1:0.1333 2:0.1333 3:0.1333 4:0.1333 5:0.1333 6:0.1333 7:0.1333 8:0.1333 9:0.1333 10:0.1333 11:0.1333 12:0.1333 13:0.1333 14:0.1333 15:0.1333 16:0.1333 17:0.1333 18:0.1333 19:0.1333 20:0.1333 21:0.1333 22:0.1333 23:0.1333 24:0.1333 25:0.1333 26:0.1333 27:0.1333 28:0.1333 29:0.1333 30:0.3333 31:0.3333 32:0.3333 33:0.3333 34:0.2333 35:0.2333 36:0.2167 37:0.2167 38:0.2167 39:0.2167 40:0.2167 41:0.2167 42:0.2167 43:0.2167 44:0.2167 45:0.2167 46:0.2167 47:0.2167 48:0.2167 49:0.2167 50:0.2167 51:0.2167 52:0.2167 53:0.2167 54:0.2167 55:0.2167 56:0.2167 57:0.2333 58:0.2333 59:0.35 60:0.35 61:0.35 62:0.35 63:0.35 64:0.35 65:0.35 66:0.35 67:0.35 68:0.35 69:0.35 70:0.35 71:0.3833 72:0.3833 73:0.3833 74:0.3833 75:0.3833 76:0.6167 77:0.6167 78:0.75 79:0.75 80:0.75 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:0.45 91:0.45 92:0.45 93:0.25 94:0.25 95:0.25 96:0.25 97:0.25 98:0.25 99:0.25 100:0.25 101:0.25 102:0.25 103:0.25 104:0.25 105:0.2333 106:0.2333 107:0.2333 108:0.2333 109:0.2333 110:0.2333 111:0.2333 112:0.2333 113:0.2333 114:0.2333 115:0.2333 116:0.2333 117:0.2333 118:0.2333 119:0.2333 120:0.2333 121:0.2333 122:0.2333 123:0.2333 124:0.2333 125:0.2333 126:0.2333 127:0.2167 128:0.2333 129:0.2333 130:0.2333 131:0.2333 132:0.2333 133:0.2333 134:0.2333 135:0.2333 136:0.2333 137:0.2333 138:0.2333 139:0.2333 140:0.25 141:0.25 142:0.21052632 143:0.21052632 144:0.21052632 145:0.21052632 146:0.21052632 147:0.21052632 148:0.21052632 149:0.21052632 150:0.21052632 151:0.21052632 152:0.31578947 153:0.21052632 154:0.21052632 155:0.36842105 156:0.22810526 157:0.21431862 158:0.35714056 159:0.35714056 160:0.35714056 161:0.35714056 162:0.35714056 163:0.35714056 164:0.4999625 165:0.4999625 166:0.51785542 167:0.62499866 168:0.60710574 169:0.7321419 170:0.91074968 171:0.91074968 172:0.92853546 173:1 174:1 175:1 176:1 177:1 178:1 179:1 180:0.33924764 181:0.33924764 182:0.33924764 183:0.17853278 184:0.17853278 185:0.17853278 186:0.17853278 187:0.17853278 188:0.17853278 189:0.17853278 190:0.17853278 191:0.17853278 192:0.17853278 193:0.17853278 194:0.12496116 195:0.12496116 196:0.12496116 197:0.12496116 198:0.12496116 199:0.12496116 200:0.12496116 201:0.10717538 202:0.10717538 203:0.089282462 204:0.089282462 205:0.089282462 206:0.071389541 207:0.071389541 208:0.071389541 209:0.071389541 210:0.071389541 211:0.071389541 212:0.071389541 213:0.071389541 214:0.071389541 215:0.071389541 216:0.071389541 217:0.071389541 218:0.071389541 219:0.071389541 220:0.071389541 221:0.1333 222:0.1333 223:0.1333 224:0.1333 225:0.1333 226:0.1333 227:0.1333 228:0.1333 229:0.1333 230:0.1333 231:0.1333 232:0.1333 233:0.1333 234:0.1333 235:0.1333 236:0.1333 237:0.1333 238:0.1333 239:0.15 240:0.15 241:0.15 242:0.15 243:0.15 244:0.15 245:0.15 246:0.15 247:0.15 248:0.15 249:0.15 250:0.15 251:0.15 252:0.15 253:0.15 254:0.15 255:0.15 256:0.15 257:0.1667 258:0.2167 259:0.2 260:0.2167 261:0.2167 262:0.2 263:0.2 264:0.2 265:0.3333 266:0.3333 267:0.35 268:0.3833 269:0.3833 270:1 271:1 272:0.55 273:0.55 274:0.55 275:0.55 276:0.5333 277:0.5333 278:0.5333 279:0.5333 280:0.5333 281:0.5333 282:0.5333 283:0.5333 284:0.5333 285:0.6 286:0.6 287:0.4167 288:0.5833 289:0.4167 290:0.4167 291:0.4167 292:0.4167 293:0.4167 294:0.4167 295:0.3833 296:0.3833 297:0.3833 298:0.3833 299:0.3667 300:0.3667 301:0.35 302:0.35 303:0.35 304:0.35 305:0.35 306:0.35 307:0.35 308:0.35 309:0.35 310:0.35 311:0.35 312:0.35 313:0.35 314:0.4333 315:0.4333 316:0.1667 317:0.15 318:0.1667 319:0.1667 320:0.1667 321:0.1667 322:0.1667 323:0.1667 324:0.1667 325:0.1667 326:0.1667 327:0.1667 328:0.1667 329:0.1667 330:0.1667 331:0.1667 332:0.1667 333:0.1667 334:0.1667 335:0.1667 336:0.1667 337:0.1667 338:0.1667 339:0.15 340:0.1667 341:0.1667 342:0.15 343:0.15 344:0.15 345:0.15 346:0.15 347:0.15 348:0.15 349:0.15 350:0.15 351:0.15 352:0.1333 353:0.1333 354:0.1333 355:0.1333 356:0.1333 357:0.1333 358:0.1333 359:0.1333 360:0.1333
0.2424910957736602 1:0.3833 2:0.3833 3:0.3833 4:0.3833 5:0.1167 6:0.1167 7:0.1167 8:0.1167 9:0.1167 10:0.1167 11:0.1167 12:0.1167 13:0.1167 14:0.1167 15:0.1167 16:0.1333 17:0.1333 18:0.4 19:0.4 20:0.1167 21:0.1167 22:0.1333 23:0.1333 24:0.4 25:0.3 26:0.3167 27:0.1167 28:0.1167 29:0.1167 30:0.1333 31:0.3167 32:0.3 33:0.1167 34:0.1167 35:0.1167 36:0.1167 37:0.1167 38:0.1167 39:0.1167 40:0.2 41:0.2 42:0.2 43:0.2 44:0.2 45:0.2 46:0.2 47:0.2 48:0.2 49:0.2 50:0.2 51:0.2 52:0.2 53:0.2 54:0.2 55:0.1833 56:0.1833 57:0.3167 58:0.3167 59:0.3167 60:0.3167 61:0.3167 62:0.3167 63:0.3167 64:0.3167 65:0.3167 66:0.3167 67:0.3167 68:0.3167 69:0.3167 70:0.3167 71:0.3167 72:0.3333 73:0.45 74:0.4667 75:0.45 76:0.45 77:0.45 78:0.5833 79:0.6 80:0.7167 81:0.7167 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:0.7833 93:0.7833 94:0.6 95:0.4333 96:0.4333 97:0.2333 98:0.2333 99:0.2333 100:0.2333 101:0.2333 102:0.2333 103:0.25 104:0.25 105:0.2333 106:0.25 107:0.25 108:0.25 109:0.2333 110:0.2333 111:0.2333 112:0.2333 113:0.2333 114:0.2333 115:0.2167 116:0.2167 117:0.2167 118:0.2167 119:0.2333 120:0.2167 121:0.2167 122:0.2167 123:0.2167 124:0.2167 125:0.2167 126:0.2167 127:0.2167 128:0.2167 129:0.2167 130:0.2167 131:0.2167 132:0.2167 133:0.2167 134:0.2167 135:0.2167 136:0.2167 137:0.2167 138:0.2167 139:0.2167 140:0.2167 141:0.2167 142:0.19294737 143:0.19294737 144:0.19294737 145:0.21052632 146:0.21052632 147:0.21052632 148:0.22810526 149:0.22810526 150:0.22810526 151:0.22810526 152:0.22810526 153:0.22810526 154:0.28073684 155:0.28073684 156:0.29821053 157:0.30356894 158:0.32146186 159:0.33924764 160:0.35714056 161:0.37503348 162:0.37503348 163:0.37503348 164:0.37503348 165:0.37503348 166:0.37503348 167:0.37503348 168:0.37503348 169:0.58931996 170:0.62499866 171:0.6964632 172:0.78571352 173:0.89285676 174:0.9643213 175:1 176:1 177:0.75003482 178:0.75003482 179:0.75003482 180:0.75003482 181:0.75003482 182:0.53574834 183:0.1964257 184:0.1964257 185:0.1964257 186:0.1964257 187:0.17853278 188:0.17853278 189:0.17853278 190:0.17853278 191:0.17853278 192:0.17853278 193:0.1964257 194:0.1964257 195:0.17853278 196:0.1964257 197:0.14285408 198:0.14285408 199:0.14285408 200:0.14285408 201:0.14285408 202:0.14285408 203:0.14285408 204:0.12496116 205:0.12496116 206:0.12496116 207:0.10717538 208:0.10717538 209:0.10717538 210:0.089282462 211:0.089282462 212:0.089282462 213:0.10717538 214:0.10717538 215:0.10717538 216:0.089282462 217:0.089282462 218:0.10717538 219:0.10717538 220:0.10717538 221:0.1667 222:0.15 223:0.1667 224:0.1667 225:0.1667 226:0.1667 227:0.1667 228:0.15 229:0.1667 230:0.1667 231:0.1667 232:0.15 233:0.15 234:0.15 235:0.1667 236:0.1667 237:0.1667 238:0.1667 239:0.1667 240:0.1833 241:0.1667 242:0.1833 243:0.2 244:0.1833 245:0.1833 246:0.1667 247:0.2333 248:0.2333 249:0.1833 250:0.1667 251:0.1667 252:0.2333 253:0.2333 254:0.2333 255:0.2333 256:0.2333 257:0.2333 258:0.2333 259:0.2333 260:0.2333 261:0.2333 262:0.3667 263:0.3833 264:0.3667 265:0.4 266:0.55 267:0.7 268:0.8333 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:0.9167 278:0.7667 279:0.7667 280:0.7667 281:0.6167 282:0.6167 283:0.6167 284:0.6167 285:0.5833 286:0.5833 287:0.5667 288:0.5333 289:0.5167 290:0.4833 291:0.4667 292:0.4333 293:0.2833 294:0.2833 295:0.2667 296:0.2667 297:0.2833 298:0.2667 299:0.2667 300:0.2833 301:0.2833 302:0.2667 303:0.2833 304:0.2833 305:0.2667 306:0.2833 307:0.2833 308:0.2667 309:0.2667 310:0.25 311:0.1667 312:0.1667 313:0.1667 314:0.1667 315:0.1667 316:0.25 317:0.1667 318:0.1667 319:0.1667 320:0.2333 321:0.2333 322:0.1667 323:0.1667 324:0.1667 325:0.2333 326:0.2333 327:0.1667 328:0.1667 329:0.1667 330:0.1667 331:0.1667 332:0.1667 333:0.1667 334:0.1667 335:0.1667 336:0.2333 337:0.2333 338:0.2333 339:0.2333 340:0.2333 341:0.2333 342:0.2333 343:0.2333 344:0.2333 345:0.2333 346:0.2333 347:0.2333 348:0.25 349:0.3167 350:0.3167 351:0.3167 352:0.3167 353:0.3167 354:0.3167 355:0.3167 356:0.3167 357:0.3833 358:0.3833 359:0.3833 360:0.3833
0.1791208155313824 1:1 2:1 3:1 4:1 5:1 6:1 7:1 8:1 9:1 10:1 11:1 12:1 13:0.5167 14:0.5167 15:0.5167 16:0.5167 17:0.5 18:0.3833 19:0.3833 20:0.3833 21:0.3833 22:0.3833 23:0.3833 24:0.3833 25:0.3833 26:0.3833 27:0.3833 28:0.3833 29:0.5167 30:0.5 31:0.5 32:0.3333 33:0.3333 34:0.3167 35:0.2833 36:0.2833 37:0.3167 38:0.2833 39:0.2833 40:0.2833 41:0.2833 42:0.2833 43:0.2833 44:0.2833 45:0.2833 46:0.2833 47:0.2667 48:0.2667 49:0.2667 50:0.2667 51:0.2667 52:0.2667 53:0.2667 54:0.15 55:0.15 56:0.1333 57:0.1333 58:0.1333 59:0.1333 60:0.1333 61:0.1333 62:0.1333 63:0.15 64:0.15 65:0.1333 66:0.1333 67:0.1333 68:0.1333 69:0.15 70:0.15 71:0.15 72:0.1333 73:0.1333 74:0.1333 75:0.15 76:0.15 77:0.15 78:0.1333 79:0.1333 80:0.1333 81:0.1333 82:0.1333 83:0.1333 84:0.1333 85:0.1333 86:0.1333 87:0.1333 88:0.1333 89:0.1333 90:0.1333 91:0.1333 92:0.1333 93:0.1333 94:0.1333 95:0.1333 96:0.08333 97:0.08333 98:0.08333 99:0.08333 100:0.08333 101:0.08333 102:0.08333 103:0.1 104:0.1 105:0.1 106:0.08333 107:0.1 108:0.1 109:0.1 110:0.1 111:0.1 112:0.1 113:0.1 114:0.1 115:0.1 116:0.1 117:0.1 118:0.1 119:0.1 120:0.1 121:0.1 122:0.1 123:0.1 124:0.1 125:0.08333 126:0.1 127:0.1 128:0.1 129:0.1 130:0.1 131:0.1 132:0.1 133:0.08333 134:0.08333 135:0.08333 136:0.08333 137:0.08333 138:0.08333 139:0.08333 140:0.1 141:0.1 142:0.052631579 143:0.052631579 144:0.052631579 145:0.052631579 146:0.070210526 147:0.070210526 148:0.070210526 149:0.070210526 150:0.070210526 151:0.070210526 152:0.070210526 153:0.070210526 154:0.070210526 155:0.070210526 156:0.070210526 157:0.035710842 158:0.035710842 159:0.053603763 160:0.053603763 161:0.053603763 162:0.053603763 163:0.053603763 164:0.053603763 165:0.053603763 166:0.053603763 167:0.053603763 168:0.053603763 169:0.053603763 170:0.071389541 171:0.071389541 172:0.089282462 173:0.89285676 174:0.89285676 175:1 176:1 177:1 178:1 179:1 180:1 181:0.7321419 182:0.7321419 183:0.71424898 184:0.71424898 185:0.71424898 186:0.51785542 187:0.51785542 188:0.51785542 189:0.51785542 190:0.51785542 191:0.51785542 192:0.51785542 193:0.51785542 194:0.71424898 195:0.71424898 196:0.57142704 197:0.57142704 198:0.57142704 199:0.57142704 200:0.57142704 201:0.57142704 202:0.57142704 203:0.57142704 204:0.57142704 205:0.57142704 206:0.64289158 207:0.64289158 208:0.64289158 209:0.58931996 210:0.28567602 211:0.28567602 212:0.28567602 213:0.28567602 214:0.28567602 215:0.28567602 216:0.28567602 217:0.28567602 218:0.28567602 219:0.14285408 220:0.14285408 221:0.2 222:0.2 223:0.1833 224:0.2 225:0.2 226:0.2 227:0.2 228:0.2 229:0.2 230:0.2 231:0.2 232:0.2 233:0.2 234:0.2 235:0.2 236:0.2 237:0.2 238:0.2 239:0.2 240:0.2 241:0.2 242:0.1833 243:0.2 244:0.2 245:0.2167 246:0.2167 247:0.2167 248:0.2167 249:0.2167 250:0.2167 251:0.2167 252:0.2167 253:0.2167 254:0.2167 255:0.2167 256:0.2167 257:0.2167 258:0.2167 259:0.2167 260:0.2167 261:0.2333 262:0.2167 263:0.2167 264:0.2167 265:0.3167 266:0.3167 267:0.5833 268:0.5833 269:0.75 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:0.9333 278:0.7833 279:0.6 280:0.4667 281:0.4667 282:0.4667 283:0.3667 284:0.3667 285:0.3667 286:0.3667 287:0.3667 288:0.3667 289:0.3667 290:0.3667 291:0.2667 292:0.25 293:0.25 294:0.2333 295:0.2167 296:0.2167 297:0.1667 298:0.1667 299:0.1667 300:0.15 301:0.15 302:0.15 303:0.1667 304:0.1667 305:0.1667 306:0.15 307:0.15 308:0.1667 309:0.1667 310:0.1667 311:0.1667 312:0.15 313:0.1667 314:0.1667 315:0.1667 316:0.1667 317:0.1667 318:0.15 319:0.1667 320:0.1667 321:0.1667 322:0.15 323:0.15 324:0.15 325:0.1667 326:0.1667 327:0.1667 328:0.1667 329:0.1667 330:0.2167 331:0.2167 332:0.2167 333:0.2833 334:0.2833 335:0.2833 336:1 337:1 338:1 339:1 340:1 341:1 342:1 343:1 344:1 345:1 346:1 347:1 348:1 349:1 350:1 351:1 352:1 353:1 354:1 355:1 356:1 357:1 358:1 359:1 360:1
0.9451452458578892 1:0.1333 2:0.1333 3:0.1333 4:0.1333 5:0.4333 6:0.4333 7:0.4333 8:0.4333 9:0.4167 10:0.4167 11:0.4167 12:0.4167 13:0.4167 14:0.4167 15:0.4167 16:0.4167 17:0.3833 18:0.25 19:0.2333 20:0.2333 21:0.2167 22:0.2167 23:0.2167 24:0.2167 25:0.2167 26:0.2167 27:0.2167 28:0.2 29:0.2 30:0.2167 31:0.2167 32:0.2 33:0.2167 34:0.2167 35:0.2167 36:0.2167 37:0.2 38:0.2167 39:0.2167 40:0.2167 41:0.2 42:0.2167 43:0.2167 44:0.2167 45:0.2 46:0.2 47:0.2667 48:0.2667 49:0.2667 50:0.2667 51:0.2667 52:0.2667 53:0.2667 54:0.2667 55:0.2667 56:0.2667 57:0.2667 58:0.2667 59:0.2667 60:0.3167 61:0.3167 62:0.3167 63:0.3167 64:0.3167 65:0.3167 66:0.3333 67:0.3333 68:0.3167 69:0.3333 70:0.4 71:0.4 72:0.4 73:0.4 74:0.4167 75:0.5833 76:0.5833 77:0.5833 78:0.5833 79:0.5833 80:0.5833 81:0.7833 82:0.7833 83:0.7833 84:0.7833 85:0.9667 86:0.9667 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:0.5167 99:0.5333 100:0.3833 101:0.2333 102:0.2167 103:0.2167 104:0.2167 105:0.2167 106:0.2167 107:0.2167 108:0.2167 109:0.2167 110:0.2167 111:0.2167 112:0.2167 113:0.2167 114:0.2167 115:0.2167 116:0.2167 117:0.2167 118:0.2167 119:0.2167 120:0.2167 121:0.2167 122:0.2167 123:0.2167 124:0.2167 125:0.2167 126:0.2167 127:0.1 128:0.1 129:0.1 130:0.1 131:0.1 132:0.1 133:0.08333 134:0.08333 135:0.08333 136:0.08333 137:0.08333 138:0.08333 139:0.08333 140:0.08333 141:0.08333 142:0.035084211 143:0.035084211 144:0.035084211 145:0.035084211 146:0.035084211 147:0.035084211 148:0.035084211 149:0.035084211 150:0.035084211 151:0.035084211 152:0.035084211 153:0.035084211 154:0.035084211 155:0.035084211 156:0.035084211 157:0.017850064 158:0.017850064 159:0.017850064 160:0.017850064 161:0.017850064 162:0.017850064 163:0.017850064 164:0.017850064 165:0.017850064 166:0.017850064 167:0.017850064 168:0.017850064 169:0.017850064 170:0.017850064 171:0.017850064 172:0.017850064 173:0.017850064 174:0.017850064 175:0.017850064 176:0.017850064 177:0.017850064 178:0.017850064 179:0.017850064 180:0.017850064 181:0.017850064 182:0.017850064 183:0.017850064 184:0.017850064 185:0.017850064 186:0.55353412 187:0.55353412 188:0.55353412 189:0.55353412 190:1 191:0.64289158 192:0.64289158 193:0.64289158 194:0.64289158 195:0.48217672 196:0.48217672 197:0.4642838 198:0.48217672 199:0.48217672 200:0.48217672 201:0.48217672 202:0.48217672 203:0.48217672 204:0.51785542 205:0.4286051 206:0.41071218 207:0.41071218 208:0.41071218 209:0.41071218 210:0.41071218 211:0.26789024 212:0.26789024 213:0.26789024 214:0.26789024 215:0.26789024 216:0.26789024 217:0.26789024 218:0.26789024 219:0.053603763 220:0.053603763 221:0.1167 222:0.1167 223:0.1167 224:0.1333 225:0.1333 226:0.1333 227:0.1333 228:0.1167 229:0.1167 230:0.1333 231:0.1333 232:0.1333 233:0.1333 234:0.1333 235:0.1333 236:0.1167 237:0.1333 238:0.1333 239:0.1333 240:0.1333 241:0.1333 242:0.1167 243:0.1167 244:0.1167 245:0.1333 246:0.1333 247:0.1333 248:0.1167 249:0.1167 250:0.1167 251:0.1167 252:0.1333 253:0.1333 254:0.1333 255:0.1333 256:0.1333 257:0.1333 258:0.1333 259:0.1333 260:0.1333 261:0.3 262:0.3 263:0.3 264:0.3 265:0.3 266:0.3 267:0.3 268:0.3 269:0.3 270:0.4667 271:0.4667 272:0.65 273:0.2833 274:0.2833 275:0.2833 276:0.2833 277:0.2833 278:0.2833 279:0.2833 280:0.2833 281:0.2833 282:0.2833 283:0.2833 284:0.2833 285:0.2833 286:0.2833 287:0.2833 288:0.2833 289:0.5333 290:0.5333 291:0.5333 292:0.5333 293:0.5333 294:0.5333 295:0.5333 296:0.5333 297:0.5333 298:0.5333 299:0.5333 300:0.5333 301:0.5333 302:0.75 303:0.4833 304:0.4833 305:0.4833 306:0.4833 307:0.4833 308:0.2667 309:0.2667 310:0.25 311:0.25 312:0.25 313:0.2333 314:0.2333 315:0.25 316:0.25 317:0.25 318:0.25 319:0.25 320:0.25 321:0.25 322:0.25 323:0.25 324:0.25 325:0.2333 326:0.25 327:0.25 328:0.25 329:0.2333 330:0.15 331:0.15 332:0.15 333:0.1333 334:0.1333 335:0.1333 336:0.1333 337:0.1333 338:0.1333 339:0.1333 340:0.1333 341:0.1333 342:0.1333 343:0.1333 344:0.1333 345:0.1333 346:0.1333 347:0.1333 348:0.1333 349:0.1333 350:0.1333 351:0.1333 352:0.1333 353:0.1333 354:0.1333 355:0.1333 356:0.1333 357:0.1333 358:0.1333 359:0.1333 360:0.1333
0.694538071472227 1:0.2833 2:0.2833 3:1 4:1 5:1 6:1 7:0.8667 8:0.75 9:0.75 10:0.6 11:0.6 12:0.4833 13:0.4833 14:0.4833 15:0.45 16:0.35 17:0.35 18:0.3667 19:0.3 20:0.3 21:0.3 22:0.3 23:0.2833 24:0.2833 25:0.2833 26:0.2833 27:0.2833 28:0.2833 29:0.3 30:0.2833 31:0.2833 32:0.3 33:0.2833 34:0.2833 35:0.3 36:0.2833 37:0.2833 38:0.2833 39:0.3 40:0.3 41:0.3 42:0.3 43:0.3 44:0.3 45:0.3 46:0.3 47:0.3 48:0.3 49:0.3 50:0.3 51:0.3 52:0.3 53:0.3 54:0.3 55:0.3 56:0.3 57:0.3167 58:0.3167 59:0.3333 60:0.3333 61:0.3333 62:0.3333 63:0.3167 64:0.3333 65:0.3333 66:0.3167 67:0.3333 68:0.3333 69:0.3333 70:0.3333 71:0.3333 72:0.3333 73:0.3333 74:0.3167 75:0.3333 76:0.3333 77:0.3333 78:0.3333 79:0.55 80:0.55 81:0.55 82:0.5667 83:0.5667 84:0.5833 85:0.5667 86:0.7667 87:0.7667 88:0.7667 89:0.7667 90:0.7667 91:0.7833 92:0.9667 93:1 94:1 95:1 96:1 97:1 98:1 99:0.7833 100:0.7833 101:0.65 102:0.4833 103:0.4833 104:0.4833 105:0.4667 106:0.4833 107:0.4667 108:0.4833 109:0.4667 110:0.4833 111:0.2667 112:0.25 113:0.25 114:0.25 115:0.25 116:0.25 117:0.25 118:0.25 119:0.25 120:0.25 121:0.25 122:0.25 123:0.1667 124:0.1667 125:0.1667 126:0.1667 127:0.1667 128:0.1667 129:0.1667 130:0.1667 131:0.1667 132:0.1667 133:0.1667 134:0.1667 135:0.1667 136:0.1667 137:0.1667 138:0.1667 139:0.1667 140:0.1667 141:0.1667 142:0.12284211 143:0.12284211 144:0.12284211 145:0.12284211 146:0.12284211 147:0.12284211 148:0.12284211 149:0.12284211 150:0.14031579 151:0.14031579 152:0.17547368 153:0.17547368 154:0.17547368 155:0.15789474 156:0.15789474 157:0.14285408 158:0.14285408 159:0.14285408 160:0.14285408 161:0.14285408 162:0.14285408 163:0.14285408 164:0.14285408 165:0.14285408 166:0.14285408 167:0.14285408 168:0.14285408 169:0.14285408 170:0.14285408 171:0.14285408 172:0.14285408 173:0.14285408 174:0.14285408 175:0.14285408 176:0.14285408 177:0.14285408 178:0.071389541 179:0.071389541 180:0.071389541 181:0.071389541 182:0.071389541 183:0.071389541 184:0.071389541 185:0.071389541 186:0.071389541 187:0.071389541 188:0.071389541 189:0.071389541 190:0.071389541 191:0.071389541 192:0.071389541 193:0.071389541 194:0.071389541 195:0.071389541 196:0.071389541 197:0.071389541 198:0.071389541 199:0.071389541 200:0.071389541 201:0.071389541 202:0.071389541 203:0.071389541 204:0.071389541 205:0.071389541 206:0.071389541 207:0.071389541 208:0.071389541 209:0.071389541 210:0.071389541 211:0.071389541 212:0.071389541 213:0.071389541 214:0.071389541 215:0.071389541 216:0.160747 217:0.14285408 218:0.160747 219:0.160747 220:0.160747 221:0.2 222:0.2167 223:0.2167 224:0.2167 225:0.2 226:0.2 227:0.2167 228:0.2167 229:0.2167 230:0.2167 231:0.2167 232:0.2333 233:0.2333 234:0.2333 235:0.4167 236:0.4 237:0.4167 238:0.4 239:0.4167 240:0.4167 241:0.4 242:0.3667 243:0.3667 244:0.35 245:0.35 246:0.3667 247:0.35 248:0.35 249:0.3667 250:0.35 251:0.35 252:0.3667 253:0.35 254:0.3667 255:0.35 256:0.35 257:0.3667 258:0.5 259:0.5 260:0.5 261:0.5167 262:0.65 263:0.65 264:0.8333 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:0.9 279:0.9 280:0.7 281:0.5167 282:0.5167 283:0.5167 284:0.5167 285:0.5167 286:0.35 287:0.35 288:0.5167 289:0.35 290:0.3667 291:0.35 292:0.35 293:0.7167 294:0.1833 295:0.1833 296:0.1833 297:0.1833 298:0.1833 299:0.1833 300:0.1833 301:0.1833 302:0.1833 303:0.1833 304:0.1833 305:0.1833 306:0.1833 307:0.1833 308:0.1833 309:0.1833 310:0.1833 311:0.1833 312:0.1833 313:0.1833 314:0.1833 315:0.1833 316:0.1833 317:0.1833 318:0.1833 319:0.1833 320:0.1833 321:0.1833 322:0.1833 323:0.1833 324:0.1833 325:0.1833 326:0.1833 327:0.1833 328:0.1833 329:0.1833 330:0.1833 331:0.1833 332:0.2167 333:0.2167 334:0.2167 335:0.2167 336:0.2167 337:0.2167 338:0.2167 339:0.2167 340:0.2167 341:0.2167 342:0.2167 343:0.2167 344:0.2167 345:0.2167 346:0.2167 347:0.2167 348:0.2167 349:0.2167 350:0.2167 351:0.2833 352:0.2833 353:0.2833 354:0.2833 355:0.2833 356:0.2833 357:0.2833 358:0.2833 359:0.2833 360:0.2833
1.511082805737294 1:1 2:1 3:1 4:1 5:1 6:0.8833 7:0.7667 8:0.6333 9:0.5833 10:0.5167 11:0.5167 12:0.4833 13:0.3667 14:0.3667 15:0.3667 16:0.35 17:0.3333 18:0.3167 19:0.3 20:0.3 21:0.3 22:0.3 23:0.3 24:0.3 25:0.3 26:0.3 27:0.3 28:0.3 29:0.3 30:0.3 31:0.3 32:0.3 33:0.3 34:0.3 35:0.3 36:0.3 37:0.3 38:0.3167 39:0.3167 40:0.3 41:0.3167 42:0.3167 43:0.3167 44:0.3167 45:0.3167 46:0.3167 47:0.3167 48:0.3167 49:0.3167 50:0.3167 51:0.3167 52:0.3 53:0.3167 54:0.3167 55:0.3167 56:0.3333 57:0.3333 58:0.3167 59:0.3333 60:0.3333 61:0.3333 62:0.3333 63:0.3167 64:0.3333 65:0.3333 66:0.3167 67:0.3333 68:0.3333 69:0.3333 70:0.3333 71:0.3333 72:0.3333 73:0.3333 74:0.3167 75:0.3333 76:0.55 77:0.55 78:0.55 79:0.55 80:0.55 81:0.55 82:0.7333 83:0.7333 84:0.7667 85:0.7667 86:0.7667 87:0.7667 88:0.7667 89:0.7667 90:0.8667 91:0.9667 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:0.4667 101:0.4667 102:0.4667 103:0.4667 104:0.4667 105:0.3 106:0.2833 107:0.2833 108:0.25 109:0.2333 110:0.2333 111:0.2333 112:0.2333 113:0.2333 114:0.2333 115:0.2333 116:0.2333 117:0.2333 118:0.2333 119:0.2333 120:0.15 121:0.15 122:0.15 123:0.15 124:0.15 125:0.15 126:0.15 127:0.15 128:0.15 129:0.15 130:0.15 131:0.15 132:0.15 133:0.15 134:0.15 135:0.15 136:0.15 137:0.15 138:0.15 139:0.15 140:0.15 141:0.15 142:0.10526316 143:0.10526316 144:0.10526316 145:0.10526316 146:0.10526316 147:0.10526316 148:0.10526316 149:0.10526316 150:0.10526316 151:0.10526316 152:0.10526316 153:0.14031579 154:0.14031579 155:0.14031579 156:0.14031579 157:0.12496116 158:0.12496116 159:0.12496116 160:0.12496116 161:0.12496116 162:0.12496116 163:0.12496116 164:0.12496116 165:0.12496116 166:0.12496116 167:0.12496116 168:0.12496116 169:0.12496116 170:0.12496116 171:0.12496116 172:0.12496116 173:0.089282462 174:0.089282462 175:0.089282462 176:0.089282462 177:0.089282462 178:0.053603763 179:0.053603763 180:0.053603763 181:0.053603763 182:0.053603763 183:0.053603763 184:0.053603763 185:0.053603763 186:0.035710842 187:0.035710842 188:0.035710842 189:0.035710842 190:0.035710842 191:0.035710842 192:0.053603763 193:0.053603763 194:0.035710842 195:0.035710842 196:0.035710842 197:0.053603763 198:0.053603763 199:0.053603763 200:0.053603763 201:0.053603763 202:0.035710842 203:0.053603763 204:0.053603763 205:0.053603763 206:0.053603763 207:0.053603763 208:0.053603763 209:0.053603763 210:0.035710842 211:0.035710842 212:0.035710842 213:0.053603763 214:0.053603763 215:0.053603763 216:0.053603763 217:0.053603763 218:0.035710842 219:0.035710842 220:0.035710842 221:0.1 222:0.1 223:0.1 224:0.2 225:0.2 226:0.2 227:0.2 228:0.2 229:0.1833 230:0.2 231:0.2 232:0.2 233:0.2 234:0.2167 235:0.2167 236:0.2167 237:0.2333 238:0.2333 239:0.2333 240:0.4167 241:0.4 242:0.4167 243:0.4 244:0.4167 245:0.4 246:0.4 247:0.4167 248:0.3667 249:0.3667 250:0.3667 251:0.3667 252:0.3667 253:0.3667 254:0.3667 255:0.3667 256:0.3667 257:0.3667 258:0.3667 259:0.3667 260:0.5167 261:0.5167 262:0.5167 263:0.6667 264:0.6667 265:0.8167 266:0.9833 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:0.9167 279:0.9167 280:0.9167 281:0.7167 282:0.7167 283:0.5333 284:0.5333 285:0.5333 286:0.5333 287:0.5333 288:0.3667 289:0.3667 290:0.3667 291:0.3667 292:0.3667 293:0.3667 294:0.3667 295:0.3667 296:0.3667 297:0.3667 298:0.2 299:0.2 300:0.2167 301:0.2167 302:0.2 303:0.2 304:0.2 305:0.2 306:0.2 307:0.2 308:0.2 309:0.2 310:0.2 311:0.2 312:0.2 313:0.2 314:0.2 315:0.2 316:0.2 317:0.2 318:0.2 319:0.2 320:0.2 321:0.2 322:0.2 323:0.2 324:0.2 325:0.2167 326:0.2 327:0.2 328:0.2 329:0.2 330:0.2167 331:0.2167 332:0.2167 333:0.2333 334:0.2333 335:0.2333 336:0.2333 337:0.2333 338:0.2333 339:0.2333 340:0.2333 341:0.2333 342:0.2333 343:0.2333 344:0.2333 345:0.2333 346:0.2333 347:0.2333 348:0.25 349:0.3 350:0.3 351:0.3 352:0.3 353:0.3 354:0.3 355:0.3 356:0.3 357:0.3 358:0.3 359:0.3 360:0.5833
0.3538394096402166 1:1 2:1 3:1 4:1 5:0.8667 6:0.6833 7:0.6833 8:0.6167 9:0.5333 10:0.4833 11:0.4333 12:0.3833 13:0.35 14:0.3333 15:0.3 16:0.2833 17:0.2833 18:0.2833 19:0.2833 20:0.2833 21:0.2833 22:0.2833 23:0.2833 24:0.2833 25:0.2833 26:0.2833 27:0.2833 28:0.2833 29:0.2833 30:0.2833 31:0.2833 32:0.2833 33:0.2833 34:0.2833 35:0.2833 36:0.3 37:0.2833 38:0.3 39:0.3 40:0.2833 41:0.3 42:0.3 43:0.2833 44:0.2833 45:0.3 46:0.3 47:0.3 48:0.3 49:0.3 50:0.3 51:0.3 52:0.3 53:0.3 54:0.3 55:0.3 56:0.3 57:0.3167 58:0.3167 59:0.3167 60:0.3167 61:0.3167 62:0.3167 63:0.3167 64:0.3167 65:0.3167 66:0.3167 67:0.3167 68:0.3167 69:0.3167 70:0.3167 71:0.3167 72:0.3167 73:0.3167 74:0.3167 75:0.5333 76:0.5333 77:0.5333 78:0.5333 79:0.5333 80:0.55 81:0.55 82:0.7167 83:0.7167 84:0.75 85:0.75 86:0.75 87:0.75 88:0.75 89:0.75 90:0.7667 91:0.95 92:1 93:1 94:1 95:0.9833 96:0.9833 97:0.9833 98:0.7667 99:0.7667 100:0.6167 101:0.6167 102:0.6167 103:0.45 104:0.45 105:0.45 106:0.45 107:0.45 108:0.45 109:0.2333 110:0.2333 111:0.2333 112:0.2333 113:0.2333 114:0.2333 115:0.2333 116:0.2333 117:0.2333 118:0.2333 119:0.2333 120:0.2333 121:0.2333 122:0.2333 123:0.2333 124:0.2333 125:0.2333 126:0.2333 127:0.2167 128:0.15 129:0.15 130:0.15 131:0.1667 132:0.1667 133:0.1667 134:0.15 135:0.1667 136:0.1667 137:0.1667 138:0.1667 139:0.1667 140:0.15 141:0.1667 142:0.12284211 143:0.12284211 144:0.12284211 145:0.10526316 146:0.10526316 147:0.12284211 148:0.12284211 149:0.12284211 150:0.10526316 151:0.10526316 152:0.10526316 153:0.12284211 154:0.12284211 155:0.12284211 156:0.14031579 157:0.12496116 158:0.12496116 159:0.12496116 160:0.12496116 161:0.12496116 162:0.12496116 163:0.12496116 164:0.12496116 165:0.12496116 166:0.12496116 167:0.12496116 168:0.12496116 169:0.12496116 170:0.12496116 171:0.12496116 172:0.12496116 173:0.12496116 174:0.12496116 175:0.12496116 176:0.12496116 177:0.12496116 178:0.12496116 179:0.10717538 180:0.10717538 181:0.10717538 182:0.10717538 183:0.10717538 184:0.089282462 185:0.053603763 186:0.053603763 187:0.053603763 188:0.053603763 189:0.053603763 190:0.053603763 191:0.053603763 192:0.053603763 193:0.053603763 194:0.053603763 195:0.053603763 196:0.071389541 197:0.071389541 198:0.071389541 199:0.071389541 200:0.053603763 201:0.053603763 202:0.071389541 203:0.071389541 204:0.071389541 205:0.071389541 206:0.071389541 207:0.053603763 208:0.053603763 209:0.053603763 210:0.071389541 211:0.071389541 212:0.071389541 213:0.053603763 214:0.053603763 215:0.053603763 216:0.053603763 217:0.053603763 218:0.053603763 219:0.053603763 220:0.071389541 221:0.1333 222:0.1333 223:0.2167 224:0.2167 225:0.2 226:0.2 227:0.2167 228:0.2167 229:0.2167 230:0.2167 231:0.2167 232:0.2333 233:0.2333 234:0.2333 235:0.25 236:0.25 237:0.25 238:0.4333 239:0.4167 240:0.4167 241:0.4167 242:0.4167 243:0.4333 244:0.4167 245:0.3667 246:0.3667 247:0.3667 248:0.3667 249:0.3667 250:0.4333 251:0.3667 252:0.4833 253:0.3667 254:0.3667 255:0.3667 256:0.3667 257:0.3667 258:0.5167 259:0.5167 260:0.5167 261:0.5167 262:0.6667 263:0.6667 264:0.85 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:0.9333 278:0.9333 279:0.7333 280:0.7333 281:0.5333 282:0.5333 283:0.5333 284:0.5333 285:0.3667 286:0.3667 287:0.3667 288:0.3667 289:0.3667 290:0.3833 291:0.3667 292:0.3833 293:0.3667 294:0.2333 295:0.2167 296:0.2167 297:0.2167 298:0.2 299:0.2 300:0.2167 301:0.2167 302:0.2 303:0.2 304:0.2 305:0.2 306:0.2 307:0.2 308:0.2 309:0.2 310:0.2167 311:0.2 312:0.2 313:0.2 314:0.2 315:0.2 316:0.2 317:0.2 318:0.2 319:0.2167 320:0.2167 321:0.2 322:0.2 323:0.2 324:0.2167 325:0.2167 326:0.2167 327:0.2333 328:0.2333 329:0.2333 330:0.2333 331:0.2333 332:0.2333 333:0.2333 334:0.2333 335:0.2333 336:0.2333 337:0.2333 338:0.2333 339:0.2333 340:0.2333 341:0.2333 342:0.2333 343:0.2333 344:0.2833 345:0.2833 346:0.2833 347:0.3 348:0.2833 349:0.2833 350:0.3 351:0.2833 352:0.2833 353:0.2833 354:0.2833 355:0.2833 356:0.2833 357:0.45 358:0.5667 359:0.8 360:1
0.006257312053404475 1:1 2:1 3:1 4:0.7833 5:0.75 6:0.7333 7:0.55 8:0.4667 9:0.4167 10:0.3667 11:0.3333 12:0.3 13:0.2833 14:0.2667 15:0.2667 16:0.2667 17:0.2667 18:0.2667 19:0.2667 20:0.2667 21:0.2667 22:0.2667 23:0.2667 24:0.2667 25:0.2667 26:0.2667 27:0.2667 28:0.2667 29:0.2667 30:0.2667 31:0.2667 32:0.2667 33:0.2833 34:0.2833 35:0.2833 36:0.2833 37:0.2833 38:0.2833 39:0.2833 40:0.2833 41:0.2833 42:0.2833 43:0.2833 44:0.2833 45:0.2833 46:0.2833 47:0.2833 48:0.2833 49:0.2833 50:0.2833 51:0.2833 52:0.2833 53:0.2833 54:0.3 55:0.2833 56:0.3 57:0.3 58:0.2833 59:0.3 60:0.3 61:0.2833 62:0.3 63:0.3 64:0.3 65:0.3 66:0.3 67:0.3 68:0.3 69:0.3 70:0.3 71:0.3 72:0.3 73:0.3 74:0.3 75:0.3 76:0.3 77:0.3 78:0.5333 79:0.5333 80:0.5333 81:0.5333 82:0.5333 83:0.5333 84:0.7167 85:0.7333 86:0.7333 87:0.7333 88:0.75 89:0.75 90:0.75 91:0.8167 92:1 93:1 94:0.5667 95:0.5667 96:0.5667 97:0.5667 98:0.5667 99:0.5667 100:0.5667 101:0.5667 102:0.6167 103:0.45 104:0.45 105:0.45 106:0.45 107:0.45 108:0.45 109:0.45 110:0.2833 111:0.2833 112:0.25 113:0.25 114:0.2333 115:0.2167 116:0.2167 117:0.2167 118:0.2167 119:0.2333 120:0.2167 121:0.2167 122:0.2333 123:0.2333 124:0.2167 125:0.2167 126:0.2333 127:0.2333 128:0.2167 129:0.2167 130:0.2167 131:0.15 132:0.15 133:0.15 134:0.15 135:0.15 136:0.15 137:0.15 138:0.15 139:0.15 140:0.15 141:0.15 142:0.10526316 143:0.10526316 144:0.10526316 145:0.10526316 146:0.10526316 147:0.10526316 148:0.10526316 149:0.10526316 150:0.10526316 151:0.10526316 152:0.10526316 153:0.10526316 154:0.10526316 155:0.10526316 156:0.10526316 157:0.089282462 158:0.089282462 159:0.089282462 160:0.14285408 161:0.14285408 162:0.14285408 163:0.14285408 164:0.14285408 165:0.14285408 166:0.14285408 167:0.14285408 168:0.14285408 169:0.14285408 170:0.14285408 171:0.14285408 172:0.14285408 173:0.14285408 174:0.14285408 175:0.14285408 176:0.14285408 177:0.14285408 178:0.14285408 179:0.12496116 180:0.12496116 181:0.12496116 182:0.12496116 183:0.12496116 184:0.12496116 185:0.12496116 186:0.12496116 187:0.12496116 188:0.12496116 189:0.10717538 190:0.089282462 191:0.071389541 192:0.089282462 193:0.089282462 194:0.089282462 195:0.089282462 196:0.089282462 197:0.089282462 198:0.089282462 199:0.089282462 200:0.089282462 201:0.089282462 202:0.089282462 203:0.089282462 204:0.089282462 205:0.089282462 206:0.089282462 207:0.089282462 208:0.089282462 209:0.089282462 210:0.089282462 211:0.089282462 212:0.089282462 213:0.089282462 214:0.089282462 215:0.089282462 216:0.071389541 217:0.089282462 218:0.089282462 219:0.160747 220:0.160747 221:0.2167 222:0.2167 223:0.2167 224:0.2167 225:0.2167 226:0.2167 227:0.2167 228:0.2167 229:0.2167 230:0.2167 231:0.2167 232:0.2333 233:0.2333 234:0.2333 235:0.2667 236:0.3 237:0.4333 238:0.4333 239:0.4333 240:0.4333 241:0.4333 242:0.4333 243:0.4333 244:0.3833 245:0.3833 246:0.3833 247:0.3833 248:0.3833 249:0.3833 250:0.3833 251:0.3833 252:0.3833 253:0.3833 254:0.3833 255:0.3833 256:0.5167 257:0.5167 258:0.5167 259:0.5167 260:0.6833 261:0.6833 262:0.6833 263:0.8667 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:0.9167 277:0.7167 278:0.7333 279:0.55 280:0.55 281:0.55 282:0.3833 283:0.3667 284:0.3667 285:0.3667 286:0.3667 287:0.3667 288:0.3667 289:0.2333 290:0.2333 291:0.2167 292:0.2 293:0.2 294:0.2 295:0.2 296:0.2 297:0.2 298:0.2 299:0.2 300:0.2 301:0.2 302:0.2 303:0.2 304:0.2 305:0.2 306:0.2 307:0.2 308:0.2 309:0.2 310:0.2 311:0.2 312:0.2 313:0.2 314:0.2 315:0.2 316:0.2 317:0.2167 318:0.2167 319:0.2167 320:0.2167 321:0.2167 322:0.2333 323:0.2333 324:0.2333 325:0.2333 326:0.2333 327:0.2333 328:0.2333 329:0.2333 330:0.2333 331:0.2333 332:0.2333 333:0.2333 334:0.2333 335:0.2333 336:0.2333 337:0.2333 338:0.2333 339:0.3 340:0.2833 341:0.3333 342:0.3 343:0.3 344:0.3 345:0.3 346:0.3 347:0.3 348:0.3 349:0.3 350:0.3 351:0.3 352:0.3 353:0.3167 354:0.4333 355:0.4333 356:0.55 357:0.6667 358:0.7833 359:1 360:1
0.2401477987780673 1:0.1833 2:0.1833 3:0.1833 4:0.1833 5:0.1833 6:0.1833 7:0.1833 8:0.1833 9:1 10:1 11:1 12:1 13:1 14:1 15:1 16:1 17:1 18:1 19:1 20:1 21:1 22:1 23:1 24:1 25:1 26:1 27:1 28:0.6 29:0.6 30:0.6 31:0.6 32:0.6 33:0.6 34:0.6 35:0.6 36:0.4833 37:0.4667 38:0.4667 39:0.4667 40:0.4667 41:0.4667 42:0.4667 43:0.4667 44:0.4667 45:0.4667 46:0.4667 47:0.45 48:0.45 49:0.45 50:0.45 51:0.45 52:0.45 53:0.45 54:0.45 55:0.45 56:0.45 57:0.4167 58:0.35 59:0.35 60:0.35 61:0.35 62:0.35 63:0.35 64:0.35 65:0.35 66:0.35 67:0.35 68:0.35 69:0.35 70:0.35 71:0.35 72:0.35 73:0.35 74:0.3667 75:0.35 76:0.35 77:0.3667 78:0.3667 79:0.3667 80:0.3833 81:0.3833 82:0.3667 83:0.3667 84:0.3667 85:0.3667 86:0.3667 87:0.3667 88:0.3667 89:0.3667 90:0.3333 91:0.3333 92:0.3333 93:0.3333 94:0.3333 95:0.3333 96:0.3333 97:0.3333 98:0.3333 99:0.3333 100:0.3333 101:0.3333 102:0.3333 103:0.3333 104:0.3333 105:0.3333 106:0.3833 107:0.3833 108:0.3833 109:0.3833 110:0.3833 111:0.3833 112:0.3833 113:0.3833 114:0.3833 115:0.3833 116:0.3833 117:0.4 118:0.4167 119:0.4 120:0.4167 121:0.4167 122:0.4167 123:0.4167 124:0.4 125:0.4167 126:0.4 127:0.4167 128:0.4167 129:0.4167 130:0.45 131:0.45 132:0.45 133:0.45 134:0.45 135:0.45 136:0.4667 137:0.4667 138:0.4833 139:0.4833 140:0.5 141:0.5167 142:0.49126316 143:0.50873684 144:0.49126316 145:0.50873684 146:0.49126316 147:0.49126316 148:0.50873684 149:0.49126316 150:0.50873684 151:0.49126316 152:0.50873684 153:0.80705263 154:0.80705263 155:0.80705263 156:0.80705263 157:0.80360644 158:0.80360644 159:0.80360644 160:0.80360644 161:0.80360644 162:0.80360644 163:1 164:1 165:1 166:1 167:1 168:1 169:1 170:1 171:1 172:1 173:1 174:0.75003482 175:0.75003482 176:0.75003482 177:0.75003482 178:0.33924764 179:0.33924764 180:0.21431862 181:0.21431862 182:0.21431862 183:0.21431862 184:0.21431862 185:0.21431862 186:0.21431862 187:0.1964257 188:0.1964257 189:0.1964257 190:0.21431862 191:0.1964257 192:0.1964257 193:0.21431862 194:0.1964257 195:0.1964257 196:0.21431862 197:0.21431862 198:0.1964257 199:0.1964257 200:0.21431862 201:0.1964257 202:0.1964257 203:0.1964257 204:0.1964257 205:0.2321044 206:0.28567602 207:0.28567602 208:0.14285408 209:0.14285408 210:0.12496116 211:0.14285408 212:0.14285408 213:0.14285408 214:0.14285408 215:0.14285408 216:0.14285408 217:0.14285408 218:0.14285408 219:0.14285408 220:0.14285408 221:0.2 222:0.2 223:0.2 224:0.2 225:0.2 226:0.2 227:0.2 228:0.2 229:0.1833 230:0.2 231:0.2 232:0.2 233:0.2 234:0.2 235:0.2 236:0.2 237:0.2 238:0.2167 239:0.2 240:0.2 241:0.2 242:0.2167 243:0.2167 244:0.2 245:0.2 246:0.2167 247:0.2167 248:0.2 249:0.2 250:0.2 251:0.2 252:0.2 253:0.2 254:0.2 255:0.2 256:0.2167 257:0.2333 258:0.2333 259:0.2333 260:0.2333 261:0.2333 262:0.5333 263:0.55 264:0.5167 265:0.55 266:0.6333 267:0.6333 268:0.6333 269:0.6333 270:0.6333 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:0.8667 287:0.85 288:0.85 289:0.8333 290:0.8333 291:0.8333 292:0.8667 293:0.3833 294:0.4 295:0.3833 296:0.4 297:0.3833 298:0.4 299:0.4 300:0.4 301:0.4 302:0.3833 303:0.4 304:0.4 305:0.4 306:0.4333 307:0.4333 308:0.4333 309:0.4333 310:0.4333 311:0.4333 312:0.3167 313:0.2333 314:0.2333 315:0.3 316:0.3 317:0.25 318:0.25 319:0.2833 320:0.25 321:0.25 322:0.25 323:0.2667 324:0.25 325:0.2333 326:0.2667 327:0.2667 328:0.25 329:0.2333 330:0.15 331:0.15 332:0.15 333:0.15 334:0.15 335:0.15 336:0.1667 337:0.15 338:0.15 339:0.15 340:0.15 341:0.1667 342:0.1667 343:0.15 344:0.15 345:0.15 346:0.15 347:0.1667 348:0.15 349:0.15 350:0.15 351:0.15 352:0.15 353:0.15 354:0.15 355:0.15 356:0.15 357:0.15 358:0.15 359:0.1833 360:0.1833
0.3065862027933848 1:1 2:1 3:1 4:1 5:1 6:0.5333 7:0.5333 8:0.3667 9:0.3833 10:0.3667 11:0.3833 12:0.3833 13:0.3833 14:0.3833 15:0.3667 16:0.3833 17:0.3833 18:0.3167 19:0.1833 20:0.1833 21:0.1667 22:0.1667 23:0.1833 24:0.1833 25:0.1833 26:0.1667 27:0.1667 28:0.1667 29:0.1667 30:0.1667 31:0.1667 32:0.1667 33:0.1667 34:0.1667 35:0.1667 36:0.1667 37:0.1667 38:0.1667 39:0.1667 40:0.1667 41:0.1667 42:0.1667 43:0.1667 44:0.1667 45:0.1667 46:0.1667 47:0.15 48:0.1667 49:0.1667 50:0.1667 51:0.1667 52:0.1667 53:0.1667 54:0.1667 55:0.1667 56:0.1667 57:0.1667 58:0.1667 59:0.1667 60:0.1667 61:0.1667 62:0.1667 63:0.1333 64:0.1333 65:0.1333 66:0.1333 67:0.1333 68:0.1333 69:0.1333 70:0.1333 71:0.1333 72:0.1333 73:0.1333 74:0.1333 75:0.1333 76:0.1333 77:0.1333 78:0.1333 79:0.1 80:0.1 81:0.1 82:0.1 83:0.1 84:0.1 85:0.1 86:0.1 87:0.1 88:0.1 89:0.1 90:0.1 91:0.1 92:0.1 93:0.1 94:0.1 95:0.1 96:0.1 97:0.1 98:0.1 99:0.1 100:0.1 101:0.1 102:0.1 103:0.1 104:0.1 105:0.1 106:0.1 107:0.1 108:0.1 109:0.1 110:0.1 111:0.1 112:0.1 113:0.1 114:0.1 115:0.1 116:0.1 117:0.1 118:0.1 119:0.1 120:0.1 121:0.1 122:0.1 123:0.1 124:0.1 125:0.1 126:0.1 127:0.1 128:0.1667 129:0.1667 130:0.1667 131:0.1667 132:0.1667 133:0.1667 134:0.1667 135:0.15 136:0.1667 137:0.1667 138:0.1667 139:0.1667 140:0.1667 141:0.1667 142:0.17547368 143:0.17547368 144:0.17547368 145:0.19294737 146:0.19294737 147:0.17547368 148:0.17547368 149:0.19294737 150:0.19294737 151:0.17547368 152:0.17547368 153:0.19294737 154:0.17547368 155:0.17547368 156:0.17547368 157:0.160747 158:0.17853278 159:0.2321044 160:0.2321044 161:0.2321044 162:0.2321044 163:0.24999732 164:0.26789024 165:0.28567602 166:0.30356894 167:0.32146186 168:0.35714056 169:0.37503348 170:0.37503348 171:0.37503348 172:0.37503348 173:0.37503348 174:0.37503348 175:0.37503348 176:0.37503348 177:0.37503348 178:0.7321419 179:0.7321419 180:0.9643213 181:1 182:1 183:1 184:1 185:1 186:1 187:1 188:1 189:1 190:1 191:0.75003482 192:0.75003482 193:0.75003482 194:0.75003482 195:0.75003482 196:0.75003482 197:0.7678206 198:0.9643213 199:0.87496384 200:0.7678206 201:0.80360644 202:0.78571352 203:0.7678206 204:0.7678206 205:0.7678206 206:0.80360644 207:0.80360644 208:1 209:1 210:0.39281926 211:0.83928514 212:0.39281926 213:0.80360644 214:0.39281926 215:0.78571352 216:0.39281926 217:0.78571352 218:0.39281926 219:0.32146186 220:0.32146186 221:0.35 222:0.3667 223:0.3667 224:0.3667 225:0.3667 226:0.35 227:0.3667 228:0.3667 229:0.3667 230:0.3667 231:0.35 232:0.3667 233:0.3667 234:0.3667 235:0.3833 236:0.3667 237:0.3667 238:0.4833 239:0.4833 240:0.4333 241:0.3833 242:0.3833 243:0.3833 244:0.3833 245:0.3833 246:0.3833 247:0.3833 248:0.3833 249:0.3833 250:0.3833 251:0.3833 252:0.3833 253:0.3833 254:0.3833 255:0.3833 256:0.4167 257:0.4333 258:0.4167 259:0.4333 260:0.4167 261:0.4167 262:0.4167 263:0.4167 264:0.4167 265:0.4167 266:0.45 267:0.45 268:0.4667 269:0.8667 270:0.8667 271:0.8667 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:0.6167 287:0.6167 288:0.6167 289:0.6167 290:0.6167 291:0.6167 292:0.6167 293:0.6167 294:0.6167 295:0.4333 296:0.4333 297:0.3167 298:0.3167 299:0.3167 300:0.3167 301:0.3167 302:0.3167 303:0.3167 304:0.3167 305:0.3167 306:0.3167 307:0.3167 308:0.3167 309:0.3167 310:0.3167 311:0.3167 312:0.3167 313:0.3167 314:0.3167 315:0.3167 316:0.3167 317:0.3167 318:0.3167 319:0.3167 320:0.3167 321:0.4167 322:0.4167 323:0.4167 324:0.4333 325:0.4333 326:0.4333 327:0.4333 328:0.5 329:0.5 330:0.5 331:0.5 332:0.5 333:0.5167 334:0.5 335:0.5167 336:0.8667 337:0.8667 338:0.85 339:0.85 340:0.85 341:0.85 342:0.85 343:0.85 344:0.85 345:0.9833 346:0.9833 347:1 348:1 349:1 350:1 351:1 352:1 353:1 354:1 355:1 356:1 357:1 358:1 359:1 360:1
0.06055250298999164 1:1 2:1 3:1 4:1 5:1 6:1 7:1 8:0.7 9:0.7 10:0.7 11:0.7 12:0.7 13:0.7 14:0.7 15:0.7 16:1 17:0.9667 18:0.9667 19:0.8 20:0.7833 21:0.8 22:0.8 23:0.7833 24:0.7833 25:0.7833 26:1 27:1 28:1 29:1 30:0.4333 31:0.45 32:0.4333 33:0.45 34:0.4333 35:0.45 36:0.4333 37:0.45 38:0.4333 39:0.4333 40:0.45 41:0.3 42:0.3 43:0.3 44:0.3 45:0.3 46:0.3 47:0.3 48:0.3 49:0.3 50:0.3 51:0.3 52:0.3 53:0.3 54:0.3 55:0.3 56:0.3 57:0.3 58:0.3 59:0.3 60:0.3 61:0.5333 62:0.5333 63:0.5333 64:0.5333 65:0.5333 66:0.5333 67:0.5333 68:0.5333 69:0.5333 70:0.5333 71:0.5333 72:0.5333 73:0.4833 74:0.4833 75:0.4833 76:0.4667 77:0.4833 78:0.4833 79:0.4833 80:0.4833 81:0.4833 82:0.4833 83:0.4833 84:0.4667 85:0.5667 86:0.5667 87:0.5667 88:0.5667 89:0.5667 90:0.5667 91:0.5667 92:0.4833 93:0.4833 94:0.4833 95:0.4833 96:0.4833 97:0.4833 98:0.4833 99:0.4833 100:0.4833 101:0.4833 102:0.4833 103:0.4833 104:0.5 105:0.5 106:0.5 107:0.5 108:0.5 109:0.5 110:0.5 111:0.5 112:0.5 113:0.5 114:0.3167 115:0.3333 116:0.3333 117:0.3167 118:0.3333 119:0.3333 120:0.3333 121:0.3333 122:0.3333 123:0.3333 124:0.3333 125:0.3167 126:0.3167 127:0.3333 128:0.3333 129:0.3333 130:0.3333 131:0.35 132:0.35 133:0.35 134:0.3667 135:0.3667 136:0.3667 137:0.3833 138:0.3833 139:0.3833 140:0.6833 141:0.75 142:0.36842105 143:0.36842105 144:0.36842105 145:0.36842105 146:0.36842105 147:0.36842105 148:0.36842105 149:0.36842105 150:0.36842105 151:0.36842105 152:0.35084211 153:0.36842105 154:0.36842105 155:0.36842105 156:0.42105263 157:0.41071218 158:0.41071218 159:0.41071218 160:0.41071218 161:0.41071218 162:0.41071218 163:0.41071218 164:0.57142704 165:0.57142704 166:0.57142704 167:0.64289158 168:0.60710574 169:0.67857028 170:0.67857028 171:0.67857028 172:0.67857028 173:0.67857028 174:0.6964632 175:0.71424898 176:0.71424898 177:0.71424898 178:0.80360644 179:0.80360644 180:0.80360644 181:1 182:1 183:1 184:1 185:1 186:1 187:1 188:1 189:1 190:1 191:1 192:1 193:1 194:0.28567602 195:0.28567602 196:0.28567602 197:0.28567602 198:0.26789024 199:0.28567602 200:0.28567602 201:0.28567602 202:0.28567602 203:0.28567602 204:0.28567602 205:0.28567602 206:0.26789024 207:0.28567602 208:0.28567602 209:0.26789024 210:0.28567602 211:0.28567602 212:0.28567602 213:0.28567602 214:0.28567602 215:0.28567602 216:0.28567602 217:0.28567602 218:0.12496116 219:0.12496116 220:0.12496116 221:0.1667 222:0.1667 223:0.1667 224:0.1667 225:0.1667 226:0.1667 227:0.15 228:0.1667 229:0.1667 230:0.1667 231:0.1667 232:0.1667 233:0.1667 234:0.1667 235:0.1667 236:0.1667 237:0.1667 238:0.1667 239:0.1667 240:0.1667 241:0.1667 242:0.1667 243:0.1667 244:0.1667 245:0.1667 246:0.1667 247:0.1667 248:0.1667 249:0.15 250:0.1667 251:0.1667 252:0.5833 253:0.5167 254:0.5 255:0.5 256:0.3833 257:0.3833 258:0.3833 259:0.3833 260:0.3833 261:0.3833 262:0.3833 263:0.3833 264:0.3833 265:0.3833 266:0.3833 267:0.3833 268:0.3833 269:0.3833 270:0.3833 271:0.3833 272:0.3833 273:0.3833 274:0.3833 275:1 276:1 277:1 278:1 279:1 280:1 281:0.8167 282:0.7333 283:0.7333 284:0.7333 285:0.7333 286:0.7333 287:0.7333 288:0.7333 289:0.75 290:0.75 291:0.75 292:0.75 293:0.7667 294:0.7667 295:0.7667 296:0.7667 297:0.5833 298:0.2333 299:0.2333 300:0.2167 301:0.2167 302:0.2167 303:0.2 304:0.2 305:0.2 306:0.1833 307:0.1833 308:0.1833 309:0.1833 310:0.1833 311:0.1667 312:0.1667 313:0.1667 314:0.1667 315:0.1667 316:0.1833 317:0.1667 318:0.1667 319:0.1667 320:0.1833 321:0.1833 322:0.1667 323:0.1667 324:0.1667 325:0.1833 326:0.1833 327:0.1667 328:0.1667 329:0.1667 330:0.1667 331:0.1667 332:0.1667 333:0.1667 334:0.1667 335:0.1667 336:1 337:1 338:1 339:1 340:1 341:1 342:1 343:1 344:1 345:1 346:1 347:1 348:1 349:1 350:1 351:1 352:1 353:1 354:1 355:1 356:1 357:1 358:1 359:1 360:1
0.5344429839729679 1:0.45 2:0.45 3:0.45 4:0.45 5:0.45 6:0.45 7:0.45 8:0.45 9:0.45 10:0.45 11:0.45 12:0.45 13:0.45 14:0.45 15:0.45 16:0.45 17:0.4667 18:0.4667 19:0.4667 20:0.4667 21:0.4667 22:0.4667 23:0.4667 24:0.4833 25:0.4833 26:0.4833 27:0.4833 28:0.5 29:0.5 30:0.5 31:0.5 32:0.5 33:0.5 34:0.5 35:0.5 36:0.5 37:0.5167 38:0.5167 39:0.5333 40:0.5333 41:0.5333 42:0.55 43:0.55 44:0.5667 45:1 46:1 47:1 48:1 49:1 50:1 51:1 52:1 53:1 54:1 55:1 56:1 57:1 58:1 59:1 60:1 61:1 62:1 63:1 64:1 65:1 66:1 67:1 68:1 69:1 70:1 71:1 72:1 73:1 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:0.95 110:0.95 111:0.95 112:0.95 113:0.8667 114:0.8333 115:0.7167 116:0.6833 117:0.6667 118:0.65 119:0.6167 120:0.6167 121:0.6167 122:0.6167 123:0.55 124:0.5333 125:0.55 126:0.4833 127:0.4667 128:0.4667 129:0.4667 130:0.4667 131:0.4333 132:0.4333 133:0.4333 134:0.4333 135:0.4333 136:0.4333 137:0.4333 138:0.4333 139:0.4333 140:0.3667 141:0.3667 142:0.33336842 143:0.33336842 144:0.33336842 145:0.33336842 146:0.33336842 147:0.33336842 148:0.33336842 149:0.33336842 150:0.33336842 151:0.33336842 152:0.33336842 153:0.33336842 154:0.43863158 155:0.43863158 156:0.43863158 157:0.4286051 158:0.4286051 159:0.4286051 160:1 161:1 162:1 163:1 164:1 165:1 166:1 167:1 168:1 169:1 170:1 171:1 172:1 173:0.9643213 174:0.94642838 175:0.91074968 176:0.87496384 177:0.83928514 178:0.82139222 179:0.78571352 180:0.7678206 181:0.7678206 182:0.7321419 183:0.7321419 184:0.7321419 185:0.7321419 186:0.7321419 187:0.6964632 188:0.71424898 189:0.71424898 190:0.71424898 191:0.6964632 192:0.75003482 193:0.71424898 194:0.7678206 195:0.71424898 196:0.71424898 197:0.71424898 198:0.71424898 199:0.41071218 200:0.41071218 201:0.37503348 202:0.37503348 203:0.37503348 204:0.37503348 205:0.33924764 206:0.33924764 207:0.33924764 208:0.33924764 209:0.33924764 210:0.33924764 211:0.33924764 212:0.33924764 213:0.33924764 214:0.33924764 215:0.33924764 216:0.33924764 217:0.33924764 218:0.33924764 219:0.33924764 220:0.37503348 221:0.4167 222:0.4167 223:0.4167 224:0.4 225:0.4 226:0.4167 227:0.4 228:0.4167 229:0.4 230:0.4167 231:0.4 232:0.4 233:0.4167 234:0.4 235:0.4167 236:0.4167 237:0.4333 238:0.45 239:0.45 240:0.4667 241:0.4833 242:0.5 243:0.5167 244:0.5333 245:0.55 246:0.5667 247:0.6 248:0.6167 249:0.65 250:0.6667 251:0.7167 252:0.75 253:0.7833 254:0.85 255:0.8667 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:1 296:1 297:1 298:1 299:1 300:1 301:1 302:0.8667 303:0.8333 304:0.8167 305:0.8 306:0.8 307:0.8 308:0.8 309:0.8 310:0.7833 311:0.9167 312:0.9 313:0.9 314:0.9 315:0.9167 316:1 317:0.6 318:0.6 319:0.6 320:0.6 321:0.5833 322:0.5833 323:0.6 324:0.5833 325:0.5833 326:0.5667 327:0.5167 328:0.5167 329:0.5167 330:0.5 331:0.5 332:0.5 333:0.5 334:0.5 335:0.5 336:0.5 337:0.5 338:0.5 339:0.5 340:0.5 341:0.4667 342:0.4667 343:0.4667 344:0.4667 345:0.4667 346:0.45 347:0.45 348:0.45 349:0.45 350:0.45 351:0.45 352:0.45 353:0.45 354:0.45 355:0.45 356:0.45 357:0.45 358:0.45 359:0.45 360:0.45
1.465408862755756 1:0.3667 2:0.3667 3:0.3667 4:0.3667 5:0.3667 6:0.3667 7:0.3667 8:0.3667 9:0.3667 10:0.3667 11:0.3667 12:0.3667 13:0.3667 14:0.3667 15:0.3667 16:0.3667 17:0.3667 18:0.3667 19:0.3833 20:0.3833 21:0.3833 22:0.3833 23:0.3833 24:0.3833 25:0.3833 26:0.3833 27:0.3833 28:0.4 29:0.4 30:0.4 31:0.4 32:0.3833 33:0.4 34:0.4 35:0.4 36:0.4 37:0.4167 38:0.4167 39:0.4167 40:0.4333 41:0.4333 42:0.4333 43:0.45 44:0.45 45:0.45 46:0.4667 47:0.4667 48:0.4667 49:0.4833 50:0.4667 51:0.5667 52:0.5667 53:0.55 54:0.5833 55:0.5833 56:0.6 57:1 58:1 59:1 60:1 61:1 62:1 63:1 64:1 65:1 66:1 67:1 68:1 69:1 70:1 71:1 72:1 73:1 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:0.8333 91:0.8333 92:0.8333 93:0.8333 94:0.8333 95:0.8333 96:0.8333 97:0.8333 98:0.8333 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:1 118:1 119:1 120:0.9 121:0.9 122:0.7667 123:0.7333 124:0.7333 125:0.7333 126:0.7333 127:0.6667 128:0.65 129:0.6333 130:0.6333 131:0.6167 132:0.6167 133:0.5667 134:0.5667 135:0.6 136:0.5167 137:0.5 138:0.5 139:0.4833 140:0.4833 141:0.4667 142:0.43863158 143:0.43863158 144:0.43863158 145:0.43863158 146:0.43863158 147:0.43863158 148:0.43863158 149:0.43863158 150:0.43863158 151:0.43863158 152:0.43863158 153:0.50873684 154:0.52631579 155:0.52631579 156:0.52631579 157:0.51785542 158:0.4999625 159:0.51785542 160:0.94642838 161:1 162:1 163:1 164:1 165:1 166:1 167:1 168:1 169:1 170:1 171:1 172:1 173:1 174:1 175:1 176:1 177:0.94642838 178:0.85717806 179:0.85717806 180:0.80360644 181:0.80360644 182:0.80360644 183:0.80360644 184:0.80360644 185:0.80360644 186:0.83928514 187:0.80360644 188:0.80360644 189:0.80360644 190:0.80360644 191:0.80360644 192:0.87496384 193:0.78571352 194:0.53574834 195:0.55353412 196:0.53574834 197:0.53574834 198:0.55353412 199:0.53574834 200:0.39281926 201:0.39281926 202:0.39281926 203:0.39281926 204:0.39281926 205:0.39281926 206:0.37503348 207:0.39281926 208:0.37503348 209:0.37503348 210:0.37503348 211:0.37503348 212:0.37503348 213:0.37503348 214:0.37503348 215:0.37503348 216:0.37503348 217:0.37503348 218:0.37503348 219:0.37503348 220:0.39281926 221:0.4333 222:0.4333 223:0.45 224:0.5167 225:0.5333 226:0.5167 227:0.5333 228:0.5167 229:0.5333 230:0.5167 231:0.5333 232:0.55 233:0.55 234:0.5833 235:0.5833 236:0.5667 237:0.5833 238:0.6667 239:0.6667 240:0.6667 241:0.6667 242:0.6667 243:0.6833 244:0.6833 245:0.7167 246:0.7333 247:0.7667 248:0.7833 249:0.8167 250:0.85 251:0.9 252:0.95 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:0.8833 294:0.8833 295:0.8833 296:0.8833 297:0.85 298:0.8333 299:0.8167 300:0.8167 301:0.75 302:0.7333 303:0.7333 304:0.7333 305:0.75 306:0.7 307:0.6167 308:0.6 309:0.6 310:0.6 311:0.6 312:0.6 313:0.6 314:0.6 315:0.5167 316:0.5167 317:0.5 318:0.5 319:0.4833 320:0.4833 321:0.4667 322:0.4667 323:0.4667 324:0.45 325:0.45 326:0.45 327:0.4333 328:0.4333 329:0.4333 330:0.4333 331:0.4167 332:0.4167 333:0.4167 334:0.4167 335:0.4167 336:0.4 337:0.4 338:0.4 339:0.4 340:0.4 341:0.4 342:0.4 343:0.4 344:0.3833 345:0.3667 346:0.3667 347:0.3667 348:0.3667 349:0.3667 350:0.3667 351:0.3667 352:0.3667 353:0.3667 354:0.3667 355:0.3667 356:0.3667 357:0.3667 358:0.3667 359:0.3667 360:0.3667
0.1148003145982911 1:0.3 2:0.3 3:0.3 4:0.3 5:0.3 6:0.3 7:0.3 8:0.3 9:0.3 10:0.3 11:0.3 12:0.3 13:0.3 14:0.3 15:0.3 16:0.3 17:0.3 18:0.3 19:0.3 20:0.3 21:0.3 22:0.3167 23:0.3167 24:0.3167 25:0.3167 26:0.3167 27:0.3167 28:0.3167 29:0.3167 30:0.3333 31:0.3333 32:0.3333 33:0.3333 34:0.3333 35:0.3333 36:0.35 37:0.35 38:0.35 39:0.35 40:0.3667 41:0.3833 42:0.3667 43:0.3833 44:0.3833 45:0.3833 46:0.4 47:0.4333 48:0.4333 49:0.4333 50:0.4333 51:0.4333 52:0.4333 53:0.5 54:0.5 55:0.5 56:0.9 57:0.7 58:0.7 59:0.7 60:0.7 61:0.7 62:0.7 63:0.7 64:0.7167 65:0.7 66:0.7833 67:0.7833 68:0.7833 69:0.7833 70:0.8167 71:0.8667 72:1 73:1 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:0.85 85:0.8333 86:0.6333 87:0.6333 88:0.6333 89:0.6333 90:0.6333 91:0.6333 92:0.6333 93:0.6333 94:0.6333 95:1 96:1 97:0.8667 98:0.8833 99:0.7667 100:0.7667 101:0.75 102:0.75 103:0.7167 104:0.7167 105:0.7167 106:0.6667 107:0.6667 108:0.65 109:0.6667 110:0.6667 111:0.65 112:0.6667 113:0.6667 114:0.65 115:0.6667 116:0.5 117:0.4833 118:0.4833 119:0.4833 120:0.4833 121:0.4833 122:0.4833 123:0.4833 124:0.4833 125:0.4833 126:0.4833 127:0.6833 128:0.6833 129:0.6667 130:0.6833 131:0.7 132:0.7 133:0.5833 134:0.5833 135:0.5833 136:0.5833 137:0.5833 138:0.5833 139:0.5833 140:0.5833 141:0.5833 142:0.56136842 143:0.56136842 144:0.57894737 145:0.57894737 146:0.57894737 147:0.59652632 148:0.614 149:0.63157895 150:0.64915789 151:0.73684211 152:0.73684211 153:0.75442105 154:0.77189474 155:0.77189474 156:0.87715789 157:0.87496384 158:0.89285676 159:0.91074968 160:0.94642838 161:1 162:1 163:1 164:1 165:1 166:1 167:1 168:1 169:1 170:1 171:1 172:1 173:1 174:1 175:1 176:1 177:1 178:1 179:1 180:1 181:1 182:1 183:1 184:0.82139222 185:0.82139222 186:0.82139222 187:0.82139222 188:0.7678206 189:0.62499866 190:0.57142704 191:0.48217672 192:0.44639088 193:0.39281926 194:0.39281926 195:0.39281926 196:0.39281926 197:0.39281926 198:0.39281926 199:0.39281926 200:0.39281926 201:0.39281926 202:0.39281926 203:0.39281926 204:0.39281926 205:0.78571352 206:0.78571352 207:0.26789024 208:0.26789024 209:0.24999732 210:0.24999732 211:0.26789024 212:0.24999732 213:0.24999732 214:0.26789024 215:0.24999732 216:0.24999732 217:0.26789024 218:0.24999732 219:0.24999732 220:0.26789024 221:0.3 222:0.3 223:0.4667 224:0.4333 225:0.4333 226:0.4333 227:0.4333 228:0.4333 229:0.4333 230:0.4333 231:0.4333 232:0.4333 233:0.4333 234:0.4333 235:0.4667 236:0.4667 237:0.4667 238:0.4667 239:0.45 240:0.4667 241:0.4833 242:0.4667 243:0.4833 244:0.4667 245:0.4833 246:0.4667 247:0.4667 248:0.4667 249:0.5167 250:0.4667 251:0.5167 252:0.5167 253:0.5167 254:0.5333 255:0.5667 256:0.5667 257:0.6333 258:0.6333 259:0.6333 260:0.7333 261:0.7667 262:0.4167 263:0.4167 264:0.4167 265:0.4167 266:0.4167 267:0.4167 268:0.4167 269:0.4167 270:0.4167 271:0.4167 272:0.4167 273:0.6 274:0.6333 275:0.6333 276:0.6333 277:0.65 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:0.9333 287:0.8667 288:0.8167 289:0.6667 290:0.6333 291:0.6333 292:0.6333 293:0.6333 294:0.6333 295:0.6333 296:0.6167 297:0.6167 298:0.6 299:0.6167 300:0.6167 301:0.55 302:0.55 303:0.55 304:0.55 305:0.55 306:0.55 307:0.55 308:0.55 309:0.55 310:0.55 311:0.7167 312:0.7 313:0.6833 314:0.7 315:0.6833 316:0.3667 317:0.3667 318:0.3667 319:0.3667 320:0.3667 321:0.3667 322:0.3667 323:0.35 324:0.35 325:0.35 326:0.35 327:0.3333 328:0.3333 329:0.3333 330:0.3333 331:0.3333 332:0.3333 333:0.3167 334:0.3167 335:0.3167 336:0.3167 337:0.3167 338:0.3167 339:0.3167 340:0.3167 341:0.3 342:0.3 343:0.3 344:0.3 345:0.3 346:0.3 347:0.3 348:0.3 349:0.3 350:0.3 351:0.3 352:0.3 353:0.3 354:0.3 355:0.3 356:0.3 357:0.3 358:0.3 359:0.3 360:0.3
0.02954651890168256 1:0.3 2:0.3 3:0.3 4:0.3 5:0.3 6:0.3 7:0.3 8:0.3 9:0.3 10:0.3 11:0.3 12:0.3 13:0.3 14:0.3 15:0.3 16:0.3 17:0.3 18:0.3 19:0.3 20:0.3 21:0.3333 22:0.3333 23:0.3333 24:0.3333 25:0.3333 26:0.3333 27:0.3333 28:0.3333 29:0.35 30:0.35 31:0.35 32:0.3667 33:0.3667 34:0.3667 35:0.3667 36:0.3833 37:0.3833 38:0.3833 39:0.3833 40:0.3833 41:0.3833 42:0.4333 43:0.4333 44:0.4333 45:0.4333 46:0.4333 47:0.4667 48:0.4667 49:0.4667 50:0.85 51:0.85 52:0.8667 53:0.6667 54:0.6667 55:0.6667 56:0.6667 57:0.6667 58:0.6667 59:0.6667 60:0.6667 61:0.6833 62:0.75 63:0.75 64:0.75 65:0.7333 66:0.8833 67:0.8833 68:0.8833 69:1 70:1 71:1 72:1 73:1 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:0.8667 82:0.8667 83:0.6 84:0.6 85:0.6 86:0.6 87:0.6 88:0.6 89:0.6 90:0.6 91:0.6 92:1 93:0.85 94:0.8333 95:0.8333 96:0.8333 97:0.7167 98:0.7333 99:0.7167 100:0.7167 101:0.7167 102:0.65 103:0.65 104:0.65 105:0.65 106:0.6333 107:0.6333 108:0.6333 109:0.6333 110:0.6333 111:0.6333 112:0.6333 113:0.6333 114:0.45 115:0.45 116:0.45 117:0.45 118:0.45 119:0.45 120:0.45 121:0.45 122:0.45 123:0.45 124:0.45 125:0.45 126:0.45 127:0.6333 128:0.65 129:0.65 130:0.6667 131:0.6667 132:0.65 133:0.6667 134:0.55 135:0.55 136:0.55 137:0.55 138:0.55 139:0.55 140:0.55 141:0.55 142:0.52631579 143:0.52631579 144:0.54389474 145:0.54389474 146:0.57894737 147:0.57894737 148:0.57894737 149:0.59652632 150:0.614 151:0.66663158 152:0.68421053 153:0.71926316 154:0.73684211 155:0.75442105 156:0.78947368 157:0.85717806 158:0.85717806 159:0.87496384 160:0.89285676 161:1 162:1 163:1 164:1 165:1 166:1 167:1 168:1 169:1 170:1 171:1 172:1 173:1 174:1 175:1 176:1 177:1 178:1 179:1 180:1 181:1 182:1 183:1 184:0.82139222 185:0.82139222 186:0.82139222 187:0.82139222 188:0.58931996 189:0.58931996 190:0.58931996 191:0.58931996 192:0.57142704 193:0.48217672 194:0.4642838 195:0.41071218 196:0.39281926 197:0.41071218 198:0.39281926 199:0.41071218 200:0.39281926 201:0.41071218 202:0.39281926 203:0.41071218 204:0.39281926 205:0.41071218 206:0.41071218 207:0.41071218 208:0.57142704 209:0.57142704 210:0.57142704 211:0.26789024 212:0.26789024 213:0.26789024 214:0.26789024 215:0.26789024 216:0.26789024 217:0.26789024 218:0.26789024 219:0.26789024 220:0.26789024 221:0.3167 222:0.3167 223:0.3167 224:0.3167 225:0.3167 226:0.45 227:0.4833 228:0.45 229:0.4833 230:0.45 231:0.45 232:0.4833 233:0.4667 234:0.4667 235:0.4667 236:0.4667 237:0.4667 238:0.4667 239:0.4667 240:0.4667 241:0.4667 242:0.4667 243:0.5 244:0.4833 245:0.4833 246:0.4833 247:0.4833 248:0.4833 249:0.5 250:0.5 251:0.55 252:0.5667 253:0.5667 254:0.6 255:0.6 256:0.6 257:0.7167 258:0.7667 259:0.7833 260:1 261:0.4667 262:0.4667 263:0.4667 264:0.4667 265:0.4667 266:0.4667 267:0.4667 268:0.4667 269:0.4667 270:0.4667 271:0.6333 272:0.6333 273:0.6333 274:0.6333 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:0.9167 285:0.85 286:0.8167 287:0.8167 288:0.65 289:0.65 290:0.6333 291:0.65 292:0.6333 293:0.6333 294:0.6333 295:0.6333 296:0.6333 297:0.5833 298:0.5833 299:0.5833 300:0.5833 301:0.5833 302:0.5833 303:0.5833 304:0.5833 305:0.5833 306:0.5833 307:0.75 308:0.7333 309:0.7167 310:0.7167 311:0.4 312:0.4 313:0.3833 314:0.3833 315:0.3833 316:0.3667 317:0.3667 318:0.3667 319:0.3667 320:0.3667 321:0.3667 322:0.3667 323:0.35 324:0.35 325:0.35 326:0.35 327:0.3333 328:0.3333 329:0.3333 330:0.3333 331:0.3333 332:0.3333 333:0.3167 334:0.3167 335:0.3167 336:0.3167 337:0.3167 338:0.3167 339:0.3167 340:0.3167 341:0.3 342:0.3 343:0.3 344:0.3 345:0.3 346:0.3 347:0.3 348:0.3 349:0.3 350:0.3 351:0.3 352:0.3 353:0.3 354:0.3 355:0.3 356:0.3 357:0.3 358:0.3 359:0.3 360:0.3
0.1695290082314663 1:0.3333 2:0.3333 3:0.3333 4:0.3333 5:0.3333 6:0.3333 7:0.3333 8:0.3333 9:0.3333 10:0.3333 11:0.35 12:0.35 13:0.35 14:0.35 15:0.35 16:0.35 17:0.35 18:0.35 19:0.35 20:0.3667 21:0.3667 22:0.3667 23:0.3667 24:0.3667 25:0.3667 26:0.3667 27:0.3667 28:0.3833 29:0.4 30:0.4 31:0.4 32:0.4167 33:0.4167 34:0.4167 35:0.4167 36:0.4333 37:0.4333 38:0.4333 39:0.4333 40:0.7833 41:0.7833 42:0.8333 43:0.8333 44:0.65 45:0.6333 46:0.65 47:0.65 48:0.6333 49:0.65 50:0.65 51:0.6333 52:0.65 53:0.7167 54:0.7167 55:0.7167 56:0.7167 57:0.7333 58:0.7167 59:0.7333 60:0.8167 61:0.8167 62:0.8833 63:0.9 64:1 65:1 66:1 67:1 68:1 69:1 70:1 71:1 72:1 73:1 74:1 75:1 76:1 77:0.5333 78:0.5333 79:0.5333 80:0.5333 81:0.5333 82:0.5333 83:0.5333 84:0.5333 85:0.5333 86:0.5333 87:1 88:1 89:1 90:1 91:1 92:1 93:0.8667 94:0.65 95:0.65 96:0.65 97:0.65 98:0.65 99:0.65 100:0.5833 101:0.5833 102:0.5833 103:0.5833 104:0.5833 105:0.5833 106:0.5833 107:0.5667 108:0.55 109:0.55 110:0.3833 111:0.3833 112:0.3833 113:0.3833 114:0.3833 115:0.3833 116:0.3833 117:0.3833 118:0.3833 119:0.3833 120:0.3833 121:0.3833 122:0.3833 123:0.3833 124:0.3833 125:0.5833 126:0.5833 127:0.6 128:0.6 129:0.5 130:0.5 131:0.5 132:0.5 133:0.5 134:0.5 135:0.5 136:0.5 137:0.5 138:0.5 139:0.5 140:0.5 141:0.5167 142:0.49126316 143:0.49126316 144:0.49126316 145:0.50873684 146:0.50873684 147:0.52631579 148:0.54389474 149:0.59652632 150:0.614 151:0.63157895 152:0.64915789 153:0.68421053 154:0.70178947 155:0.82452632 156:0.84210526 157:0.82139222 158:0.85717806 159:1 160:1 161:1 162:1 163:1 164:1 165:1 166:1 167:1 168:1 169:1 170:1 171:1 172:1 173:1 174:1 175:1 176:1 177:1 178:1 179:1 180:1 181:1 182:1 183:1 184:0.9643213 185:0.83928514 186:0.83928514 187:0.82139222 188:0.82139222 189:0.78571352 190:0.55353412 191:0.55353412 192:0.55353412 193:0.55353412 194:0.55353412 195:0.48217672 196:0.4999625 197:0.4999625 198:0.4999625 199:0.41071218 200:0.41071218 201:0.41071218 202:0.41071218 203:0.41071218 204:0.41071218 205:0.41071218 206:0.41071218 207:0.41071218 208:0.41071218 209:0.41071218 210:0.80360644 211:0.51785542 212:0.51785542 213:0.51785542 214:0.30356894 215:0.30356894 216:0.30356894 217:0.30356894 218:0.30356894 219:0.30356894 220:0.30356894 221:0.35 222:0.35 223:0.35 224:0.35 225:0.35 226:0.35 227:0.35 228:0.35 229:0.35 230:0.35 231:0.5167 232:0.5167 233:0.5 234:0.5 235:0.5 236:0.5 237:0.5 238:0.5 239:0.5 240:0.5 241:0.5 242:0.5 243:0.5333 244:0.5167 245:0.5333 246:0.5333 247:0.5333 248:0.5333 249:0.5333 250:0.5333 251:0.6 252:0.6 253:0.6167 254:0.65 255:0.75 256:0.8 257:0.8333 258:0.85 259:0.5 260:0.5 261:0.5 262:0.5 263:0.5 264:0.5 265:0.5 266:0.5 267:0.5 268:0.5 269:0.5 270:0.5 271:0.6833 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:0.9333 282:0.9167 283:0.8667 284:0.85 285:0.8 286:0.6667 287:0.6667 288:0.6667 289:0.6667 290:0.6667 291:0.6667 292:0.6667 293:0.65 294:0.65 295:0.65 296:0.65 297:0.65 298:0.65 299:0.65 300:0.65 301:0.65 302:0.8333 303:0.8 304:0.7833 305:0.7667 306:0.45 307:0.45 308:0.4333 309:0.4167 310:0.4167 311:0.4 312:0.4 313:0.4167 314:0.4 315:0.4 316:0.4 317:0.3833 318:0.3833 319:0.3833 320:0.3667 321:0.3833 322:0.3667 323:0.3833 324:0.3667 325:0.3667 326:0.3667 327:0.3667 328:0.35 329:0.35 330:0.35 331:0.35 332:0.35 333:0.35 334:0.3333 335:0.3333 336:0.3333 337:0.3333 338:0.3333 339:0.3333 340:0.3333 341:0.3333 342:0.3167 343:0.3333 344:0.3333 345:0.3167 346:0.3333 347:0.3333 348:0.3333 349:0.3333 350:0.3333 351:0.3333 352:0.3333 353:0.3167 354:0.3333 355:0.3333 356:0.3333 357:0.3333 358:0.3333 359:0.3333 360:0.3333
0.8249243289866591 1:0.3167 2:0.3167 3:0.3167 4:0.3167 5:0.3167 6:0.4167 7:0.4167 8:0.4167 9:0.4167 10:0.4167 11:0.4167 12:0.4167 13:0.4167 14:0.4333 15:0.5 16:0.5167 17:1 18:1 19:1 20:1 21:1 22:1 23:1 24:1 25:1 26:0.9333 27:0.85 28:0.8333 29:0.8 30:0.7667 31:0.75 32:0.75 33:0.7667 34:0.75 35:0.75 36:0.75 37:1 38:0.7 39:0.7 40:0.65 41:0.6333 42:0.65 43:0.5667 44:0.5667 45:0.65 46:0.5667 47:0.6333 48:0.5667 49:0.5667 50:0.5333 51:0.5333 52:0.4833 53:0.4833 54:0.4833 55:0.4667 56:0.4667 57:0.4667 58:0.45 59:0.45 60:0.45 61:0.45 62:0.4333 63:0.4333 64:0.4333 65:0.4333 66:0.4333 67:0.4167 68:0.4167 69:0.4167 70:0.4167 71:0.4167 72:0.4167 73:0.4167 74:0.4167 75:0.4167 76:0.4167 77:0.4167 78:0.4167 79:0.4167 80:0.4167 81:0.4167 82:0.4167 83:0.4167 84:0.4167 85:0.4167 86:0.4167 87:0.4167 88:0.4333 89:0.4333 90:0.4333 91:0.4333 92:0.4333 93:0.4333 94:0.4333 95:0.4333 96:0.4333 97:0.6333 98:0.6333 99:0.65 100:0.6333 101:0.45 102:0.45 103:0.45 104:0.45 105:0.45 106:0.4333 107:0.45 108:0.4333 109:0.45 110:0.4333 111:0.45 112:0.4333 113:0.45 114:0.4333 115:0.45 116:0.45 117:0.45 118:0.45 119:0.45 120:0.4667 121:0.4667 122:0.4667 123:0.4667 124:0.4833 125:0.4833 126:0.4833 127:0.5 128:0.5 129:0.8333 130:0.6167 131:0.6 132:0.6333 133:0.6167 134:0.6 135:0.6333 136:0.6 137:0.6333 138:0.6333 139:0.7167 140:0.6833 141:0.6833 142:0.84210526 143:0.77189474 144:0.77189474 145:0.77189474 146:0.84210526 147:0.84210526 148:1 149:1 150:1 151:1 152:1 153:1 154:1 155:1 156:1 157:0.35714056 158:0.32146186 159:0.32146186 160:0.32146186 161:0.32146186 162:0.32146186 163:0.21431862 164:0.21431862 165:0.21431862 166:0.21431862 167:0.21431862 168:0.21431862 169:0.21431862 170:0.21431862 171:0.21431862 172:0.21431862 173:0.21431862 174:0.21431862 175:0.160747 176:0.160747 177:0.160747 178:0.160747 179:0.160747 180:0.160747 181:0.160747 182:0.160747 183:0.160747 184:0.160747 185:0.160747 186:0.160747 187:0.160747 188:0.160747 189:0.10717538 190:0.10717538 191:0.12496116 192:0.12496116 193:0.12496116 194:0.12496116 195:0.12496116 196:0.089282462 197:0.089282462 198:0.089282462 199:0.089282462 200:0.089282462 201:0.089282462 202:0.089282462 203:0.089282462 204:0.089282462 205:0.089282462 206:0.089282462 207:0.089282462 208:0.089282462 209:0.089282462 210:0.089282462 211:0.089282462 212:0.089282462 213:0.10717538 214:0.089282462 215:0.089282462 216:0.089282462 217:0.089282462 218:0.089282462 219:0.089282462 220:0.089282462 221:0.15 222:0.15 223:0.15 224:0.15 225:0.1667 226:0.1667 227:0.1667 228:0.1667 229:0.1667 230:0.1667 231:0.1667 232:0.1667 233:0.1667 234:0.1667 235:0.1667 236:0.1667 237:0.1667 238:0.1667 239:0.1667 240:0.1667 241:0.1667 242:0.1667 243:0.1667 244:0.1667 245:0.1667 246:0.2 247:0.2 248:0.2 249:0.2 250:0.2 251:0.2333 252:0.2333 253:0.2333 254:0.2333 255:0.2333 256:0.2333 257:0.2333 258:0.25 259:0.3833 260:0.3833 261:0.4333 262:0.4333 263:0.4333 264:0.4667 265:0.55 266:0.5667 267:0.5833 268:0.8833 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:0.9 282:0.8333 283:0.8333 284:0.85 285:0.7833 286:0.6167 287:0.6167 288:0.5333 289:0.5167 290:0.5167 291:0.5167 292:0.4333 293:0.4333 294:0.4333 295:0.4333 296:0.4167 297:0.4 298:0.3833 299:0.3 300:0.3 301:0.3167 302:0.3 303:0.3 304:0.3167 305:0.3 306:0.3 307:0.3 308:0.3 309:0.3 310:0.3 311:0.3 312:0.3 313:0.3 314:0.3 315:0.3 316:0.2833 317:0.2833 318:0.3 319:0.2833 320:0.2833 321:0.2833 322:0.2833 323:0.2667 324:0.2667 325:0.2833 326:0.2833 327:0.2667 328:0.2833 329:0.2833 330:0.2667 331:0.2667 332:0.4 333:0.2667 334:0.2667 335:0.2833 336:0.2667 337:0.2667 338:0.2833 339:0.2667 340:0.2833 341:0.2833 342:0.2833 343:0.2833 344:0.2833 345:0.2833 346:0.2833 347:0.2833 348:0.2833 349:0.2833 350:0.2833 351:0.2833 352:0.2833 353:0.2833 354:0.2833 355:0.2833 356:0.2833 357:0.2833 358:0.2833 359:0.2833 360:0.3167
0.01963656411216134 1:1 2:1 3:1 4:1 5:1 6:1 7:1 8:1 9:1 10:1 11:1 12:0.7333 13:0.6 14:0.55 15:0.5167 16:0.5 17:0.5 18:0.5 19:0.45 20:0.45 21:0.4167 22:0.4167 23:0.3833 24:0.3833 25:0.35 26:0.35 27:0.35 28:0.35 29:0.35 30:0.35 31:0.35 32:0.3 33:0.3 34:0.3 35:0.2833 36:0.2833 37:0.3 38:0.2833 39:0.2833 40:0.3 41:0.2833 42:0.2833 43:0.2333 44:0.2333 45:0.2333 46:0.2333 47:0.2333 48:0.2 49:0.2 50:0.2 51:0.2 52:0.1833 53:0.1833 54:0.1833 55:0.1833 56:0.1833 57:0.1833 58:0.1833 59:0.1833 60:0.1833 61:0.1667 62:0.1667 63:0.1667 64:0.1667 65:0.1667 66:0.1667 67:0.1667 68:0.1667 69:0.1667 70:0.1667 71:0.1667 72:0.1667 73:0.1667 74:0.1667 75:0.1667 76:0.1667 77:0.1667 78:0.1667 79:0.1667 80:0.1667 81:0.1667 82:0.1667 83:0.1667 84:0.1667 85:0.1667 86:0.1667 87:0.1667 88:0.1667 89:0.1667 90:0.1667 91:0.1667 92:0.1667 93:0.1667 94:0.1667 95:0.1667 96:0.1667 97:0.1667 98:0.1667 99:0.1667 100:0.1667 101:0.1667 102:0.1667 103:0.1667 104:0.1667 105:0.1667 106:0.1667 107:0.1667 108:0.1667 109:0.1667 110:0.1667 111:0.1667 112:0.1667 113:0.1667 114:0.1667 115:0.1667 116:0.1667 117:0.1667 118:0.1667 119:0.1667 120:0.1667 121:0.1667 122:0.1833 123:0.1833 124:0.1833 125:0.1833 126:0.1833 127:0.1833 128:0.1833 129:0.1833 130:0.1833 131:0.2 132:0.2 133:0.2 134:0.2 135:0.2 136:0.2 137:0.25 138:0.2833 139:0.2833 140:0.2833 141:0.2833 142:0.24557895 143:0.24557895 144:0.24557895 145:0.22810526 146:0.24557895 147:0.24557895 148:0.26315789 149:0.26315789 150:0.26315789 151:0.28073684 152:0.31578947 153:0.29821053 154:0.31578947 155:0.33336842 156:0.33336842 157:0.33924764 158:0.35714056 159:0.51785542 160:0.51785542 161:0.51785542 162:0.58931996 163:1 164:1 165:1 166:1 167:1 168:1 169:1 170:1 171:1 172:1 173:1 174:1 175:1 176:1 177:1 178:1 179:1 180:0.91074968 181:0.91074968 182:0.7678206 183:0.7678206 184:0.51785542 185:0.51785542 186:0.51785542 187:0.51785542 188:0.44639088 189:0.41071218 190:0.41071218 191:0.39281926 192:0.39281926 193:0.39281926 194:0.39281926 195:0.39281926 196:0.39281926 197:0.39281926 198:0.39281926 199:0.39281926 200:0.39281926 201:0.39281926 202:0.39281926 203:0.39281926 204:0.33924764 205:0.33924764 206:0.33924764 207:0.33924764 208:0.33924764 209:0.33924764 210:0.28567602 211:0.28567602 212:0.28567602 213:0.28567602 214:0.28567602 215:0.28567602 216:0.28567602 217:0.28567602 218:0.28567602 219:0.28567602 220:0.28567602 221:0.3333 222:0.3333 223:0.3667 224:0.3667 225:0.35 226:0.35 227:0.35 228:0.35 229:0.35 230:0.35 231:0.35 232:0.35 233:0.35 234:0.35 235:0.35 236:0.35 237:0.35 238:0.35 239:0.3833 240:0.3833 241:0.3833 242:0.3833 243:0.3833 244:0.3833 245:0.3833 246:0.3833 247:0.3833 248:0.4 249:0.45 250:0.4 251:0.45 252:0.45 253:0.45 254:0.45 255:0.45 256:0.4833 257:0.5833 258:0.6333 259:0.6667 260:0.6667 261:0.7167 262:0.8 263:0.8 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:0.75 279:0.75 280:0.6833 281:0.5167 282:0.5 283:0.5 284:0.5 285:0.4667 286:0.4833 287:0.45 288:0.45 289:0.45 290:0.45 291:0.4167 292:0.4167 293:0.4167 294:0.4 295:0.4 296:0.4 297:0.4 298:0.3833 299:0.3833 300:0.3833 301:0.3833 302:0.3833 303:0.3833 304:0.3833 305:0.3667 306:0.3667 307:0.3833 308:0.3667 309:0.3667 310:0.3833 311:0.3667 312:0.3667 313:0.3667 314:0.3667 315:0.3667 316:0.3667 317:0.3667 318:0.3667 319:0.6167 320:0.3667 321:0.3667 322:0.3667 323:0.3667 324:0.6167 325:0.9167 326:0.95 327:0.4 328:0.4 329:0.4 330:0.3833 331:0.4 332:0.4 333:0.4 334:0.4 335:0.3833 336:0.4 337:0.3833 338:0.4 339:0.3833 340:0.4167 341:0.4167 342:0.4167 343:0.4167 344:0.4167 345:0.4667 346:0.4667 347:0.4667 348:0.4667 349:0.4667 350:0.6167 351:0.6167 352:0.6167 353:0.6833 354:0.85 355:1 356:1 357:1 358:1 359:1 360:1
0.121763739226158 1:0.4333 2:0.4333 3:0.4333 4:0.4333 5:1 6:1 7:1 8:1 9:1 10:1 11:1 12:1 13:1 14:1 15:1 16:1 17:0.8667 18:0.8667 19:0.8667 20:0.8667 21:0.75 22:0.7333 23:0.6833 24:0.6167 25:0.6 26:0.5667 27:0.55 28:0.5333 29:0.5167 30:0.5167 31:0.5167 32:0.5 33:0.5167 34:0.5167 35:0.5167 36:0.5167 37:0.45 38:0.45 39:0.45 40:0.45 41:0.45 42:0.4167 43:0.4167 44:0.4167 45:0.4167 46:0.4167 47:0.4167 48:0.4167 49:0.4167 50:0.4167 51:0.3833 52:0.3333 53:0.3333 54:0.3333 55:0.3333 56:0.3167 57:0.3167 58:0.3167 59:0.3167 60:0.3167 61:0.3167 62:0.3 63:0.3 64:0.3 65:0.3 66:0.3 67:0.3 68:0.3 69:0.3 70:0.2833 71:0.3 72:0.3 73:0.3 74:0.2833 75:0.2833 76:0.2833 77:0.2833 78:0.2833 79:0.2833 80:0.2833 81:0.2833 82:0.2833 83:0.2833 84:0.2833 85:0.2833 86:0.2833 87:0.2833 88:0.2833 89:0.2833 90:0.3 91:0.3 92:0.3 93:0.3 94:0.3 95:0.3 96:0.3167 97:0.3167 98:0.3167 99:0.3167 100:0.3167 101:0.3167 102:0.3167 103:0.3167 104:0.3167 105:0.3167 106:0.3167 107:0.3167 108:0.3167 109:0.3167 110:0.3167 111:0.3167 112:0.3167 113:0.3167 114:0.3167 115:0.3167 116:0.3167 117:0.3167 118:0.3167 119:0.3167 120:0.3333 121:0.3333 122:0.3333 123:0.3333 124:0.3333 125:0.3333 126:0.35 127:0.35 128:0.35 129:0.35 130:0.4333 131:0.45 132:0.45 133:0.45 134:0.45 135:0.45 136:0.45 137:0.45 138:0.45 139:0.4333 140:0.45 141:0.45 142:0.43863158 143:0.45610526 144:0.45610526 145:0.50873684 146:0.50873684 147:0.63157895 148:0.63157895 149:0.614 150:0.63157895 151:0.66663158 152:0.66663158 153:0.70178947 154:0.70178947 155:0.71926316 156:0.75442105 157:1 158:1 159:1 160:1 161:1 162:1 163:1 164:1 165:1 166:1 167:1 168:1 169:1 170:1 171:1 172:0.51785542 173:0.51785542 174:0.41071218 175:0.41071218 176:0.39281926 177:0.39281926 178:0.39281926 179:0.39281926 180:0.39281926 181:0.39281926 182:0.39281926 183:0.28567602 184:0.28567602 185:0.28567602 186:0.28567602 187:0.28567602 188:0.28567602 189:0.28567602 190:0.28567602 191:0.28567602 192:0.28567602 193:0.2321044 194:0.2321044 195:0.2321044 196:0.2321044 197:0.21431862 198:0.21431862 199:0.21431862 200:0.2321044 201:0.21431862 202:0.21431862 203:0.2321044 204:0.21431862 205:0.21431862 206:0.21431862 207:0.21431862 208:0.21431862 209:0.21431862 210:0.24999732 211:0.21431862 212:0.21431862 213:0.2321044 214:0.2321044 215:0.21431862 216:0.2321044 217:0.2321044 218:0.21431862 219:0.21431862 220:0.2321044 221:0.2833 222:0.2833 223:0.2833 224:0.2833 225:0.2833 226:0.2833 227:0.3 228:0.3 229:0.3 230:0.3 231:0.3 232:0.3 233:0.3 234:0.3 235:0.3 236:0.3 237:0.3 238:0.3 239:0.3 240:0.3 241:0.35 242:0.35 243:0.3667 244:0.35 245:0.3667 246:0.3667 247:0.3833 248:0.45 249:0.45 250:0.45 251:0.45 252:0.45 253:0.45 254:0.5333 255:0.5667 256:0.5667 257:0.5833 258:0.6333 259:0.65 260:0.65 261:0.7167 262:0.9333 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:0.9333 277:0.6 278:0.6 279:0.6 280:0.6 281:0.5333 282:0.3833 283:0.3833 284:0.3833 285:0.3833 286:0.3833 287:0.3833 288:0.3667 289:0.3667 290:0.3667 291:0.3167 292:0.3167 293:0.3167 294:0.3167 295:0.3 296:0.3167 297:0.3167 298:0.3167 299:0.3167 300:0.3167 301:0.3167 302:0.3167 303:0.3167 304:0.3167 305:0.3167 306:0.3167 307:0.3 308:0.3167 309:0.2833 310:0.2833 311:0.2833 312:0.2833 313:0.2833 314:0.3167 315:0.2833 316:0.2833 317:0.2833 318:0.4 319:0.2833 320:0.2833 321:0.2833 322:0.2833 323:0.2833 324:0.2833 325:0.2833 326:0.2833 327:0.5167 328:0.2833 329:0.2833 330:0.5167 331:0.2833 332:0.2833 333:0.5167 334:0.2833 335:0.2833 336:0.2833 337:0.2833 338:0.2833 339:0.2833 340:0.6167 341:0.6167 342:0.7 343:0.7 344:0.3333 345:0.3333 346:0.3333 347:0.3333 348:0.3333 349:0.3333 350:0.3333 351:0.3333 352:0.3333 353:0.3333 354:0.3333 355:0.3333 356:0.3333 357:0.35 358:0.3667 359:0.3667 360:0.4333
0.02385970978229091 1:0.3333 2:0.3333 3:0.3333 4:0.3333 5:0.3333 6:0.3333 7:0.3333 8:0.3667 9:0.3667 10:0.4167 11:0.4167 12:0.4167 13:0.4167 14:0.45 15:0.45 16:0.45 17:0.75 18:0.75 19:0.7667 20:0.7667 21:1 22:1 23:1 24:1 25:1 26:1 27:1 28:1 29:1 30:1 31:1 32:1 33:1 34:1 35:1 36:1 37:1 38:1 39:1 40:1 41:1 42:1 43:1 44:1 45:1 46:0.4833 47:0.4833 48:0.4833 49:0.4833 50:0.4833 51:0.4833 52:0.4833 53:0.4833 54:0.4833 55:0.4833 56:0.4833 57:0.6167 58:0.6167 59:0.6167 60:0.6167 61:0.6 62:0.6167 63:0.6167 64:0.25 65:0.25 66:0.25 67:0.2333 68:0.2333 69:0.2333 70:0.2333 71:0.25 72:0.2333 73:0.2333 74:0.25 75:0.25 76:0.25 77:0.2333 78:0.25 79:0.25 80:0.2333 81:0.2333 82:0.2333 83:0.2333 84:0.2333 85:0.2333 86:0.2833 87:0.2833 88:0.2833 89:0.2833 90:0.2833 91:0.2833 92:0.2833 93:0.2833 94:0.2833 95:0.2833 96:0.3833 97:0.3833 98:0.3667 99:0.3833 100:0.3667 101:0.3833 102:0.3833 103:0.3667 104:0.3667 105:0.3667 106:0.3667 107:0.3667 108:0.3667 109:0.3667 110:0.3667 111:0.3667 112:0.3667 113:0.3667 114:0.3667 115:0.3833 116:0.3833 117:0.2833 118:0.2833 119:0.2833 120:0.2833 121:0.2833 122:0.2833 123:0.2833 124:0.2833 125:0.2833 126:0.2833 127:0.2833 128:0.2833 129:0.2833 130:0.2833 131:0.2833 132:0.2833 133:0.2333 134:0.2333 135:0.25 136:0.25 137:0.25 138:0.25 139:0.25 140:0.25 141:0.25 142:0.21052632 143:0.21052632 144:0.21052632 145:0.19294737 146:0.21052632 147:0.21052632 148:0.21052632 149:0.19294737 150:0.21052632 151:0.21052632 152:0.21052632 153:0.36842105 154:0.31578947 155:0.386 156:0.36842105 157:0.37503348 158:0.35714056 159:0.4999625 160:0.35714056 161:0.4999625 162:0.4999625 163:0.4999625 164:0.4999625 165:0.4999625 166:0.53574834 167:0.55353412 168:0.53574834 169:0.55353412 170:0.55353412 171:0.57142704 172:0.57142704 173:0.58931996 174:0.58931996 175:0.58931996 176:0.58931996 177:0.58931996 178:0.64289158 179:0.64289158 180:0.64289158 181:0.64289158 182:0.71424898 183:0.85717806 184:1 185:1 186:1 187:1 188:1 189:1 190:1 191:1 192:1 193:1 194:1 195:1 196:1 197:1 198:1 199:1 200:1 201:1 202:1 203:0.98210708 204:0.98210708 205:0.83928514 206:0.66067736 207:0.64289158 208:0.4999625 209:0.48217672 210:0.48217672 211:0.48217672 212:0.35714056 213:0.35714056 214:0.35714056 215:0.26789024 216:0.24999732 217:0.24999732 218:0.24999732 219:0.2321044 220:0.1964257 221:0.2167 222:0.2167 223:0.2167 224:0.2167 225:0.2167 226:0.2 227:0.2 228:0.2167 229:0.2167 230:0.2167 231:0.2 232:0.2167 233:0.2167 234:0.2167 235:0.2 236:0.2167 237:0.2167 238:0.2167 239:0.2167 240:0.2 241:0.2167 242:0.2167 243:0.2 244:0.2 245:0.25 246:0.25 247:0.25 248:0.25 249:0.2333 250:0.25 251:0.25 252:0.2333 253:0.2333 254:0.25 255:0.3833 256:0.8 257:0.3833 258:0.3833 259:0.3833 260:0.3833 261:0.3833 262:0.3833 263:0.3833 264:0.3833 265:0.3833 266:0.3833 267:0.3833 268:0.3833 269:0.3833 270:0.4833 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:0.9833 284:0.8167 285:0.8167 286:0.7667 287:0.7667 288:0.7167 289:0.65 290:0.5667 291:0.55 292:0.4833 293:0.4833 294:0.4833 295:0.4667 296:0.4167 297:0.4 298:0.4167 299:0.4 300:0.4167 301:0.3833 302:0.3667 303:0.3667 304:0.35 305:0.3167 306:0.3167 307:0.3167 308:0.3167 309:0.3167 310:0.3167 311:0.3167 312:0.3167 313:0.3167 314:0.3167 315:0.3167 316:0.3167 317:0.3167 318:0.3167 319:0.3833 320:0.3833 321:0.3833 322:0.3833 323:0.5333 324:0.5333 325:0.5333 326:0.5333 327:0.5167 328:0.5167 329:0.4833 330:0.4833 331:0.5 332:0.4833 333:0.5 334:0.4833 335:0.4833 336:0.4667 337:0.4667 338:0.45 339:0.45 340:0.3167 341:0.2833 342:0.2833 343:0.2833 344:0.2833 345:0.2833 346:0.2833 347:0.3 348:0.2833 349:0.2833 350:0.3 351:0.2833 352:0.2833 353:0.2833 354:0.2833 355:0.2833 356:0.2833 357:0.3333 358:0.3333 359:0.3333 360:0.3333
0.1020957440900423 1:0.3167 2:0.3167 3:0.3167 4:0.3167 5:0.3167 6:0.3167 7:0.3167 8:0.3167 9:0.35 10:0.35 11:0.4 12:0.4 13:0.4 14:0.4333 15:0.4333 16:0.4333 17:0.7333 18:0.7333 19:0.75 20:0.75 21:1 22:1 23:1 24:1 25:1 26:1 27:1 28:1 29:1 30:1 31:1 32:1 33:1 34:1 35:1 36:1 37:1 38:1 39:1 40:1 41:1 42:1 43:1 44:1 45:1 46:1 47:0.4833 48:0.4667 49:0.4667 50:0.4667 51:0.4667 52:0.4667 53:0.4667 54:0.4667 55:0.4667 56:0.4667 57:0.4667 58:0.4833 59:0.4833 60:0.6 61:0.6 62:0.6 63:0.6 64:0.6 65:0.6 66:0.6 67:0.2333 68:0.2333 69:0.2333 70:0.2333 71:0.2333 72:0.2333 73:0.2333 74:0.2333 75:0.2333 76:0.2333 77:0.2333 78:0.2333 79:0.2333 80:0.2333 81:0.2333 82:0.2333 83:0.2333 84:0.2333 85:0.2333 86:0.2333 87:0.2333 88:0.2333 89:0.2333 90:0.2833 91:0.2833 92:0.2833 93:0.2833 94:0.2833 95:0.2833 96:0.2833 97:0.2833 98:0.2833 99:0.3833 100:0.3833 101:0.3833 102:0.3833 103:0.3833 104:0.3833 105:0.3667 106:0.3667 107:0.3667 108:0.3667 109:0.3667 110:0.3833 111:0.3667 112:0.3833 113:0.3667 114:0.3667 115:0.3667 116:0.3667 117:0.3667 118:0.4 119:0.4 120:0.3833 121:0.2833 122:0.3 123:0.3 124:0.2833 125:0.2833 126:0.2833 127:0.2833 128:0.2833 129:0.2833 130:0.2833 131:0.2833 132:0.2833 133:0.2833 134:0.2833 135:0.25 136:0.25 137:0.25 138:0.2667 139:0.25 140:0.25 141:0.25 142:0.22810526 143:0.21052632 144:0.21052632 145:0.22810526 146:0.21052632 147:0.21052632 148:0.21052632 149:0.21052632 150:0.21052632 151:0.21052632 152:0.21052632 153:0.22810526 154:0.33336842 155:0.33336842 156:0.33336842 157:0.37503348 158:0.37503348 159:0.37503348 160:0.37503348 161:0.37503348 162:0.4999625 163:0.51785542 164:0.51785542 165:0.51785542 166:0.51785542 167:0.55353412 168:0.55353412 169:0.57142704 170:0.57142704 171:0.58931996 172:0.58931996 173:0.60710574 174:0.60710574 175:0.60710574 176:0.60710574 177:0.60710574 178:0.66067736 179:0.66067736 180:0.66067736 181:0.66067736 182:0.7321419 183:0.87496384 184:1 185:1 186:1 187:1 188:1 189:1 190:1 191:1 192:1 193:1 194:1 195:1 196:1 197:1 198:1 199:1 200:1 201:1 202:1 203:1 204:0.85717806 205:0.85717806 206:0.66067736 207:0.66067736 208:0.4999625 209:0.4999625 210:0.4999625 211:0.37503348 212:0.37503348 213:0.37503348 214:0.26789024 215:0.26789024 216:0.24999732 217:0.24999732 218:0.21431862 219:0.21431862 220:0.17853278 221:0.2167 222:0.2167 223:0.2167 224:0.2167 225:0.2167 226:0.2167 227:0.2167 228:0.2167 229:0.2167 230:0.2167 231:0.2167 232:0.2167 233:0.2167 234:0.2167 235:0.2167 236:0.2167 237:0.2167 238:0.2167 239:0.2167 240:0.2167 241:0.2167 242:0.2167 243:0.25 244:0.25 245:0.25 246:0.25 247:0.25 248:0.25 249:0.25 250:0.25 251:0.2667 252:0.4 253:0.4 254:0.4 255:0.4 256:0.3833 257:0.3833 258:0.3833 259:0.3833 260:0.3833 261:0.3833 262:0.3833 263:0.3833 264:0.3833 265:0.3833 266:0.3833 267:0.3833 268:0.4833 269:0.8167 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:0.9667 283:0.8 284:0.7667 285:0.7667 286:0.7667 287:0.6333 288:0.55 289:0.55 290:0.4833 291:0.4667 292:0.4833 293:0.4167 294:0.4 295:0.4 296:0.4 297:0.4 298:0.3833 299:0.3667 300:0.3667 301:0.35 302:0.3 303:0.3 304:0.3 305:0.3 306:0.3 307:0.3 308:0.3 309:0.3 310:0.3 311:0.3 312:0.3 313:0.3 314:0.3 315:0.3 316:0.3 317:0.3 318:0.3833 319:0.3667 320:0.3667 321:0.5167 322:0.5167 323:0.5167 324:0.5167 325:0.5167 326:0.5 327:0.5 328:0.5 329:0.4667 330:0.4833 331:0.4667 332:0.4833 333:0.4667 334:0.4667 335:0.45 336:0.45 337:0.45 338:0.4333 339:0.3 340:0.2667 341:0.2667 342:0.2667 343:0.2833 344:0.2667 345:0.2667 346:0.2833 347:0.2833 348:0.2667 349:0.2667 350:0.2833 351:0.2667 352:0.2667 353:0.2667 354:0.2667 355:0.2667 356:0.2833 357:0.3167 358:0.3167 359:0.3167 360:0.3167
0.008936277474449287 1:0.4333 2:0.4333 3:0.4333 4:0.4333 5:0.4667 6:0.4667 7:0.4667 8:0.5333 9:0.6 10:0.6 11:0.6 12:0.6 13:0.7667 14:0.7667 15:0.7667 16:0.7667 17:0.9333 18:1 19:1 20:1 21:1 22:1 23:1 24:1 25:1 26:1 27:1 28:1 29:1 30:1 31:1 32:1 33:1 34:1 35:1 36:1 37:1 38:1 39:1 40:0.4333 41:0.45 42:0.45 43:0.45 44:0.45 45:0.45 46:0.45 47:0.45 48:0.45 49:0.4333 50:0.45 51:0.3167 52:0.3167 53:0.3167 54:0.2 55:0.1833 56:0.1833 57:0.1833 58:0.1833 59:0.1833 60:0.1833 61:0.1833 62:0.1833 63:0.1833 64:0.1833 65:0.1833 66:0.1833 67:0.1833 68:0.1833 69:0.1833 70:0.1833 71:0.1833 72:0.1833 73:0.1833 74:0.1833 75:0.1833 76:0.1833 77:0.1833 78:0.1833 79:0.2 80:0.2167 81:0.2167 82:0.2167 83:0.2167 84:0.2167 85:0.2167 86:0.2167 87:0.2167 88:0.2167 89:0.2 90:0.2 91:0.2 92:0.2 93:0.2 94:0.2 95:0.2 96:0.2 97:0.2 98:0.2 99:0.2 100:0.2 101:0.2 102:0.2 103:0.2 104:0.2 105:0.2 106:0.2 107:0.2 108:0.2 109:0.2 110:0.2 111:0.3 112:0.3167 113:0.3167 114:0.3167 115:0.3167 116:0.3167 117:0.3167 118:0.3167 119:0.3167 120:0.3167 121:0.3167 122:0.3167 123:0.3167 124:0.3167 125:0.3167 126:0.3167 127:0.3167 128:0.3333 129:0.3333 130:0.3167 131:0.3333 132:0.3333 133:0.3167 134:0.3333 135:0.3333 136:0.3167 137:0.3333 138:0.3333 139:0.3333 140:0.35 141:0.25 142:0.14031579 143:0.14031579 144:0.14031579 145:0.15789474 146:0.15789474 147:0.14031579 148:0.14031579 149:0.14031579 150:0.15789474 151:0.15789474 152:0.15789474 153:0.14031579 154:0.15789474 155:0.15789474 156:0.15789474 157:0.12496116 158:0.12496116 159:0.14285408 160:0.14285408 161:0.12496116 162:0.12496116 163:0.12496116 164:0.14285408 165:0.14285408 166:0.32146186 167:0.32146186 168:0.32146186 169:0.32146186 170:0.33924764 171:0.58931996 172:0.58931996 173:0.58931996 174:0.58931996 175:0.58931996 176:0.62499866 177:0.62499866 178:0.62499866 179:0.62499866 180:0.62499866 181:0.64289158 182:0.66067736 183:0.66067736 184:0.67857028 185:0.67857028 186:0.6964632 187:0.6964632 188:0.6964632 189:1 190:1 191:1 192:1 193:1 194:1 195:1 196:1 197:1 198:1 199:1 200:1 201:1 202:1 203:1 204:1 205:1 206:1 207:1 208:0.98210708 209:0.67857028 210:0.67857028 211:0.67857028 212:0.67857028 213:0.62499866 214:0.4999625 215:0.4999625 216:0.4999625 217:0.4999625 218:0.4999625 219:0.44639088 220:0.39281926 221:0.4333 222:0.4333 223:0.4333 224:0.4333 225:0.35 226:0.35 227:0.35 228:0.3333 229:0.3333 230:0.3333 231:0.3167 232:0.3 233:0.2667 234:0.2667 235:0.2833 236:0.2833 237:0.2667 238:0.25 239:0.25 240:0.25 241:0.2667 242:0.2667 243:0.25 244:0.2667 245:0.2667 246:0.25 247:0.25 248:0.2833 249:0.2667 250:0.25 251:0.2833 252:0.2667 253:0.25 254:0.25 255:0.2833 256:0.2833 257:0.2833 258:0.2833 259:0.2833 260:0.3 261:0.4333 262:0.4333 263:0.4333 264:0.4333 265:0.4333 266:0.4333 267:0.4333 268:0.4333 269:0.4333 270:0.4833 271:0.4833 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:0.9667 284:0.9667 285:0.8167 286:0.8167 287:0.8167 288:0.8167 289:0.8167 290:0.7 291:0.5667 292:0.5667 293:0.5667 294:0.4833 295:0.4667 296:0.45 297:0.4667 298:0.4167 299:0.4167 300:0.4167 301:0.4167 302:0.4167 303:0.4167 304:0.4167 305:0.4 306:0.4167 307:0.4 308:0.4167 309:0.4167 310:0.4167 311:0.4167 312:0.4 313:0.4167 314:0.4 315:0.4333 316:0.4333 317:0.4333 318:0.4333 319:0.4333 320:0.5833 321:0.25 322:0.25 323:0.25 324:0.25 325:0.25 326:0.25 327:0.25 328:0.25 329:0.25 330:0.25 331:0.25 332:0.25 333:0.25 334:0.25 335:0.25 336:0.25 337:0.25 338:0.25 339:0.25 340:0.25 341:0.35 342:0.3333 343:0.5667 344:0.35 345:0.3333 346:0.35 347:0.35 348:0.35 349:0.35 350:0.35 351:0.35 352:0.35 353:0.35 354:0.35 355:0.35 356:0.35 357:0.35 358:0.4167 359:0.4167 360:0.4333
0.04463601072592369 1:0.4167 2:0.4167 3:0.4333 4:0.4333 5:0.45 6:0.45 7:0.45 8:0.45 9:0.4833 10:0.6167 11:0.6333 12:0.6333 13:0.6333 14:0.65 15:0.7833 16:0.7833 17:0.7833 18:0.95 19:1 20:1 21:1 22:1 23:1 24:1 25:1 26:1 27:1 28:1 29:1 30:1 31:1 32:1 33:1 34:1 35:1 36:1 37:1 38:1 39:1 40:1 41:0.4833 42:0.4667 43:0.4833 44:0.4667 45:0.4833 46:0.4667 47:0.4833 48:0.4667 49:0.4833 50:0.4333 51:0.4333 52:0.3333 53:0.3333 54:0.2333 55:0.2167 56:0.2167 57:0.2167 58:0.2167 59:0.2167 60:0.2167 61:0.2167 62:0.2167 63:0.2167 64:0.2333 65:0.2167 66:0.2167 67:0.2167 68:0.2333 69:0.2167 70:0.2167 71:0.2167 72:0.2167 73:0.2167 74:0.2167 75:0.2167 76:0.2167 77:0.2333 78:0.2333 79:0.2333 80:0.2333 81:0.2333 82:0.2333 83:0.2333 84:0.2333 85:0.2333 86:0.2333 87:0.2333 88:0.2333 89:0.2333 90:0.2333 91:0.2333 92:0.2333 93:0.3333 94:0.3333 95:0.3333 96:0.3333 97:0.3333 98:0.3333 99:0.3167 100:0.3333 101:0.3333 102:0.3333 103:0.3333 104:0.3333 105:0.3333 106:0.3333 107:0.3167 108:0.3167 109:0.3333 110:0.3167 111:0.3333 112:0.3333 113:0.3333 114:0.3333 115:0.3333 116:0.3167 117:0.3333 118:0.3333 119:0.3167 120:0.3333 121:0.3333 122:0.3333 123:0.3333 124:0.2333 125:0.2333 126:0.2333 127:0.2333 128:0.2333 129:0.2333 130:0.2333 131:0.2333 132:0.2 133:0.1833 134:0.1833 135:0.1833 136:0.1833 137:0.1833 138:0.1833 139:0.1667 140:0.1667 141:0.1667 142:0.14031579 143:0.14031579 144:0.14031579 145:0.14031579 146:0.14031579 147:0.14031579 148:0.14031579 149:0.14031579 150:0.14031579 151:0.12284211 152:0.14031579 153:0.14031579 154:0.14031579 155:0.14031579 156:0.12284211 157:0.12496116 158:0.12496116 159:0.12496116 160:0.10717538 161:0.10717538 162:0.35714056 163:0.35714056 164:0.35714056 165:0.35714056 166:0.35714056 167:0.35714056 168:0.35714056 169:0.57142704 170:0.57142704 171:0.57142704 172:0.57142704 173:0.60710574 174:0.60710574 175:0.60710574 176:0.60710574 177:0.60710574 178:0.62499866 179:0.62499866 180:0.62499866 181:0.64289158 182:0.64289158 183:0.64289158 184:0.64289158 185:0.64289158 186:0.64289158 187:0.64289158 188:1 189:1 190:1 191:1 192:1 193:1 194:1 195:1 196:1 197:1 198:0.98210708 199:0.98210708 200:0.98210708 201:0.98210708 202:0.98210708 203:1 204:1 205:1 206:1 207:1 208:0.82139222 209:0.66067736 210:0.66067736 211:0.66067736 212:0.62499866 213:0.48217672 214:0.4642838 215:0.4642838 216:0.4642838 217:0.4286051 218:0.4286051 219:0.37503348 220:0.37503348 221:0.4 222:0.4 223:0.3833 224:0.3833 225:0.3 226:0.3 227:0.2667 228:0.2667 229:0.2667 230:0.2667 231:0.25 232:0.25 233:0.25 234:0.2333 235:0.2167 236:0.2333 237:0.2333 238:0.2333 239:0.2333 240:0.2333 241:0.2333 242:0.2333 243:0.2333 244:0.2333 245:0.2333 246:0.2333 247:0.2333 248:0.2333 249:0.2333 250:0.2333 251:0.2333 252:0.2333 253:0.2333 254:0.2667 255:0.2667 256:0.2667 257:0.2667 258:0.2667 259:0.2667 260:0.2667 261:0.2667 262:0.2667 263:0.4167 264:0.4167 265:0.4167 266:0.4167 267:0.4167 268:0.4167 269:0.4167 270:0.4167 271:0.4167 272:0.4167 273:0.45 274:0.45 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:0.9167 285:0.9 286:0.9 287:0.7667 288:0.7667 289:0.7667 290:0.7833 291:0.7667 292:0.7 293:0.6833 294:0.5667 295:0.5333 296:0.5333 297:0.5333 298:0.5167 299:0.45 300:0.45 301:0.45 302:0.4333 303:0.4333 304:0.3833 305:0.3833 306:0.3833 307:0.3833 308:0.3833 309:0.3833 310:0.3833 311:0.3833 312:0.3833 313:0.3833 314:0.3833 315:0.3833 316:0.4 317:0.4 318:0.4 319:0.4333 320:0.4333 321:0.4333 322:0.4333 323:0.5667 324:0.5833 325:0.5833 326:0.5667 327:0.5667 328:0.55 329:0.55 330:0.55 331:0.55 332:0.55 333:0.5167 334:0.5 335:0.5 336:0.35 337:0.35 338:0.35 339:0.35 340:0.35 341:0.35 342:0.35 343:0.35 344:0.35 345:0.35 346:0.35 347:0.35 348:0.35 349:0.35 350:0.35 351:0.35 352:0.3667 353:0.3667 354:0.3667 355:0.3667 356:0.3667 357:0.3667 358:0.3667 359:0.3667 360:0.4167
0.3395558283041472 1:0.3333 2:0.3333 3:0.3833 4:0.3833 5:0.4 6:0.4 7:0.4 8:0.4 9:0.4 10:0.4667 11:0.4667 12:0.4667 13:0.4667 14:0.5167 15:0.7 16:0.7 17:0.7 18:0.8667 19:0.8667 20:0.8667 21:1 22:1 23:1 24:1 25:1 26:1 27:1 28:1 29:1 30:1 31:1 32:1 33:1 34:1 35:1 36:1 37:1 38:1 39:1 40:1 41:0.9 42:0.9 43:0.8833 44:0.4 45:0.4 46:0.4 47:0.4 48:0.4 49:0.4 50:0.4 51:0.4 52:0.4 53:0.4 54:0.4 55:0.3833 56:0.3 57:0.3 58:0.3 59:0.3 60:0.3 61:0.3 62:0.3 63:0.3 64:0.3 65:0.3 66:0.3 67:0.3 68:0.1667 69:0.1667 70:0.1667 71:0.1667 72:0.1667 73:0.1667 74:0.1667 75:0.1667 76:0.1667 77:0.1667 78:0.1667 79:0.1667 80:0.1667 81:0.1667 82:0.1667 83:0.1667 84:0.1667 85:0.1667 86:0.1667 87:0.1667 88:0.1667 89:0.1667 90:0.1667 91:0.1667 92:0.1667 93:0.1667 94:0.1667 95:0.1667 96:0.1667 97:0.1667 98:0.1667 99:0.2 100:0.2 101:0.2 102:0.2 103:0.2 104:0.2 105:0.2 106:0.2 107:0.2 108:0.2 109:0.2 110:0.2 111:0.2 112:0.2 113:0.2 114:0.2 115:0.2 116:0.2167 117:0.2167 118:0.2167 119:0.2167 120:0.2167 121:0.2167 122:0.2167 123:0.2167 124:0.2167 125:0.2167 126:0.2167 127:0.2167 128:0.2167 129:0.2167 130:0.2167 131:0.2167 132:0.3 133:0.3 134:0.3 135:0.3 136:0.3 137:0.3 138:0.25 139:0.25 140:0.25 141:0.3 142:0.21052632 143:0.21052632 144:0.21052632 145:0.21052632 146:0.21052632 147:0.21052632 148:0.21052632 149:0.21052632 150:0.21052632 151:0.21052632 152:0.21052632 153:0.21052632 154:0.21052632 155:0.21052632 156:0.21052632 157:0.1964257 158:0.1964257 159:0.1964257 160:0.1964257 161:0.1964257 162:0.1964257 163:0.1964257 164:0.1964257 165:0.1964257 166:0.1964257 167:0.1964257 168:0.1964257 169:0.1964257 170:0.1964257 171:0.1964257 172:0.21431862 173:0.4999625 174:0.4999625 175:0.51785542 176:0.51785542 177:0.51785542 178:0.51785542 179:0.51785542 180:0.51785542 181:0.55353412 182:0.55353412 183:0.55353412 184:0.6964632 185:0.6964632 186:0.6964632 187:0.6964632 188:0.6964632 189:1 190:1 191:1 192:1 193:1 194:1 195:1 196:0.82139222 197:0.82139222 198:0.82139222 199:0.82139222 200:0.82139222 201:0.82139222 202:0.82139222 203:0.82139222 204:0.83928514 205:1 206:1 207:1 208:1 209:0.91074968 210:0.75003482 211:0.75003482 212:0.75003482 213:0.55353412 214:0.55353412 215:0.55353412 216:0.55353412 217:0.55353412 218:0.44639088 219:0.44639088 220:0.44639088 221:0.4833 222:0.4667 223:0.3833 224:0.3833 225:0.3833 226:0.3167 227:0.3167 228:0.3167 229:0.3167 230:0.2833 231:0.2833 232:0.2833 233:0.2833 234:0.2833 235:0.2833 236:0.2833 237:0.2833 238:0.2833 239:0.2833 240:0.2833 241:0.2833 242:0.2833 243:0.2833 244:0.2833 245:0.2833 246:0.2833 247:0.2833 248:0.2833 249:0.2833 250:0.3333 251:0.3333 252:0.3333 253:0.4667 254:0.4667 255:0.4667 256:0.4667 257:0.4667 258:0.4667 259:0.4667 260:0.4667 261:0.4667 262:0.4667 263:0.4667 264:0.6333 265:0.65 266:0.65 267:0.65 268:0.7 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:0.9667 281:0.9167 282:0.8 283:0.6833 284:0.6833 285:0.6667 286:0.6333 287:0.6333 288:0.6333 289:0.5167 290:0.4333 291:0.4333 292:0.4333 293:0.4167 294:0.4167 295:0.3833 296:0.3833 297:0.3833 298:0.3833 299:0.3833 300:0.3833 301:0.3833 302:0.3833 303:0.3833 304:0.3833 305:0.3833 306:0.3833 307:0.3833 308:0.3833 309:0.3833 310:0.4167 311:0.4167 312:0.6 313:0.5833 314:0.55 315:0.55 316:0.2 317:0.2 318:0.55 319:0.5333 320:0.2167 321:0.2 322:0.5 323:0.5 324:0.2167 325:0.2 326:0.2167 327:0.2833 328:0.2167 329:0.2167 330:0.2 331:0.2833 332:0.2833 333:0.2 334:0.2 335:0.2833 336:0.2833 337:0.2833 338:0.2833 339:0.2833 340:0.2833 341:0.2833 342:0.2833 343:0.3 344:0.3167 345:0.3167 346:0.3167 347:0.3167 348:0.3167 349:0.3167 350:0.3167 351:0.3167 352:0.3167 353:0.3167 354:0.3167 355:0.3167 356:0.3167 357:0.3333 358:0.3333 359:0.3333 360:0.3333
0.7309356042906542 1:0.35 2:0.35 3:0.35 4:0.35 5:0.35 6:0.35 7:0.35 8:0.45 9:0.55 10:0.55 11:0.7333 12:0.7333 13:0.7333 14:0.7333 15:1 16:1 17:1 18:1 19:1 20:1 21:1 22:1 23:1 24:1 25:1 26:1 27:1 28:1 29:1 30:1 31:0.6833 32:0.6333 33:0.5833 34:0.5833 35:0.5167 36:0.4833 37:0.4667 38:0.4667 39:0.45 40:0.4333 41:0.4333 42:0.4333 43:0.4333 44:0.4333 45:0.4333 46:0.4333 47:0.4333 48:0.4333 49:0.4333 50:0.4333 51:0.3667 52:0.3667 53:0.3667 54:0.3667 55:0.35 56:0.35 57:0.3333 58:0.3333 59:0.35 60:0.3333 61:0.3333 62:0.35 63:0.3333 64:0.3333 65:0.35 66:0.3333 67:0.35 68:0.3333 69:0.3333 70:0.35 71:0.35 72:0.35 73:0.35 74:0.3667 75:0.35 76:0.35 77:0.3667 78:0.3667 79:0.3667 80:0.3833 81:0.45 82:0.45 83:0.45 84:0.4667 85:0.4667 86:0.4667 87:0.4833 88:0.4833 89:0.9667 90:0.9667 91:0.85 92:0.85 93:0.85 94:0.85 95:0.85 96:0.85 97:0.85 98:0.85 99:0.85 100:0.85 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:0.7667 109:0.7667 110:0.7667 111:0.7167 112:0.7167 113:0.7667 114:0.7167 115:0.6667 116:0.7167 117:0.6833 118:0.6667 119:0.7 120:0.6833 121:0.65 122:0.6667 123:0.6167 124:0.6167 125:0.6167 126:0.6167 127:0.6167 128:0.5667 129:0.55 130:0.5667 131:0.5667 132:0.5667 133:0.2333 134:0.2333 135:0.55 136:0.55 137:0.25 138:0.25 139:0.25 140:0.25 141:0.25 142:0.21052632 143:0.21052632 144:0.21052632 145:0.19294737 146:0.21052632 147:0.21052632 148:0.21052632 149:0.19294737 150:0.21052632 151:0.21052632 152:0.24557895 153:0.21052632 154:0.21052632 155:0.24557895 156:0.24557895 157:0.2321044 158:0.2321044 159:0.2321044 160:0.2321044 161:0.2321044 162:0.2321044 163:0.2321044 164:0.2321044 165:0.2321044 166:0.2321044 167:0.2321044 168:0.2321044 169:0.2321044 170:0.2321044 171:0.2321044 172:0.2321044 173:0.2321044 174:0.2321044 175:0.2321044 176:0.2321044 177:0.2321044 178:0.071389541 179:0.071389541 180:0.071389541 181:0.071389541 182:0.071389541 183:0.071389541 184:0.071389541 185:0.071389541 186:0.071389541 187:0.071389541 188:0.071389541 189:0.071389541 190:0.071389541 191:0.071389541 192:0.071389541 193:0.071389541 194:0.071389541 195:0.071389541 196:0.071389541 197:0.071389541 198:0.071389541 199:0.071389541 200:0.071389541 201:0.071389541 202:0.071389541 203:0.071389541 204:0.071389541 205:0.071389541 206:0.071389541 207:0.071389541 208:0.071389541 209:0.071389541 210:0.160747 211:0.160747 212:0.160747 213:0.160747 214:0.160747 215:0.160747 216:0.160747 217:0.160747 218:0.160747 219:0.160747 220:0.160747 221:0.4167 222:0.2167 223:0.2167 224:0.2167 225:0.4 226:0.4 227:0.3833 228:0.3833 229:0.3833 230:0.3667 231:0.3833 232:0.3667 233:0.3833 234:0.3833 235:0.3667 236:0.3833 237:0.3667 238:0.3833 239:0.3833 240:0.3667 241:1 242:1 243:1 244:1 245:1 246:1 247:1 248:1 249:0.4833 250:0.4833 251:0.4833 252:0.4833 253:0.4833 254:0.4833 255:0.4833 256:0.4833 257:0.4833 258:0.4833 259:0.4833 260:0.4833 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:0.95 281:0.95 282:0.8 283:0.6833 284:0.4833 285:0.4833 286:0.4833 287:0.4167 288:0.3667 289:0.3667 290:0.3667 291:0.3167 292:0.3167 293:0.2833 294:0.2833 295:0.2833 296:0.2833 297:0.2833 298:0.25 299:0.25 300:0.2833 301:0.25 302:0.25 303:0.25 304:0.25 305:0.25 306:0.25 307:0.25 308:0.25 309:0.25 310:0.25 311:0.6 312:0.25 313:0.25 314:0.25 315:0.5667 316:0.5667 317:0.5333 318:0.5167 319:0.5167 320:0.5167 321:0.5167 322:0.5167 323:0.25 324:0.25 325:0.25 326:0.25 327:0.25 328:0.25 329:0.25 330:0.25 331:0.25 332:0.25 333:0.25 334:0.25 335:0.25 336:0.25 337:0.25 338:0.25 339:0.25 340:0.25 341:0.2667 342:0.4833 343:0.4833 344:0.3833 345:0.3667 346:0.3667 347:0.35 348:0.35 349:0.35 350:0.35 351:0.35 352:0.35 353:0.35 354:0.35 355:0.35 356:0.35 357:0.35 358:0.35 359:0.35 360:0.35
0.5631591986299216 1:0.2167 2:0.2167 3:0.2167 4:0.2167 5:0.2167 6:0.2167 7:0.2167 8:0.2333 9:0.2333 10:0.2333 11:0.2333 12:0.2167 13:0.2167 14:0.2167 15:0.2167 16:0.2167 17:0.2167 18:0.2167 19:0.2167 20:0.2167 21:0.2167 22:0.2167 23:0.2167 24:0.2167 25:0.2167 26:0.2167 27:0.2167 28:0.2167 29:0.2167 30:0.2167 31:0.2167 32:0.2167 33:0.25 34:0.25 35:0.2667 36:0.2667 37:0.25 38:0.2667 39:0.2667 40:0.25 41:0.25 42:0.2667 43:0.2667 44:0.2667 45:0.2667 46:0.2833 47:0.2667 48:0.2833 49:0.2833 50:0.2667 51:0.3 52:0.3 53:0.3167 54:0.3167 55:0.3333 56:0.3333 57:0.3333 58:0.3333 59:0.3333 60:0.3333 61:0.35 62:0.3667 63:0.3667 64:0.3833 65:0.4 66:0.4167 67:0.4333 68:0.45 69:0.4667 70:0.4833 71:0.5167 72:0.5833 73:0.5667 74:0.6 75:0.6333 76:0.6667 77:0.7167 78:0.8167 79:0.8333 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:0.9667 101:0.9167 102:0.75 103:0.6833 104:0.6333 105:0.6 106:0.55 107:0.5167 108:0.4833 109:0.4667 110:0.4667 111:0.4167 112:0.4 113:0.4167 114:0.3833 115:0.35 116:0.35 117:0.35 118:0.35 119:0.3 120:0.3 121:0.3167 122:0.3 123:0.2333 124:0.2333 125:0.2333 126:0.2333 127:0.2333 128:0.2333 129:0.2333 130:0.2333 131:0.2333 132:0.2333 133:0.2333 134:0.2333 135:0.2333 136:0.2 137:0.2 138:0.2167 139:0.2167 140:0.2167 141:0.2 142:0.17547368 143:0.17547368 144:0.17547368 145:0.15789474 146:0.17547368 147:0.17547368 148:0.17547368 149:0.17547368 150:0.15789474 151:0.17547368 152:0.17547368 153:0.15789474 154:0.15789474 155:0.17547368 156:0.17547368 157:0.160747 158:0.17853278 159:0.17853278 160:0.17853278 161:0.17853278 162:0.4286051 163:0.4286051 164:0.4286051 165:0.4286051 166:0.41071218 167:0.41071218 168:0.41071218 169:0.41071218 170:0.41071218 171:0.41071218 172:0.41071218 173:0.41071218 174:0.41071218 175:0.41071218 176:0.41071218 177:0.41071218 178:0.4286051 179:0.62499866 180:0.62499866 181:0.60710574 182:0.60710574 183:0.60710574 184:0.60710574 185:0.60710574 186:0.60710574 187:0.60710574 188:0.62499866 189:0.62499866 190:0.62499866 191:0.62499866 192:0.62499866 193:0.62499866 194:0.64289158 195:0.6964632 196:0.6964632 197:0.6964632 198:0.51785542 199:0.51785542 200:0.39281926 201:0.39281926 202:0.39281926 203:0.39281926 204:0.39281926 205:0.39281926 206:0.39281926 207:0.39281926 208:0.39281926 209:0.39281926 210:0.1964257 211:0.1964257 212:0.1964257 213:0.1964257 214:0.1964257 215:0.1964257 216:0.1964257 217:0.1964257 218:0.1964257 219:0.1964257 220:0.1964257 221:0.25 222:0.25 223:0.25 224:0.25 225:0.25 226:0.25 227:0.25 228:0.2167 229:0.2167 230:0.2167 231:0.2167 232:0.2167 233:0.2167 234:0.2167 235:0.2167 236:0.2167 237:0.2167 238:0.2167 239:0.2167 240:0.2167 241:0.2167 242:0.2167 243:0.2167 244:0.2167 245:0.2167 246:0.2167 247:0.2167 248:0.2167 249:0.2167 250:0.2167 251:0.2167 252:0.2333 253:0.2333 254:0.3667 255:0.3833 256:0.4167 257:0.45 258:0.5667 259:0.6 260:0.65 261:0.6667 262:0.6667 263:0.6667 264:0.6667 265:1 266:1 267:1 268:0.6667 269:0.6333 270:0.6333 271:0.6333 272:0.6333 273:0.6333 274:0.6333 275:0.6333 276:0.6333 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:0.8667 285:0.85 286:0.8 287:0.75 288:0.6667 289:0.6667 290:0.6 291:0.5667 292:0.5667 293:0.5167 294:0.4833 295:0.4667 296:0.45 297:0.4333 298:0.4167 299:0.4 300:0.4 301:0.3833 302:0.3667 303:0.3833 304:0.2333 305:0.2333 306:0.2167 307:0.2167 308:0.2167 309:0.2167 310:0.2167 311:0.2167 312:0.2167 313:0.2167 314:0.2167 315:0.2167 316:0.2167 317:0.2167 318:0.2167 319:0.2167 320:0.2167 321:0.2167 322:0.2167 323:0.2167 324:0.2167 325:0.2167 326:0.2167 327:0.2167 328:0.2167 329:0.2167 330:0.2167 331:0.2167 332:0.2167 333:0.2167 334:0.25 335:0.2167 336:0.2167 337:0.2167 338:0.2167 339:0.2167 340:0.2167 341:0.2167 342:0.2167 343:0.2167 344:0.2167 345:0.2167 346:0.2167 347:0.2167 348:0.2167 349:0.2167 350:0.2167 351:0.2167 352:0.2167 353:0.2167 354:0.2167 355:0.2167 356:0.2167 357:0.2167 358:0.2167 359:0.2167 360:0.2167
1.942381595911747 1:0.15 2:0.15 3:0.15 4:0.15 5:0.15 6:0.15 7:0.15 8:0.15 9:0.15 10:0.15 11:0.15 12:0.15 13:0.15 14:0.15 15:0.15 16:0.15 17:0.15 18:0.15 19:0.15 20:0.15 21:0.15 22:0.15 23:0.15 24:0.15 25:0.15 26:0.15 27:0.15 28:0.15 29:0.15 30:0.15 31:0.15 32:0.15 33:0.15 34:0.1667 35:0.1667 36:0.1667 37:0.1667 38:0.1667 39:0.1667 40:0.1667 41:0.2833 42:0.2833 43:0.3 44:0.2833 45:0.2833 46:0.3 47:0.2833 48:0.2833 49:0.2833 50:0.3 51:0.3 52:0.3 53:0.3167 54:0.3167 55:0.3333 56:0.3333 57:0.35 58:0.35 59:0.3667 60:0.3667 61:0.3833 62:0.4 63:0.4 64:0.4167 65:0.4333 66:0.45 67:0.4667 68:0.4833 69:0.5167 70:0.5333 71:0.55 72:0.5833 73:0.5667 74:0.6167 75:0.6333 76:0.7667 77:0.7833 78:0.7833 79:0.85 80:0.9167 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:0.9833 100:0.9 101:0.8167 102:0.7667 103:0.6833 104:0.6333 105:0.5333 106:0.5333 107:0.5333 108:0.5333 109:0.4 110:0.3833 111:0.3667 112:0.3667 113:0.3667 114:0.3667 115:0.3667 116:0.3 117:0.2833 118:0.2833 119:0.2833 120:0.25 121:0.25 122:0.25 123:0.25 124:0.25 125:0.25 126:0.25 127:0.25 128:0.2333 129:0.2333 130:0.25 131:0.25 132:0.2333 133:0.2333 134:0.2333 135:0.25 136:0.2333 137:0.25 138:0.25 139:0.25 140:0.2333 141:0.25 142:0.21052632 143:0.19294737 144:0.19294737 145:0.19294737 146:0.21052632 147:0.21052632 148:0.21052632 149:0.19294737 150:0.21052632 151:0.21052632 152:0.21052632 153:0.47368421 154:0.43863158 155:0.43863158 156:0.43863158 157:0.4286051 158:0.41071218 159:0.41071218 160:0.41071218 161:0.41071218 162:0.41071218 163:0.41071218 164:0.41071218 165:0.41071218 166:0.41071218 167:0.41071218 168:0.41071218 169:0.41071218 170:0.44639088 171:0.48217672 172:0.67857028 173:0.67857028 174:0.67857028 175:0.67857028 176:0.60710574 177:0.60710574 178:0.60710574 179:0.60710574 180:0.60710574 181:0.60710574 182:0.60710574 183:0.60710574 184:0.62499866 185:0.62499866 186:0.62499866 187:0.58931996 188:0.4999625 189:0.4999625 190:0.51785542 191:0.4999625 192:0.37503348 193:0.37503348 194:0.35714056 195:0.35714056 196:0.35714056 197:0.35714056 198:0.35714056 199:0.35714056 200:0.35714056 201:0.35714056 202:0.35714056 203:0.35714056 204:0.35714056 205:0.35714056 206:0.35714056 207:0.37503348 208:0.17853278 209:0.17853278 210:0.17853278 211:0.17853278 212:0.17853278 213:0.17853278 214:0.17853278 215:0.17853278 216:0.17853278 217:0.17853278 218:0.17853278 219:0.17853278 220:0.17853278 221:0.2333 222:0.2333 223:0.2333 224:0.2333 225:0.2333 226:0.2333 227:0.2333 228:0.25 229:0.25 230:0.2667 231:0.25 232:0.25 233:0.25 234:0.25 235:0.25 236:0.25 237:0.25 238:0.25 239:0.25 240:0.25 241:0.25 242:0.25 243:0.25 244:0.25 245:0.25 246:0.25 247:0.25 248:0.25 249:0.25 250:0.25 251:0.2667 252:0.2667 253:0.25 254:0.25 255:0.2667 256:0.2833 257:0.5167 258:0.75 259:0.75 260:0.75 261:0.75 262:0.7667 263:0.7667 264:0.8833 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:0.9167 285:0.85 286:0.8 287:0.7 288:0.7 289:0.6833 290:0.6333 291:0.55 292:0.5333 293:0.5333 294:0.5333 295:0.4667 296:0.45 297:0.45 298:0.4167 299:0.4167 300:0.4167 301:0.3833 302:0.3667 303:0.3667 304:0.35 305:0.35 306:0.35 307:0.35 308:0.35 309:0.35 310:0.35 311:0.3 312:0.3 313:0.2833 314:0.2833 315:0.2833 316:0.2833 317:0.2833 318:0.2833 319:0.2833 320:0.2833 321:0.2833 322:0.2833 323:0.2833 324:0.2833 325:0.2833 326:0.2833 327:0.2833 328:0.25 329:0.25 330:0.25 331:0.2667 332:0.2667 333:0.25 334:0.2667 335:0.2667 336:0.25 337:0.25 338:0.2667 339:0.2667 340:0.25 341:0.2667 342:0.2667 343:0.2167 344:0.2167 345:0.2167 346:0.2167 347:0.2167 348:0.2167 349:0.2167 350:0.2167 351:0.2167 352:0.2167 353:0.2167 354:0.2167 355:0.2167 356:0.2167 357:0.2167 358:0.2167 359:0.15 360:0.15
2 1:0.2 2:0.2 3:0.2 4:0.1833 5:0.1833 6:0.1833 7:0.1833 8:0.1833 9:0.1833 10:0.1833 11:0.1833 12:0.1833 13:0.1833 14:0.1833 15:0.1833 16:0.1833 17:0.1833 18:0.1833 19:0.1833 20:0.1833 21:0.1833 22:0.1833 23:0.1833 24:0.1833 25:0.1833 26:0.1833 27:0.1833 28:0.1833 29:0.1833 30:0.2 31:0.2 32:0.2 33:0.2 34:0.2 35:0.2667 36:0.2667 37:0.2667 38:0.3167 39:0.3167 40:0.3167 41:0.3167 42:0.3167 43:0.3167 44:0.3167 45:0.3167 46:0.3167 47:0.3333 48:0.3333 49:0.3333 50:0.3333 51:0.3333 52:0.3333 53:0.3333 54:0.3833 55:0.3833 56:0.4 57:0.4 58:0.4167 59:0.4333 60:0.4333 61:0.45 62:0.4667 63:0.4833 64:0.5 65:0.5167 66:0.5333 67:0.55 68:0.5667 69:0.5667 70:0.5833 71:0.65 72:0.65 73:0.6667 74:0.7167 75:0.8 76:0.8 77:0.85 78:0.9167 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:0.8833 99:0.7667 100:0.6833 101:0.5167 102:0.5167 103:0.5167 104:0.5167 105:0.5167 106:0.5 107:0.5 108:0.5 109:0.5 110:0.2833 111:0.2833 112:0.25 113:0.25 114:0.2333 115:0.2167 116:0.2167 117:0.2167 118:0.2167 119:0.2333 120:0.2167 121:0.2167 122:0.2167 123:0.2167 124:0.2167 125:0.2167 126:0.2167 127:0.2167 128:0.2167 129:0.2 130:0.2 131:0.2 132:0.2167 133:0.2167 134:0.2 135:0.2 136:0.2167 137:0.2167 138:0.2 139:0.2 140:0.2 141:0.2167 142:0.17547368 143:0.15789474 144:0.15789474 145:0.17547368 146:0.15789474 147:0.15789474 148:0.15789474 149:0.15789474 150:0.17547368 151:0.17547368 152:0.17547368 153:0.42105263 154:0.40347368 155:0.40347368 156:0.40347368 157:0.37503348 158:0.37503348 159:0.37503348 160:0.37503348 161:0.37503348 162:0.37503348 163:0.37503348 164:0.37503348 165:0.37503348 166:0.37503348 167:0.37503348 168:0.37503348 169:0.37503348 170:0.37503348 171:0.39281926 172:0.58931996 173:0.60710574 174:0.58931996 175:0.58931996 176:0.57142704 177:0.57142704 178:0.57142704 179:0.57142704 180:0.57142704 181:0.57142704 182:0.57142704 183:0.57142704 184:0.58931996 185:0.58931996 186:0.58931996 187:0.53574834 188:0.55353412 189:0.53574834 190:0.58931996 191:0.55353412 192:0.24999732 193:0.24999732 194:0.24999732 195:0.24999732 196:0.24999732 197:0.24999732 198:0.24999732 199:0.24999732 200:0.24999732 201:0.24999732 202:0.14285408 203:0.14285408 204:0.14285408 205:0.14285408 206:0.14285408 207:0.14285408 208:0.14285408 209:0.14285408 210:0.14285408 211:0.14285408 212:0.14285408 213:0.14285408 214:0.14285408 215:0.14285408 216:0.14285408 217:0.14285408 218:0.14285408 219:0.14285408 220:0.14285408 221:0.2 222:0.2 223:0.2 224:0.2 225:0.2333 226:0.2333 227:0.2333 228:0.2333 229:0.2333 230:0.2333 231:0.2333 232:0.2333 233:0.25 234:0.25 235:0.25 236:0.25 237:0.25 238:0.25 239:0.25 240:0.25 241:0.25 242:0.25 243:0.25 244:0.25 245:0.25 246:0.25 247:0.25 248:0.25 249:0.25 250:0.25 251:0.25 252:0.25 253:0.25 254:0.25 255:0.25 256:0.25 257:0.25 258:0.25 259:0.25 260:0.25 261:0.25 262:0.2667 263:0.7667 264:0.75 265:0.75 266:0.85 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:0.9333 287:0.8833 288:0.8167 289:0.7833 290:0.7333 291:0.7 292:0.6667 293:0.65 294:0.5667 295:0.5667 296:0.5667 297:0.55 298:0.5667 299:0.4833 300:0.4833 301:0.4833 302:0.4333 303:0.4333 304:0.4167 305:0.4 306:0.4 307:0.3833 308:0.3833 309:0.3667 310:0.3667 311:0.3667 312:0.3667 313:0.3833 314:0.3667 315:0.3667 316:0.3167 317:0.3167 318:0.3167 319:0.3167 320:0.3 321:0.3 322:0.3167 323:0.3 324:0.3 325:0.3167 326:0.3 327:0.3 328:0.3167 329:0.3 330:0.3 331:0.2833 332:0.2833 333:0.2833 334:0.3 335:0.2833 336:0.2833 337:0.3 338:0.2833 339:0.2833 340:0.3 341:0.2833 342:0.2833 343:0.2833 344:0.2833 345:0.25 346:0.25 347:0.25 348:0.25 349:0.25 350:0.25 351:0.25 352:0.25 353:0.25 354:0.25 355:0.25 356:0.25 357:0.25 358:0.25 359:0.2 360:0.2
0.02059784968635983 1:1 2:1 3:1 4:1 5:1 6:1 7:1 8:1 9:1 10:1 11:0.5167 12:0.4833 13:0.4333 14:0.4167 15:0.4167 16:0.4167 17:0.4167 18:0.4167 19:0.4167 20:0.4167 21:0.4167 22:0.4167 23:0.4167 24:0.4167 25:0.4167 26:0.4 27:0.45 28:0.45 29:0.45 30:0.4667 31:0.4667 32:0.4667 33:0.4667 34:0.4833 35:0.4833 36:0.5 37:0.5167 38:0.5333 39:0.5 40:0.4667 41:0.45 42:0.45 43:0.4667 44:0.45 45:0.4667 46:0.45 47:0.45 48:0.3333 49:0.3333 50:0.3333 51:0.3333 52:0.3333 53:0.3333 54:0.3333 55:0.3333 56:0.3333 57:0.3333 58:0.3333 59:0.3333 60:0.3333 61:0.3333 62:0.3333 63:0.3333 64:0.3333 65:0.3333 66:0.3333 67:0.35 68:0.3667 69:0.3833 70:0.45 71:0.45 72:0.45 73:0.45 74:0.45 75:0.45 76:0.4833 77:0.6 78:0.6 79:0.6 80:0.75 81:0.75 82:0.8 83:0.8167 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:0.85 108:0.7167 109:0.5667 110:0.5667 111:0.5333 112:0.4833 113:0.4667 114:0.45 115:0.4333 116:0.4333 117:0.4333 118:0.4333 119:0.4333 120:0.4333 121:0.4167 122:0.4 123:0.4 124:0.3833 125:0.3833 126:0.3833 127:0.3833 128:0.3833 129:0.2833 130:0.2833 131:0.2833 132:0.2667 133:0.2667 134:0.2667 135:0.25 136:0.25 137:0.25 138:0.25 139:0.25 140:0.2333 141:0.2333 142:0.19294737 143:0.19294737 144:0.15789474 145:0.15789474 146:0.15789474 147:0.15789474 148:0.15789474 149:0.15789474 150:0.15789474 151:0.15789474 152:0.15789474 153:0.14031579 154:0.14031579 155:0.14031579 156:0.14031579 157:0.12496116 158:0.12496116 159:0.12496116 160:0.12496116 161:0.12496116 162:0.12496116 163:0.12496116 164:0.12496116 165:0.12496116 166:0.12496116 167:0.12496116 168:0.12496116 169:0.12496116 170:0.12496116 171:0.12496116 172:0.12496116 173:0.12496116 174:0.12496116 175:0.12496116 176:0.12496116 177:0.12496116 178:0.12496116 179:0.12496116 180:0.12496116 181:0.12496116 182:0.12496116 183:0.12496116 184:0.12496116 185:0.12496116 186:0.12496116 187:0.12496116 188:0.12496116 189:0.12496116 190:0.12496116 191:0.12496116 192:0.12496116 193:0.12496116 194:0.12496116 195:0.12496116 196:0.12496116 197:0.12496116 198:0.14285408 199:0.14285408 200:0.14285408 201:0.14285408 202:0.14285408 203:0.12496116 204:0.14285408 205:0.14285408 206:0.14285408 207:0.14285408 208:0.12496116 209:0.12496116 210:0.14285408 211:0.14285408 212:0.14285408 213:0.14285408 214:0.14285408 215:0.14285408 216:0.14285408 217:0.14285408 218:0.14285408 219:0.160747 220:0.160747 221:0.2167 222:0.2167 223:0.2167 224:0.2167 225:0.2333 226:0.2333 227:0.2333 228:0.2333 229:0.2333 230:0.25 231:0.25 232:0.25 233:0.2667 234:0.2667 235:0.2667 236:0.2833 237:0.2833 238:0.3333 239:0.3333 240:0.3333 241:0.3333 242:0.3333 243:0.3333 244:0.3333 245:0.3333 246:0.3333 247:0.35 248:0.4 249:0.3833 250:0.4 251:0.4167 252:0.4333 253:0.4833 254:0.4833 255:0.5167 256:0.55 257:0.55 258:0.55 259:0.6333 260:0.65 261:0.7167 262:0.8 263:0.9333 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:0.9167 284:0.85 285:0.7833 286:0.6667 287:0.6333 288:0.6 289:0.5833 290:0.5833 291:0.55 292:0.5333 293:0.5333 294:0.5333 295:0.3833 296:0.3667 297:0.3667 298:0.35 299:0.3667 300:0.35 301:0.35 302:0.3667 303:0.35 304:0.3667 305:0.3667 306:0.35 307:0.3667 308:0.35 309:0.35 310:0.3667 311:0.3667 312:0.5667 313:0.7333 314:0.7333 315:0.7333 316:0.7167 317:0.7333 318:0.75 319:0.6667 320:0.65 321:0.6667 322:0.6667 323:0.65 324:0.6167 325:0.55 326:0.55 327:0.5167 328:0.5167 329:0.5167 330:0.5 331:0.5 332:0.5 333:0.5 334:0.4833 335:0.4833 336:0.4833 337:0.4833 338:0.4833 339:0.4833 340:0.4833 341:0.4833 342:0.4833 343:0.4833 344:0.4833 345:1 346:1 347:1 348:1 349:1 350:1 351:1 352:1 353:1 354:1 355:1 356:1 357:1 358:1 359:1 360:1
0.3603063780745222 1:0.1833 2:0.1833 3:0.1833 4:0.1833 5:0.1833 6:0.1833 7:0.1833 8:0.1833 9:0.1833 10:0.1833 11:0.1833 12:0.1833 13:0.1833 14:0.1833 15:0.1833 16:0.1833 17:0.1833 18:0.1833 19:0.1833 20:0.1833 21:0.1833 22:0.1833 23:0.1833 24:0.1833 25:0.1833 26:0.1833 27:0.1833 28:0.1833 29:0.1833 30:0.2 31:0.2 32:0.2 33:0.2 34:0.2 35:0.2 36:0.2 37:0.2 38:0.2 39:0.2167 40:0.2167 41:0.2167 42:0.2167 43:0.2167 44:0.2167 45:0.2333 46:0.2333 47:0.2333 48:0.2333 49:0.2333 50:0.25 51:0.25 52:0.25 53:0.2667 54:0.2667 55:0.2667 56:0.2833 57:0.2833 58:0.3 59:0.3 60:0.3 61:0.3167 62:0.3333 63:0.3333 64:0.35 65:0.3667 66:0.3667 67:0.4167 68:0.4 69:0.4167 70:0.4 71:0.4833 72:0.4833 73:0.5833 74:0.5833 75:0.5833 76:0.5833 77:0.5833 78:0.5833 79:0.7 80:0.7167 81:0.7167 82:0.9333 83:0.9333 84:0.9333 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:0.9833 103:0.85 104:0.85 105:0.7167 106:0.6667 107:0.65 108:0.6 109:0.5833 110:0.5833 111:0.6 112:0.5833 113:0.5833 114:0.4833 115:0.4833 116:0.45 117:0.45 118:0.45 119:0.45 120:0.45 121:0.45 122:0.45 123:0.45 124:0.45 125:0.45 126:0.45 127:0.4667 128:0.5167 129:0.9833 130:0.9833 131:0.6667 132:0.65 133:0.6333 134:0.6333 135:0.6167 136:0.6 137:0.6 138:0.6 139:0.6 140:0.6 141:0.5833 142:0.56136842 143:0.54389474 144:0.54389474 145:0.54389474 146:0.54389474 147:0.54389474 148:0.54389474 149:0.54389474 150:0.54389474 151:0.54389474 152:0.54389474 153:0.54389474 154:0.54389474 155:0.54389474 156:0.54389474 157:0.57142704 158:0.58931996 159:0.62499866 160:0.64289158 161:0.67857028 162:0.7321419 163:0.7321419 164:0.71424898 165:0.71424898 166:0.71424898 167:0.71424898 168:0.71424898 169:0.71424898 170:0.71424898 171:0.71424898 172:0.71424898 173:0.75003482 174:1 175:1 176:1 177:1 178:1 179:1 180:1 181:1 182:1 183:1 184:1 185:0.62499866 186:0.62499866 187:0.62499866 188:0.44639088 189:0.4642838 190:0.44639088 191:0.44639088 192:0.44639088 193:0.44639088 194:0.44639088 195:0.44639088 196:0.44639088 197:0.44639088 198:0.44639088 199:0.4286051 200:0.4286051 201:0.4286051 202:0.4286051 203:0.4286051 204:0.4286051 205:0.4286051 206:0.4286051 207:0.4286051 208:0.17853278 209:0.17853278 210:0.17853278 211:0.17853278 212:0.17853278 213:0.17853278 214:0.17853278 215:0.17853278 216:0.17853278 217:0.17853278 218:0.17853278 219:0.17853278 220:0.17853278 221:0.2333 222:0.2333 223:0.2333 224:0.2333 225:0.2333 226:0.2333 227:0.2333 228:0.2667 229:0.2667 230:0.2667 231:0.2667 232:0.2667 233:0.2667 234:0.2667 235:0.2667 236:0.2667 237:0.2667 238:0.2667 239:0.2667 240:0.2833 241:0.3167 242:0.3 243:0.3 244:0.3167 245:0.3167 246:0.3333 247:0.35 248:0.3667 249:0.3833 250:0.4 251:0.4333 252:0.4333 253:0.7 254:0.7 255:0.7 256:0.7 257:0.7 258:0.7 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:0.6333 288:0.6 289:0.5833 290:0.5833 291:0.6 292:0.5833 293:0.5833 294:0.45 295:0.4333 296:0.4167 297:0.4 298:0.4 299:0.3667 300:0.3667 301:0.35 302:0.3333 303:0.3333 304:0.3167 305:0.3167 306:0.3 307:0.3 308:0.2667 309:0.2667 310:0.25 311:0.25 312:0.25 313:0.25 314:0.25 315:0.25 316:0.25 317:0.25 318:0.25 319:0.25 320:0.2333 321:0.2333 322:0.2333 323:0.2333 324:0.2 325:0.2 326:0.2 327:0.2 328:0.2 329:0.2 330:0.2 331:0.2 332:0.2 333:0.1833 334:0.1833 335:0.1833 336:0.1833 337:0.1833 338:0.1833 339:0.1833 340:0.1833 341:0.1833 342:0.1833 343:0.1833 344:0.1833 345:0.1833 346:0.1833 347:0.1833 348:0.1833 349:0.1833 350:0.1833 351:0.1833 352:0.1833 353:0.1833 354:0.1833 355:0.1833 356:0.1833 357:0.1833 358:0.1833 359:0.1833 360:0.1833
0.346971872463373 1:1 2:1 3:1 4:1 5:1 6:1 7:1 8:1 9:1 10:1 11:1 12:1 13:1 14:1 15:1 16:1 17:1 18:1 19:1 20:1 21:1 22:1 23:0.7 24:0.7 25:0.7 26:0.7 27:0.7 28:0.7 29:0.7 30:0.7 31:0.8667 32:0.8833 33:0.8833 34:0.8667 35:0.8833 36:0.4167 37:0.4167 38:0.4167 39:0.4167 40:0.4167 41:0.4167 42:0.4167 43:0.4167 44:0.4167 45:0.4167 46:0.4167 47:0.4167 48:0.4167 49:0.4167 50:0.4167 51:0.4833 52:0.4833 53:0.4833 54:0.5667 55:0.5667 56:0.5667 57:0.5667 58:0.5667 59:0.6667 60:0.6667 61:0.6833 62:0.7667 63:0.75 64:0.75 65:0.7667 66:0.7667 67:0.7667 68:0.7833 69:0.7833 70:0.9 71:0.9833 72:0.9833 73:1 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:1 118:0.9833 119:0.9833 120:0.8833 121:0.7833 122:0.7833 123:0.7833 124:0.7833 125:0.7833 126:0.6833 127:0.6667 128:0.65 129:0.6333 130:0.6333 131:0.6333 132:0.6333 133:0.6333 134:0.55 135:0.55 136:0.5333 137:0.5333 138:0.5333 139:0.5333 140:0.5333 141:0.5167 142:0.50873684 143:0.47368421 144:0.49126316 145:0.49126316 146:0.49126316 147:0.49126316 148:0.47368421 149:0.43863158 150:0.43863158 151:0.43863158 152:0.43863158 153:0.43863158 154:0.43863158 155:0.43863158 156:0.43863158 157:0.4286051 158:0.4286051 159:0.4286051 160:0.4286051 161:0.4286051 162:0.4286051 163:0.4286051 164:0.4286051 165:0.4286051 166:0.41071218 167:0.41071218 168:0.41071218 169:0.41071218 170:0.4286051 171:0.41071218 172:0.39281926 173:0.39281926 174:0.37503348 175:0.37503348 176:0.37503348 177:0.37503348 178:0.37503348 179:0.37503348 180:0.35714056 181:0.35714056 182:0.35714056 183:0.35714056 184:0.35714056 185:0.35714056 186:0.35714056 187:0.35714056 188:0.32146186 189:0.33924764 190:0.32146186 191:0.33924764 192:0.35714056 193:0.33924764 194:0.33924764 195:0.32146186 196:0.33924764 197:0.37503348 198:0.32146186 199:0.37503348 200:0.37503348 201:0.37503348 202:0.37503348 203:0.37503348 204:0.37503348 205:0.37503348 206:0.35714056 207:0.37503348 208:0.37503348 209:0.37503348 210:0.37503348 211:0.37503348 212:0.39281926 213:0.39281926 214:0.39281926 215:0.39281926 216:0.39281926 217:0.39281926 218:0.44639088 219:0.44639088 220:0.44639088 221:0.5 222:1 223:1 224:0.9 225:0.8833 226:0.8833 227:0.8833 228:0.8833 229:0.8833 230:0.65 231:0.6667 232:0.6667 233:0.65 234:0.6667 235:0.6667 236:0.65 237:0.6667 238:0.7333 239:0.7333 240:0.7333 241:0.7333 242:0.7333 243:1 244:1 245:1 246:1 247:1 248:1 249:1 250:1 251:1 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:0.85 290:0.85 291:0.8333 292:0.8333 293:0.8333 294:0.7833 295:0.7833 296:0.7833 297:0.7833 298:0.7833 299:0.7833 300:0.7167 301:0.6833 302:0.6833 303:0.6833 304:0.6833 305:0.6833 306:0.6833 307:0.6833 308:0.6833 309:0.6833 310:0.6167 311:0.5167 312:0.4667 313:0.4667 314:0.4667 315:0.4667 316:0.4667 317:0.4667 318:0.4667 319:0.4667 320:0.4667 321:0.4667 322:0.4667 323:0.4667 324:0.4667 325:0.4667 326:0.4667 327:0.4333 328:0.4333 329:0.4333 330:0.4333 331:0.4333 332:0.3667 333:0.3667 334:0.3667 335:0.3667 336:0.3667 337:0.3667 338:0.3667 339:0.3667 340:0.3667 341:0.3667 342:0.3667 343:0.3667 344:0.3667 345:0.3667 346:0.3667 347:0.3667 348:0.6667 349:0.6667 350:0.6667 351:0.6667 352:0.6667 353:0.6667 354:0.6667 355:0.85 356:0.85 357:0.85 358:1 359:1 360:1
0.024445814678122 1:1 2:1 3:1 4:1 5:1 6:1 7:1 8:1 9:1 10:1 11:1 12:1 13:1 14:1 15:1 16:0.6833 17:0.6833 18:0.6833 19:0.6833 20:0.6833 21:0.6833 22:0.6833 23:0.4167 24:0.4167 25:0.4167 26:0.4167 27:0.4 28:0.4167 29:0.4 30:0.4167 31:0.4167 32:0.4167 33:0.4167 34:0.4 35:0.4167 36:0.4 37:0.4167 38:0.4167 39:0.4167 40:0.5 41:0.5 42:0.5 43:0.5 44:0.5 45:0.5 46:0.5 47:0.5 48:0.5 49:0.5167 50:0.5167 51:0.5167 52:0.6167 53:0.6 54:0.6167 55:0.6167 56:0.6333 57:0.7 58:0.7 59:0.7 60:0.7 61:0.7 62:0.7 63:0.7 64:0.7167 65:0.7 66:0.7333 67:0.8333 68:0.9167 69:0.85 70:0.85 71:0.85 72:0.85 73:0.9333 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:0.8833 102:0.8667 103:0.8667 104:0.8667 105:0.8667 106:0.8667 107:0.8667 108:0.8667 109:0.8667 110:1 111:1 112:1 113:1 114:1 115:0.9667 116:0.9667 117:0.95 118:0.95 119:0.9 120:0.9 121:0.8167 122:0.7 123:0.7 124:0.7 125:0.7 126:0.7 127:0.7 128:0.7 129:0.7 130:0.6833 131:0.6833 132:0.6 133:0.5667 134:0.55 135:0.5667 136:0.5667 137:0.5667 138:0.5667 139:0.4833 140:0.4833 141:0.4667 142:0.43863158 143:0.43863158 144:0.43863158 145:0.43863158 146:0.43863158 147:0.43863158 148:0.43863158 149:0.42105263 150:0.42105263 151:0.42105263 152:0.42105263 153:0.42105263 154:0.42105263 155:0.42105263 156:0.42105263 157:0.37503348 158:0.37503348 159:0.37503348 160:0.37503348 161:0.37503348 162:0.37503348 163:0.37503348 164:0.37503348 165:0.37503348 166:0.37503348 167:0.37503348 168:0.37503348 169:0.37503348 170:0.37503348 171:0.37503348 172:0.37503348 173:0.37503348 174:0.37503348 175:0.37503348 176:0.39281926 177:0.39281926 178:0.39281926 179:0.39281926 180:0.39281926 181:0.39281926 182:0.39281926 183:0.35714056 184:0.35714056 185:0.35714056 186:0.35714056 187:0.35714056 188:0.35714056 189:0.35714056 190:0.35714056 191:0.35714056 192:0.35714056 193:0.35714056 194:0.35714056 195:0.35714056 196:0.35714056 197:0.35714056 198:0.35714056 199:0.35714056 200:0.35714056 201:0.35714056 202:0.35714056 203:0.35714056 204:0.35714056 205:0.35714056 206:0.35714056 207:0.39281926 208:0.39281926 209:0.44639088 210:0.44639088 211:0.44639088 212:0.44639088 213:0.44639088 214:0.44639088 215:0.44639088 216:0.44639088 217:0.48217672 218:0.48217672 219:0.48217672 220:0.48217672 221:0.5167 222:0.5167 223:0.5167 224:0.5167 225:0.5167 226:0.5167 227:0.5167 228:0.5167 229:0.5167 230:0.5167 231:0.5333 232:0.55 233:0.6667 234:0.65 235:0.6667 236:0.7167 237:0.7167 238:0.7167 239:0.7167 240:0.7167 241:0.7167 242:0.7167 243:1 244:1 245:1 246:1 247:1 248:1 249:1 250:1 251:1 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:0.8833 290:0.8833 291:0.8667 292:0.8667 293:0.8667 294:0.8667 295:0.8667 296:0.8833 297:0.7333 298:0.7833 299:0.75 300:0.75 301:0.75 302:0.75 303:0.75 304:0.7667 305:0.7667 306:0.7667 307:0.55 308:0.55 309:0.5333 310:0.5333 311:0.5333 312:0.5333 313:0.5333 314:0.5333 315:0.5333 316:0.4333 317:0.5333 318:0.45 319:0.45 320:0.45 321:0.45 322:0.45 323:0.45 324:0.45 325:0.45 326:0.5167 327:0.6167 328:0.5167 329:0.7833 330:0.5 331:0.7833 332:0.8 333:0.8 334:0.7833 335:0.95 336:0.95 337:0.9167 338:0.9167 339:0.8667 340:0.8667 341:0.7 342:0.7 343:0.7 344:0.7 345:0.7 346:0.7 347:0.7 348:0.7 349:0.9167 350:0.9167 351:0.9167 352:1 353:1 354:1 355:1 356:1 357:1 358:1 359:1 360:1
1.284492163688887 1:0.9667 2:0.9667 3:0.9667 4:0.9667 5:0.9667 6:0.9667 7:0.9667 8:0.9667 9:0.9667 10:0.9667 11:0.9833 12:0.9667 13:0.9667 14:0.9833 15:0.9833 16:0.35 17:0.3333 18:0.35 19:0.35 20:0.3333 21:0.35 22:0.3333 23:0.35 24:0.35 25:0.3333 26:0.35 27:0.35 28:0.3333 29:0.35 30:0.35 31:0.35 32:0.35 33:0.35 34:0.35 35:0.5 36:0.5 37:0.5167 38:0.5 39:0.5 40:0.5 41:0.5 42:0.5 43:0.5 44:0.5 45:0.5 46:0.5 47:0.5 48:0.5 49:0.5167 50:0.5167 51:0.5667 52:0.5333 53:0.5667 54:0.5333 55:0.5333 56:0.5333 57:0.5667 58:0.5667 59:1 60:0.6 61:0.9833 62:0.9667 63:0.9667 64:0.95 65:0.95 66:0.9333 67:0.95 68:0.95 69:0.95 70:0.95 71:1 72:0.6333 73:0.6333 74:0.6333 75:0.6333 76:0.6333 77:0.6333 78:0.6333 79:0.6167 80:0.6333 81:0.6167 82:0.6167 83:0.6333 84:0.6167 85:0.6167 86:0.75 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:0.6667 115:0.6333 116:0.6167 117:0.5833 118:0.5833 119:0.5833 120:0.5833 121:0.5833 122:0.5833 123:0.5833 124:0.5833 125:0.5833 126:0.5833 127:0.6 128:0.6 129:0.6167 130:0.6167 131:0.6 132:0.6 133:0.5333 134:0.5333 135:0.4667 136:0.4667 137:0.45 138:0.45 139:0.4667 140:0.45 141:0.4667 142:0.42105263 143:0.43863158 144:0.42105263 145:0.43863158 146:0.42105263 147:0.43863158 148:0.43863158 149:0.43863158 150:0.43863158 151:0.43863158 152:0.45610526 153:0.43863158 154:0.45610526 155:0.43863158 156:0.43863158 157:0.4286051 158:0.4286051 159:0.4286051 160:0.4286051 161:0.4286051 162:0.4286051 163:0.4286051 164:0.33924764 165:0.33924764 166:0.35714056 167:0.33924764 168:0.35714056 169:0.35714056 170:0.33924764 171:0.35714056 172:0.30356894 173:0.30356894 174:0.30356894 175:0.30356894 176:0.30356894 177:0.30356894 178:0.30356894 179:0.30356894 180:0.30356894 181:0.30356894 182:0.30356894 183:0.30356894 184:0.30356894 185:0.30356894 186:0.30356894 187:0.30356894 188:0.32146186 189:0.32146186 190:0.33924764 191:0.33924764 192:0.33924764 193:0.33924764 194:0.33924764 195:0.32146186 196:0.32146186 197:0.32146186 198:0.32146186 199:0.32146186 200:0.33924764 201:0.32146186 202:0.33924764 203:0.32146186 204:0.32146186 205:0.32146186 206:0.32146186 207:0.32146186 208:0.33924764 209:0.35714056 210:0.35714056 211:0.37503348 212:0.44639088 213:0.44639088 214:0.33924764 215:0.32146186 216:0.32146186 217:0.30356894 218:0.30356894 219:0.30356894 220:0.30356894 221:0.35 222:0.35 223:0.35 224:0.35 225:0.35 226:0.35 227:0.35 228:0.35 229:0.35 230:0.35 231:0.35 232:0.3667 233:0.3667 234:0.3833 235:0.3833 236:0.4 237:0.4 238:0.4167 239:0.4333 240:0.4333 241:0.45 242:0.7 243:0.7 244:0.7167 245:0.7 246:0.7667 247:0.8833 248:1 249:1 250:1 251:1 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:1 296:0.9833 297:0.7833 298:0.7833 299:0.7667 300:0.7333 301:0.7333 302:0.7333 303:0.7333 304:0.7333 305:0.7333 306:0.6833 307:0.6833 308:0.6833 309:0.6833 310:0.65 311:0.6333 312:0.55 313:0.5333 314:0.5333 315:0.5333 316:0.5333 317:0.5333 318:0.5333 319:0.5333 320:0.5333 321:0.5333 322:0.5667 323:0.5667 324:0.5667 325:0.5667 326:0.7833 327:0.4333 328:0.4333 329:0.4333 330:0.4333 331:0.4333 332:0.4333 333:0.4333 334:0.4333 335:0.4333 336:0.4333 337:0.4333 338:0.45 339:0.45 340:0.45 341:0.45 342:0.45 343:0.45 344:0.45 345:0.45 346:0.7 347:0.7 348:0.7 349:0.7 350:0.7 351:0.7833 352:0.7833 353:0.7833 354:1 355:1 356:1 357:1 358:1 359:0.9833 360:0.9667
0.02246875610680569 1:0.95 2:0.95 3:0.95 4:0.95 5:0.95 6:0.95 7:0.95 8:0.95 9:0.95 10:0.95 11:0.95 12:0.95 13:0.95 14:0.9333 15:0.9333 16:0.8 17:0.7833 18:0.7833 19:0.7833 20:0.7833 21:0.7833 22:0.7167 23:0.7167 24:0.7167 25:0.7167 26:0.7167 27:0.7167 28:0.7167 29:0.55 30:0.5 31:0.4833 32:0.4833 33:0.4833 34:0.4833 35:0.4833 36:0.4833 37:0.4833 38:0.4833 39:0.4833 40:0.4833 41:0.4833 42:0.4833 43:0.4833 44:0.4833 45:0.4833 46:0.4833 47:0.4833 48:0.4833 49:0.4833 50:0.5 51:1 52:1 53:1 54:1 55:1 56:1 57:1 58:1 59:1 60:1 61:0.95 62:0.9333 63:0.9333 64:0.9167 65:0.9167 66:0.9167 67:0.9167 68:0.9167 69:0.9167 70:0.9167 71:0.9167 72:1 73:0.65 74:0.65 75:0.65 76:0.65 77:0.65 78:0.65 79:0.6333 80:0.6333 81:0.6333 82:0.6333 83:0.6333 84:0.6333 85:0.6333 86:0.6333 87:0.6333 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:0.65 117:0.6333 118:0.6 119:0.5833 120:0.5667 121:0.5833 122:0.5667 123:0.5667 124:0.5667 125:0.5667 126:0.5667 127:0.5667 128:0.5667 129:0.5667 130:0.5833 131:0.5833 132:0.6 133:0.6 134:0.6 135:0.6 136:0.6 137:0.5 138:0.5 139:0.5 140:0.5 141:0.4667 142:0.43863158 143:0.43863158 144:0.43863158 145:0.43863158 146:0.43863158 147:0.43863158 148:0.43863158 149:0.43863158 150:0.43863158 151:0.43863158 152:0.43863158 153:0.45610526 154:0.45610526 155:0.45610526 156:0.45610526 157:0.44639088 158:0.44639088 159:0.44639088 160:0.44639088 161:0.4286051 162:0.4286051 163:0.4286051 164:0.4286051 165:0.4286051 166:0.4286051 167:0.4286051 168:0.4286051 169:0.4286051 170:0.66067736 171:0.44639088 172:0.44639088 173:0.44639088 174:0.44639088 175:0.44639088 176:0.44639088 177:0.44639088 178:0.32146186 179:0.32146186 180:0.32146186 181:0.32146186 182:0.32146186 183:0.32146186 184:0.32146186 185:0.32146186 186:0.32146186 187:0.32146186 188:0.32146186 189:0.32146186 190:0.32146186 191:0.32146186 192:0.32146186 193:0.35714056 194:0.35714056 195:0.33924764 196:0.33924764 197:0.33924764 198:0.33924764 199:0.33924764 200:0.33924764 201:0.33924764 202:0.33924764 203:0.33924764 204:0.33924764 205:0.33924764 206:0.33924764 207:0.35714056 208:0.35714056 209:0.35714056 210:0.35714056 211:0.37503348 212:0.39281926 213:0.41071218 214:0.48217672 215:0.48217672 216:0.37503348 217:0.33924764 218:0.33924764 219:0.32146186 220:0.32146186 221:0.3667 222:0.3667 223:0.3833 224:0.3667 225:0.3667 226:0.3667 227:0.3667 228:0.3833 229:0.3667 230:0.3667 231:0.3833 232:0.3833 233:0.4 234:0.4 235:0.4167 236:0.4167 237:0.4333 238:0.45 239:0.45 240:0.4667 241:0.7167 242:0.7167 243:0.7333 244:0.7333 245:0.7333 246:0.7667 247:0.9167 248:1 249:1 250:1 251:1 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:1 296:1 297:0.7667 298:0.75 299:0.7333 300:0.7333 301:0.7333 302:0.7333 303:0.7333 304:0.7333 305:0.7 306:0.7 307:0.7 308:0.65 309:0.7 310:0.55 311:0.4833 312:0.55 313:0.4833 314:0.55 315:0.4833 316:0.4833 317:0.4833 318:0.4833 319:0.4833 320:0.5667 321:0.5667 322:0.5667 323:0.8167 324:0.8167 325:0.8167 326:0.4833 327:0.4833 328:0.4833 329:0.4833 330:0.4833 331:0.45 332:0.4333 333:0.4333 334:0.4333 335:0.4333 336:0.4333 337:0.4333 338:0.4333 339:0.4333 340:0.4333 341:0.4333 342:0.4333 343:0.45 344:0.7 345:0.7 346:0.7 347:0.7 348:0.7 349:0.7833 350:0.7833 351:1 352:1 353:1 354:1 355:1 356:1 357:0.9667 358:0.95 359:0.95 360:0.95
0.5467183656136703 1:1 2:1 3:1 4:1 5:1 6:1 7:1 8:1 9:1 10:1 11:1 12:1 13:1 14:0.8667 15:0.85 16:0.85 17:0.85 18:0.85 19:0.8333 20:0.8167 21:0.75 22:0.8167 23:0.7833 24:0.7667 25:0.7667 26:0.5667 27:0.55 28:0.55 29:0.55 30:0.5333 31:0.5333 32:0.5333 33:0.5167 34:0.5167 35:0.5167 36:0.5167 37:0.5167 38:0.5167 39:0.5167 40:0.5167 41:0.5167 42:0.5333 43:0.5333 44:0.55 45:0.55 46:0.5667 47:0.5667 48:0.5833 49:0.5667 50:0.5667 51:0.5833 52:0.5833 53:0.5833 54:0.6 55:1 56:1 57:1 58:0.9667 59:0.9667 60:0.95 61:0.95 62:0.9333 63:0.9333 64:0.9333 65:0.9333 66:0.9333 67:0.9333 68:1 69:1 70:1 71:1 72:0.7667 73:0.7667 74:0.75 75:0.75 76:0.75 77:0.75 78:0.75 79:0.75 80:0.75 81:0.75 82:0.75 83:0.7667 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:0.6 112:0.5833 113:0.55 114:0.5333 115:0.5333 116:0.5333 117:0.5167 118:0.5167 119:0.5167 120:0.5167 121:0.5167 122:0.5167 123:0.5167 124:0.5167 125:0.5167 126:0.5333 127:0.5333 128:0.5333 129:0.5333 130:0.5333 131:0.5333 132:0.4667 133:0.4667 134:0.4 135:0.4 136:0.4 137:0.4 138:0.4 139:0.4 140:0.4 141:0.4 142:0.36842105 143:0.36842105 144:0.36842105 145:0.36842105 146:0.36842105 147:0.36842105 148:0.386 149:0.386 150:0.386 151:0.386 152:0.386 153:0.386 154:0.386 155:0.386 156:0.386 157:0.35714056 158:0.35714056 159:0.35714056 160:0.35714056 161:0.35714056 162:0.35714056 163:0.35714056 164:0.35714056 165:0.35714056 166:0.35714056 167:0.35714056 168:0.35714056 169:0.66067736 170:0.58931996 171:0.57142704 172:0.57142704 173:0.55353412 174:0.55353412 175:0.55353412 176:0.55353412 177:0.24999732 178:0.24999732 179:0.24999732 180:0.24999732 181:0.24999732 182:0.24999732 183:0.24999732 184:0.24999732 185:0.24999732 186:0.24999732 187:0.24999732 188:0.24999732 189:0.24999732 190:0.24999732 191:0.24999732 192:0.24999732 193:0.24999732 194:0.24999732 195:0.24999732 196:0.24999732 197:0.24999732 198:0.26789024 199:0.28567602 200:0.28567602 201:0.28567602 202:0.28567602 203:0.28567602 204:0.28567602 205:0.28567602 206:0.26789024 207:0.28567602 208:0.28567602 209:0.26789024 210:0.28567602 211:0.28567602 212:0.28567602 213:0.28567602 214:0.28567602 215:0.28567602 216:0.30356894 217:0.30356894 218:0.30356894 219:0.30356894 220:0.41071218 221:0.4667 222:0.45 223:0.3833 224:0.3833 225:0.35 226:0.35 227:0.35 228:0.3333 229:0.3333 230:0.3333 231:0.3333 232:0.35 233:0.3333 234:0.3333 235:0.35 236:0.3333 237:0.3333 238:0.3333 239:0.3333 240:0.3333 241:0.35 242:0.3667 243:0.3667 244:0.3833 245:0.4 246:0.4167 247:0.4333 248:0.45 249:0.7167 250:0.7167 251:0.75 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:1 296:1 297:1 298:1 299:1 300:0.95 301:0.8167 302:0.8 303:0.7833 304:0.7833 305:0.7833 306:0.7 307:0.7 308:0.7 309:0.7 310:0.7 311:0.7 312:0.7167 313:0.7167 314:0.6 315:0.6 316:0.6 317:0.6 318:0.6 319:0.6 320:0.6 321:0.6 322:0.6 323:0.6333 324:0.6333 325:0.6333 326:0.85 327:0.85 328:0.85 329:0.55 330:0.55 331:0.5333 332:0.55 333:0.5333 334:0.55 335:0.55 336:0.55 337:0.55 338:0.5333 339:0.7833 340:0.7667 341:0.7667 342:0.7667 343:0.7667 344:0.75 345:0.7667 346:0.7667 347:0.7667 348:0.7667 349:0.75 350:0.8333 351:0.8333 352:0.9 353:1 354:1 355:1 356:1 357:1 358:1 359:1 360:1
1.140237959663935 1:0.8667 2:0.8667 3:0.8667 4:0.8667 5:0.8667 6:0.8667 7:0.8667 8:0.8833 9:0.8833 10:0.8667 11:0.8667 12:0.8833 13:0.8833 14:0.8833 15:0.8833 16:0.8833 17:0.8833 18:0.8167 19:0.7333 20:0.7167 21:0.7 22:0.7167 23:0.7167 24:0.7 25:0.7 26:0.7 27:0.6333 28:0.6333 29:0.6333 30:0.6333 31:0.6333 32:0.6333 33:0.6333 34:0.65 35:0.65 36:0.45 37:0.45 38:0.4333 39:0.4333 40:0.4333 41:0.4333 42:0.4333 43:0.4333 44:0.4333 45:0.4333 46:0.4333 47:0.4333 48:0.4333 49:0.4333 50:0.4333 51:0.4333 52:0.4333 53:0.4333 54:0.4333 55:0.4333 56:0.4333 57:0.4333 58:0.45 59:0.45 60:0.5333 61:0.5 62:0.5333 63:0.4833 64:1 65:1 66:0.9167 67:0.9167 68:0.9167 69:0.9 70:0.9 71:0.9 72:0.9 73:0.9 74:0.9 75:0.9 76:0.9 77:1 78:1 79:1 80:1 81:1 82:1 83:0.8 84:0.8 85:0.8 86:0.8 87:0.8 88:0.8 89:0.8 90:0.8 91:0.8 92:0.8 93:0.8 94:0.8333 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:1 118:1 119:1 120:1 121:0.7167 122:0.7 123:0.6833 124:0.6667 125:0.65 126:0.6333 127:0.6167 128:0.6167 129:0.6333 130:0.6167 131:0.6167 132:0.6333 133:0.6167 134:0.6333 135:0.65 136:0.65 137:0.6667 138:0.6667 139:0.6667 140:0.6167 141:0.6 142:0.57894737 143:0.57894737 144:0.50873684 145:0.50873684 146:0.50873684 147:0.50873684 148:0.50873684 149:0.50873684 150:0.50873684 151:0.50873684 152:0.50873684 153:0.52631579 154:0.52631579 155:0.52631579 156:0.54389474 157:0.53574834 158:0.53574834 159:0.53574834 160:0.53574834 161:0.53574834 162:0.51785542 163:0.51785542 164:0.51785542 165:0.51785542 166:0.51785542 167:0.44639088 168:0.44639088 169:0.44639088 170:0.44639088 171:0.44639088 172:0.44639088 173:0.44639088 174:0.41071218 175:0.41071218 176:0.41071218 177:0.41071218 178:0.41071218 179:0.41071218 180:0.41071218 181:0.41071218 182:0.41071218 183:0.41071218 184:0.41071218 185:0.41071218 186:0.41071218 187:0.41071218 188:0.41071218 189:0.4642838 190:0.4286051 191:0.4286051 192:0.4286051 193:0.4286051 194:0.4286051 195:0.4286051 196:0.4286051 197:0.4286051 198:0.4286051 199:0.4286051 200:0.4286051 201:0.4286051 202:0.4286051 203:0.4286051 204:0.44639088 205:0.44639088 206:0.4642838 207:0.48217672 208:0.53574834 209:0.55353412 210:0.53574834 211:0.53574834 212:0.53574834 213:0.53574834 214:0.55353412 215:0.55353412 216:0.57142704 217:0.55353412 218:0.55353412 219:0.55353412 220:0.55353412 221:0.5833 222:0.6 223:0.6 224:0.6 225:0.6 226:0.6 227:0.6167 228:0.6333 229:0.7333 230:0.7167 231:0.7333 232:0.7667 233:0.7667 234:0.7667 235:0.7667 236:0.7667 237:0.75 238:0.7667 239:0.7667 240:0.8 241:0.8167 242:1 243:1 244:1 245:1 246:1 247:1 248:1 249:1 250:1 251:1 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:0.9833 288:0.9833 289:0.9833 290:0.9667 291:0.95 292:0.7167 293:0.7 294:0.7 295:0.6833 296:0.6833 297:0.55 298:0.6833 299:0.55 300:0.6333 301:0.5667 302:0.55 303:0.4833 304:0.4833 305:0.4833 306:0.4833 307:0.4833 308:0.4833 309:0.4833 310:0.4833 311:0.4833 312:0.4833 313:0.4833 314:0.5 315:0.5 316:0.5 317:0.5 318:0.5 319:0.5167 320:0.4333 321:0.4167 322:0.4 323:0.4 324:0.4 325:0.4 326:0.4 327:0.4 328:0.4 329:0.4 330:0.4 331:0.4 332:0.4 333:0.4 334:0.4167 335:0.6333 336:0.6333 337:0.6167 338:0.6167 339:0.6167 340:0.6167 341:0.6167 342:0.6167 343:0.6167 344:0.6167 345:0.6167 346:0.6167 347:0.6167 348:0.7 349:0.6833 350:0.7 351:0.7167 352:0.7333 353:0.8667 354:0.8667 355:0.8667 356:0.8667 357:0.8667 358:0.8833 359:0.8667 360:0.8667
0.545646309465038 1:1 2:1 3:1 4:1 5:0.9333 6:0.9333 7:0.5833 8:0.6 9:0.5833 10:0.5833 11:0.4333 12:0.4167 13:0.4167 14:0.4167 15:0.4167 16:0.4167 17:0.4167 18:0.4167 19:0.4167 20:0.4167 21:0.4167 22:0.4167 23:0.4167 24:0.4 25:0.4 26:0.4 27:0.4 28:0.4 29:0.4 30:0.4 31:0.3167 32:0.3 33:0.3 34:0.3 35:0.2833 36:0.2833 37:0.3 38:0.2833 39:0.2833 40:0.2833 41:0.2833 42:0.2667 43:0.2833 44:0.2833 45:0.2667 46:0.2833 47:0.2833 48:0.2833 49:0.2833 50:0.2833 51:0.2833 52:0.2833 53:0.2833 54:0.2833 55:0.2667 56:0.3 57:0.3167 58:0.3167 59:0.3167 60:0.3167 61:0.3167 62:0.3167 63:0.3167 64:0.3167 65:0.3167 66:0.3167 67:0.3 68:0.3167 69:0.3833 70:0.3833 71:0.3833 72:0.3833 73:0.3833 74:0.3833 75:0.3833 76:0.3833 77:0.3833 78:0.6167 79:0.6167 80:0.7333 81:0.7833 82:0.9 83:0.8833 84:0.8833 85:0.8833 86:0.8833 87:1 88:1 89:1 90:1 91:0.8167 92:0.5 93:0.5 94:0.5 95:0.3667 96:0.2833 97:0.2667 98:0.2 99:0.1833 100:0.1833 101:0.2 102:0.1333 103:0.1333 104:0.1333 105:0.1333 106:0.1333 107:0.1333 108:0.1333 109:0.1333 110:0.06667 111:0.06667 112:0.06667 113:0.06667 114:0.06667 115:0.06667 116:0.06667 117:0.06667 118:0.06667 119:0.08333 120:0.08333 121:0.08333 122:0.08333 123:0.08333 124:0.06667 125:0.06667 126:0.06667 127:0.08333 128:0.08333 129:0.08333 130:0.08333 131:0.08333 132:0.08333 133:0.08333 134:0.08333 135:0.08333 136:0.06667 137:0.08333 138:0.08333 139:0.08333 140:0.08333 141:0.08333 142:0.035084211 143:0.035084211 144:0.035084211 145:0.035084211 146:0.017547368 147:0.017547368 148:0.017547368 149:0.035084211 150:0.035084211 151:0.035084211 152:0.035084211 153:0.035084211 154:0.017547368 155:0.017547368 156:0.017547368 163:0.017850064 164:0.017850064 165:0.017850064 166:0.035710842 167:0.035710842 168:0.035710842 169:0.035710842 170:0.035710842 171:0.035710842 172:0.035710842 173:0.035710842 174:0.035710842 175:0.035710842 176:0.035710842 177:0.035710842 178:0.035710842 179:0.035710842 180:0.035710842 181:0.035710842 182:0.035710842 183:0.035710842 184:0.035710842 185:0.035710842 186:0.035710842 187:0.035710842 188:0.035710842 189:0.035710842 190:0.035710842 191:0.035710842 192:0.035710842 193:0.035710842 194:0.035710842 195:0.035710842 196:0.035710842 197:0.053603763 198:0.053603763 199:0.053603763 200:0.053603763 201:0.053603763 202:0.035710842 203:0.053603763 204:0.053603763 205:0.053603763 206:0.053603763 207:0.053603763 208:0.053603763 209:0.053603763 210:0.035710842 211:0.035710842 212:0.035710842 213:0.053603763 214:0.053603763 215:0.053603763 216:0.053603763 217:0.053603763 218:0.035710842 219:0.035710842 220:0.035710842 221:0.1 222:0.1 223:0.1 224:0.1167 225:0.1167 226:0.1167 227:0.1167 228:0.1167 229:0.1167 230:0.1167 231:0.1167 232:0.1167 233:0.1167 234:0.1333 235:0.1333 236:0.1167 237:0.1333 238:0.1333 239:0.1333 240:0.1333 241:0.1333 242:0.1167 243:0.1167 244:0.1167 245:0.1333 246:0.1333 247:0.1333 248:0.1167 249:0.1167 250:0.1167 251:0.1167 252:0.2333 253:0.2333 254:0.2333 255:0.2333 256:0.2333 257:0.2333 258:0.25 259:0.2833 260:0.2833 261:0.2833 262:0.2833 263:0.4833 264:0.4667 265:0.4833 266:0.4833 267:0.7167 268:0.7333 269:0.7333 270:0.7333 271:0.7333 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:0.7167 280:0.7167 281:0.7167 282:0.7167 283:0.7167 284:0.7167 285:0.3833 286:0.3833 287:0.3833 288:0.3833 289:0.3833 290:0.3833 291:0.3833 292:0.3833 293:0.3833 294:0.3833 295:0.3833 296:0.25 297:0.25 298:0.25 299:0.25 300:0.25 301:0.25 302:0.25 303:0.25 304:0.25 305:0.25 306:0.25 307:0.25 308:0.25 309:0.25 310:0.25 311:0.25 312:0.25 313:0.25 314:0.25 315:0.2667 316:0.2667 317:0.2667 318:0.2667 319:0.2667 320:0.2667 321:0.2667 322:0.2667 323:0.2667 324:0.2667 325:0.2667 326:0.2833 327:0.2833 328:0.2833 329:0.2833 330:0.2667 331:0.2667 332:0.2833 333:0.2833 334:0.2667 335:0.2667 336:0.2833 337:0.2667 338:0.2667 339:0.2833 340:0.2667 341:0.2667 342:0.2833 343:0.2667 344:0.2667 345:0.2667 346:0.2833 347:0.4333 348:0.4167 349:0.4333 350:0.4167 351:0.4167 352:0.4167 353:0.4167 354:0.4167 355:0.4167 356:0.6 357:0.6 358:0.75 359:0.75 360:1
0.133663192574621 1:1 2:1 3:1 4:1 5:1 6:1 7:1 8:0.8667 9:0.5333 10:0.5167 11:0.5167 12:0.5 13:0.5 14:0.3333 15:0.3333 16:0.3333 17:0.3333 18:0.3167 19:0.3333 20:0.3333 21:0.3333 22:0.3333 23:0.3333 24:0.3333 25:0.3333 26:0.3167 27:0.3333 28:0.3333 29:0.3167 30:0.3333 31:0.3333 32:0.3333 33:0.3333 34:0.3167 35:0.3333 36:0.3333 37:0.3167 38:0.3333 39:0.3333 40:0.3167 41:0.3333 42:0.3333 43:0.3167 44:0.3333 45:0.2333 46:0.2333 47:0.2333 48:0.2167 49:0.2167 50:0.2167 51:0.2333 52:0.2167 53:0.2167 54:0.2167 55:0.2167 56:0.2333 57:0.2167 58:0.2167 59:0.2333 60:0.2333 61:0.2167 62:0.2167 63:0.2333 64:0.2167 65:0.2167 66:0.2167 67:0.2167 68:0.2333 69:0.2333 70:0.2333 71:0.2333 72:0.2333 73:0.2333 74:0.2667 75:0.2667 76:0.2833 77:0.2833 78:0.2667 79:0.2667 80:0.2833 81:0.2667 82:0.2667 83:0.2667 84:0.2667 85:0.2667 86:0.2833 87:0.4 88:0.4 89:0.4 90:0.4167 91:0.4167 92:0.4167 93:0.8333 94:0.85 95:1 96:1 97:1 98:1 99:1 100:0.8333 101:0.75 102:0.6833 103:0.6833 104:0.6833 105:0.5167 106:0.5333 107:0.5333 108:0.4167 109:0.4 110:0.4 111:0.4 112:0.4 113:0.4 114:0.3167 115:0.3 116:0.3 117:0.3 118:0.3 119:0.3 120:0.25 121:0.25 122:0.25 123:0.2333 124:0.25 125:0.25 126:0.25 127:0.2333 128:0.25 129:0.2 130:0.2 131:0.2 132:0.2 133:0.1833 134:0.2 135:0.2 136:0.2 137:0.2 138:0.2 139:0.2 140:0.2 141:0.2 142:0.15789474 143:0.15789474 144:0.15789474 145:0.15789474 146:0.15789474 147:0.12284211 148:0.12284211 149:0.10526316 150:0.12284211 151:0.12284211 152:0.12284211 153:0.12284211 154:0.12284211 155:0.12284211 156:0.12284211 157:0.10717538 158:0.10717538 159:0.10717538 160:0.10717538 161:0.10717538 162:0.10717538 163:0.10717538 164:0.10717538 165:0.10717538 166:0.10717538 167:0.10717538 168:0.10717538 169:0.10717538 170:0.10717538 171:0.053603763 172:0.053603763 173:0.053603763 174:0.053603763 175:0.053603763 176:0.053603763 177:0.035710842 178:0.035710842 179:0.035710842 180:0.035710842 181:0.035710842 182:0.035710842 183:0.035710842 184:0.035710842 185:0.035710842 186:0.035710842 187:0.035710842 188:0.035710842 189:0.035710842 190:0.035710842 191:0.035710842 192:0.035710842 193:0.035710842 194:0.035710842 195:0.035710842 196:0.035710842 197:0.035710842 198:0.035710842 199:0.035710842 200:0.035710842 201:0.035710842 202:0.035710842 203:0.035710842 204:0.035710842 205:0.035710842 206:0.035710842 207:0.035710842 208:0.035710842 209:0.035710842 210:0.035710842 211:0.035710842 212:0.035710842 213:0.035710842 214:0.035710842 215:0.035710842 216:0.035710842 217:0.035710842 218:0.035710842 219:0.035710842 220:0.035710842 221:0.1 222:0.1 223:0.1 224:0.1833 225:0.1833 226:0.1833 227:0.1833 228:0.1833 229:0.1833 230:0.2 231:0.25 232:0.25 233:0.2667 234:0.2667 235:0.2667 236:0.2833 237:0.2833 238:0.3 239:0.3 240:0.3 241:0.3 242:0.3 243:0.3 244:0.3 245:0.3 246:0.3 247:0.3 248:0.3 249:0.3 250:0.3 251:0.4833 252:0.4833 253:0.4833 254:0.4833 255:0.4833 256:0.4833 257:0.5 258:0.5 259:0.5 260:0.5 261:0.5167 262:0.5333 263:0.5333 264:0.5167 265:0.5333 266:0.5333 267:0.5667 268:0.5667 269:1 270:1 271:1 272:1 273:1 274:0.5167 275:0.35 276:0.35 277:0.35 278:0.35 279:0.35 280:0.35 281:0.35 282:0.35 283:0.35 284:0.35 285:0.35 286:0.35 287:0.35 288:0.5833 289:0.5833 290:0.8 291:0.8 292:1 293:1 294:1 295:1 296:1 297:1 298:0.2 299:0.2 300:0.2167 301:0.2167 302:0.2 303:0.2 304:0.2 305:0.2 306:0.2 307:0.2 308:0.2 309:0.2 310:0.2167 311:0.2 312:0.2 313:0.2 314:0.2 315:0.2 316:0.2 317:0.2 318:0.2 319:0.2 320:0.2 321:0.2 322:0.1833 323:0.1833 324:0.1833 325:0.2 326:0.2 327:0.1833 328:0.1833 329:0.1833 330:0.2 331:0.2 332:0.2 333:0.1833 334:0.2 335:0.2 336:0.2 337:0.1833 338:0.1833 339:0.2 340:0.2 341:0.1833 342:0.1833 343:0.1833 344:0.2833 345:0.2833 346:0.2833 347:0.3 348:0.3333 349:0.3333 350:0.3333 351:0.3333 352:0.3333 353:0.3333 354:0.3333 355:0.3333 356:0.3333 357:0.5167 358:0.5167 359:0.5167 360:0.5167
0.5760179746988341 1:0.1333 2:0.1333 3:0.1333 4:0.1333 5:0.1333 6:0.1333 7:0.1333 8:0.1333 9:0.1333 10:0.1333 11:0.1333 12:0.1333 13:0.1333 14:0.1333 15:0.1333 16:0.1333 17:0.1333 18:0.1333 19:0.1333 20:0.1333 21:0.1333 22:0.1333 23:0.1333 24:0.1333 25:0.1333 26:0.1333 27:0.1333 28:0.1333 29:0.1333 30:0.1833 31:0.1833 32:0.1833 33:0.1833 34:0.1833 35:0.1833 36:0.1833 37:0.1833 38:0.1833 39:0.1833 40:0.1833 41:0.1833 42:0.1833 43:0.1833 44:0.1833 45:0.1833 46:0.1833 47:0.1833 48:0.1833 49:0.1833 50:0.2 51:0.2 52:0.2 53:0.2 54:0.2 55:0.1833 56:0.1833 57:0.2 58:0.2 59:0.2 60:0.2 61:0.2 62:0.1833 63:0.2 64:0.2 65:0.2833 66:0.2833 67:0.2833 68:0.2833 69:0.2833 70:0.3 71:0.3 72:0.3 73:0.3 74:0.3167 75:0.3167 76:0.3167 77:0.3167 78:0.3333 79:0.55 80:0.5667 81:0.5667 82:0.6167 83:0.6167 84:0.6167 85:0.6167 86:0.6167 87:0.6167 88:0.8333 89:0.8333 90:0.8333 91:0.7667 92:0.75 93:0.75 94:0.75 95:0.6333 96:0.6333 97:0.55 98:0.55 99:0.1833 100:0.1833 101:0.2 102:0.2 103:0.2 104:0.1833 105:0.1833 106:0.1833 107:0.1833 108:0.1833 109:0.1833 110:0.1833 111:0.1833 112:0.1833 113:0.1833 114:0.1833 115:0.1833 116:0.1833 117:0.1833 118:0.1833 119:0.1833 120:0.1833 121:0.1833 122:0.1833 123:0.1833 124:0.1833 125:0.1833 126:0.1833 127:0.1833 128:0.1833 129:0.1833 130:0.1833 131:0.2 132:0.2 133:0.1833 134:0.2 135:0.2 136:0.2 137:0.2 138:0.2 139:0.2 140:0.2 141:0.2 142:0.15789474 143:0.15789474 144:0.15789474 145:0.14031579 146:0.14031579 147:0.15789474 148:0.15789474 149:0.15789474 150:0.15789474 151:0.15789474 152:0.14031579 153:0.15789474 154:0.15789474 155:0.17547368 156:0.17547368 157:0.160747 158:0.160747 159:0.160747 160:0.160747 161:0.160747 162:0.17853278 163:0.17853278 164:0.1964257 165:0.21431862 166:0.2321044 167:0.26789024 168:0.26789024 169:0.26789024 170:0.26789024 171:0.41071218 172:0.41071218 173:0.41071218 174:0.48217672 175:0.48217672 176:0.48217672 177:0.48217672 178:0.48217672 179:0.6964632 180:1 181:1 182:1 183:0.39281926 184:0.39281926 185:0.39281926 186:0.39281926 187:0.39281926 188:0.39281926 189:0.39281926 190:0.39281926 191:0.39281926 192:0.39281926 193:0.39281926 194:0.39281926 195:0.17853278 196:0.17853278 197:0.17853278 198:0.17853278 199:0.17853278 200:0.17853278 201:0.17853278 202:0.17853278 203:0.17853278 204:0.17853278 205:0.17853278 206:0.17853278 207:0.17853278 208:0.17853278 209:0.17853278 210:0.17853278 211:0.17853278 212:0.17853278 213:0.14285408 214:0.14285408 215:0.14285408 216:0.14285408 217:0.160747 218:0.14285408 219:0.14285408 220:0.14285408 221:0.2 222:0.2 223:0.2 224:0.2 225:0.2 226:0.2167 227:0.2 228:0.2 229:0.2 230:0.2 231:0.2 232:0.1833 233:0.1833 234:0.1833 235:0.2 236:0.2 237:0.1833 238:0.1833 239:0.1833 240:0.2 241:0.2 242:0.2 243:0.1833 244:0.2 245:0.2 246:0.2 247:0.1833 248:0.1833 249:0.2 250:0.2 251:0.1833 252:0.1833 253:0.1833 254:0.2 255:0.2 256:0.2167 257:0.2167 258:0.2167 259:0.2167 260:0.2167 261:0.2167 262:0.2167 263:0.2167 264:0.2167 265:0.2167 266:0.2167 267:0.2167 268:0.2167 269:0.2333 270:0.3 271:0.3 272:0.3 273:0.5833 274:0.5833 275:0.7667 276:0.7667 277:0.7833 278:0.9833 279:1 280:1 281:1 282:1 283:1 284:0.95 285:0.7167 286:0.7 287:0.7 288:0.65 289:0.6667 290:0.6667 291:0.4667 292:0.3 293:0.2833 294:0.2833 295:0.2833 296:0.2833 297:0.2833 298:0.2833 299:0.3 300:0.2833 301:0.2833 302:0.3 303:0.2833 304:0.2833 305:0.3 306:0.2833 307:0.2833 308:0.2833 309:0.3167 310:0.3167 311:0.2167 312:0.2167 313:0.2167 314:0.2167 315:0.2167 316:0.1667 317:0.15 318:0.15 319:0.15 320:0.15 321:0.15 322:0.15 323:0.15 324:0.15 325:0.15 326:0.1333 327:0.15 328:0.15 329:0.15 330:0.15 331:0.15 332:0.15 333:0.15 334:0.15 335:0.15 336:0.15 337:0.15 338:0.15 339:0.15 340:0.15 341:0.15 342:0.15 343:0.15 344:0.15 345:0.15 346:0.15 347:0.15 348:0.15 349:0.15 350:0.15 351:0.1333 352:0.1333 353:0.1333 354:0.1333 355:0.1333 356:0.1333 357:0.1333 358:0.1333 359:0.1333 360:0.1333
2 1:0.1167 2:0.1167 3:0.1167 4:0.1167 5:0.1167 6:0.1167 7:0.1167 8:0.1167 9:0.1167 10:0.1167 11:0.1167 12:0.1167 13:0.1167 14:0.1167 15:0.1167 16:0.1167 17:0.1167 18:0.1167 19:0.15 20:0.15 21:0.15 22:0.15 23:0.15 24:0.15 25:0.15 26:0.15 27:0.15 28:0.15 29:0.15 30:0.15 31:0.15 32:0.15 33:0.1667 34:0.15 35:0.15 36:0.15 37:0.15 38:0.15 39:0.15 40:0.15 41:0.15 42:0.15 43:0.15 44:0.15 45:0.25 46:0.25 47:0.25 48:0.2667 49:0.2667 50:0.2667 51:0.25 52:0.25 53:0.25 54:0.25 55:0.25 56:0.25 57:0.25 58:0.25 59:0.25 60:0.25 61:0.25 62:0.25 63:0.25 64:0.25 65:0.25 66:0.25 67:0.25 68:0.25 69:0.25 70:0.25 71:0.4 72:0.4 73:0.4 74:0.4 75:0.3833 76:0.4167 77:0.4167 78:0.4167 79:0.4167 80:0.4167 81:0.5167 82:0.65 83:0.65 84:0.6833 85:0.6833 86:0.6833 87:0.7 88:0.8667 89:0.8833 90:0.7333 91:0.7167 92:0.7167 93:0.7167 94:0.6 95:0.6 96:0.3167 97:0.3167 98:0.3167 99:0.3167 100:0.15 101:0.15 102:0.1667 103:0.1667 104:0.1667 105:0.1667 106:0.1667 107:0.1667 108:0.1667 109:0.1667 110:0.1667 111:0.1667 112:0.1667 113:0.1667 114:0.1667 115:0.1667 116:0.1667 117:0.1667 118:0.1667 119:0.1667 120:0.1667 121:0.1667 122:0.1667 123:0.15 124:0.1667 125:0.1667 126:0.1667 127:0.1667 128:0.1667 129:0.1667 130:0.1667 131:0.1667 132:0.1667 133:0.1667 134:0.1667 135:0.1667 136:0.1667 137:0.15 138:0.1667 139:0.1667 140:0.1667 141:0.1667 142:0.12284211 143:0.12284211 144:0.12284211 145:0.12284211 146:0.12284211 147:0.12284211 148:0.12284211 149:0.10526316 150:0.12284211 151:0.12284211 152:0.12284211 153:0.12284211 154:0.12284211 155:0.12284211 156:0.12284211 157:0.10717538 158:0.10717538 159:0.089282462 160:0.10717538 161:0.10717538 162:0.10717538 163:0.10717538 164:0.10717538 165:0.10717538 166:0.10717538 167:0.10717538 168:0.10717538 169:0.10717538 170:0.10717538 171:0.089282462 172:0.089282462 173:0.10717538 174:0.1964257 175:0.1964257 176:0.1964257 177:0.1964257 178:0.1964257 179:0.1964257 180:0.1964257 181:0.1964257 182:0.1964257 183:1 184:0.4286051 185:0.4286051 186:0.4286051 187:0.4286051 188:0.4286051 189:0.4286051 190:0.4286051 191:0.4286051 192:0.4286051 193:0.4286051 194:0.4286051 195:0.4286051 196:0.4286051 197:0.44639088 198:0.44639088 199:0.4286051 200:0.4286051 201:0.4286051 202:0.4286051 203:0.37503348 204:0.37503348 205:0.37503348 206:0.28567602 207:0.26789024 208:0.26789024 209:0.24999732 210:0.24999732 211:0.26789024 212:0.24999732 213:0.24999732 214:0.24999732 215:0.2321044 216:0.2321044 217:0.21431862 218:0.21431862 219:0.21431862 220:0.1964257 221:0.25 222:0.25 223:0.2333 224:0.2333 225:0.2333 226:0.2333 227:0.2333 228:0.2167 229:0.1667 230:0.1667 231:0.1667 232:0.1667 233:0.1667 234:0.1667 235:0.1667 236:0.1667 237:0.1667 238:0.1667 239:0.1667 240:0.1667 241:0.1667 242:0.1667 243:0.1667 244:0.1667 245:0.1667 246:0.1667 247:0.1667 248:0.1667 249:0.1667 250:0.1667 251:0.1667 252:0.1667 253:0.1667 254:0.1667 255:0.1667 256:0.1667 257:0.1667 258:0.1833 259:0.25 260:0.25 261:0.25 262:0.3 263:0.3 264:0.3 265:0.3 266:0.3 267:0.4667 268:0.4667 269:0.4667 270:0.4667 271:0.7833 272:0.8833 273:0.8833 274:0.9 275:1 276:1 277:1 278:1 279:1 280:0.85 281:0.8333 282:0.8333 283:0.6833 284:0.7 285:0.6833 286:0.5 287:0.5 288:0.5 289:0.5 290:0.5 291:0.5 292:0.5 293:0.5 294:0.4833 295:0.4333 296:0.4333 297:0.4333 298:0.4333 299:0.3667 300:0.2167 301:0.2167 302:0.2167 303:0.2167 304:0.2167 305:0.2167 306:0.2167 307:0.2167 308:0.2167 309:0.2167 310:0.2167 311:0.2167 312:0.2167 313:0.2167 314:0.2167 315:0.2167 316:0.1667 317:0.15 318:0.1667 319:0.2167 320:0.1667 321:0.1667 322:0.1667 323:0.1667 324:0.1667 325:0.1667 326:0.1667 327:0.1667 328:0.1667 329:0.1667 330:0.1667 331:0.1667 332:0.1667 333:0.1667 334:0.1667 335:0.1667 336:0.1667 337:0.1667 338:0.1667 339:0.15 340:0.25 341:0.3 342:0.3 343:0.3 344:0.1167 345:0.1167 346:0.1167 347:0.1167 348:0.1167 349:0.1167 350:0.1167 351:0.1167 352:0.1167 353:0.1167 354:0.1167 355:0.1167 356:0.1167 357:0.1167 358:0.1167 359:0.1167 360:0.1167
0.11331162946465 1:0.1 2:0.1 3:0.1 4:0.1 5:0.1 6:0.1 7:0.1 8:0.1 9:0.1 10:0.1 11:0.1 12:0.1 13:0.1 14:0.1 15:0.1 16:0.1 17:0.1 18:0.1 19:0.1 20:0.1 21:0.1 22:0.1 23:0.1 24:0.1 25:0.1 26:0.1 27:0.1 28:0.1 29:0.1 30:0.1 31:0.1 32:0.1 33:0.1 34:0.1 35:0.1 36:0.1 37:0.1 38:0.1167 39:0.1167 40:0.15 41:0.15 42:0.15 43:0.15 44:0.15 45:0.25 46:0.25 47:0.25 48:0.25 49:0.25 50:0.25 51:0.25 52:0.25 53:0.25 54:0.25 55:0.25 56:0.25 57:0.25 58:0.25 59:0.25 60:0.25 61:0.25 62:0.25 63:0.3667 64:0.3667 65:0.3667 66:0.3667 67:0.5167 68:0.8667 69:0.9667 70:1 71:1 72:1 73:1 74:1 75:1 76:0.8 77:0.6833 78:0.6833 79:0.4833 80:0.4833 81:0.4833 82:0.35 83:0.35 84:0.35 85:0.35 86:0.2333 87:0.2333 88:0.2333 89:0.2333 90:0.2333 91:0.2333 92:0.2333 93:0.2333 94:0.2333 95:0.2333 96:0.2333 97:0.2333 98:0.2333 99:0.2333 100:0.2333 101:0.1333 102:0.1333 103:0.1333 104:0.1333 105:0.1333 106:0.1333 107:0.1333 108:0.1333 109:0.1333 110:0.1333 111:0.1333 112:0.1333 113:0.1333 114:0.1333 115:0.1333 116:0.1333 117:0.1333 118:0.1333 119:0.1333 120:0.1333 121:0.1333 122:0.1333 123:0.1333 124:0.1333 125:0.1333 126:0.1333 127:0.1333 128:0.1333 129:0.1333 130:0.1333 131:0.1333 132:0.1333 133:0.1333 134:0.1333 135:0.1333 136:0.1333 137:0.1333 138:0.1333 139:0.1333 140:0.1667 141:0.1667 142:0.12284211 143:0.12284211 144:0.12284211 145:0.12284211 146:0.12284211 147:0.12284211 148:0.12284211 149:0.12284211 150:0.12284211 151:0.12284211 152:0.12284211 153:0.12284211 154:0.12284211 155:0.12284211 156:0.14031579 157:0.12496116 158:0.12496116 159:0.14285408 160:0.14285408 161:0.160747 162:0.160747 163:0.160747 164:0.160747 165:0.160747 166:0.160747 167:0.160747 168:0.160747 169:0.160747 170:0.160747 171:0.17853278 172:0.32146186 173:0.30356894 174:0.30356894 175:0.37503348 176:0.37503348 177:0.37503348 178:0.83928514 179:1 180:1 181:1 182:1 183:1 184:1 185:1 186:1 187:1 188:1 189:1 190:0.33924764 191:0.33924764 192:0.33924764 193:0.33924764 194:0.33924764 195:0.33924764 196:0.33924764 197:0.33924764 198:0.33924764 199:0.33924764 200:0.33924764 201:0.26789024 202:0.24999732 203:0.24999732 204:0.24999732 205:0.24999732 206:0.24999732 207:0.24999732 208:0.24999732 209:0.24999732 210:0.24999732 211:0.24999732 212:0.24999732 213:0.24999732 214:0.24999732 215:0.1964257 216:0.1964257 217:0.1964257 218:0.1964257 219:0.1964257 220:0.1964257 221:0.25 222:0.25 223:0.25 224:0.25 225:0.25 226:0.25 227:0.25 228:0.25 229:0.25 230:0.25 231:0.25 232:0.25 233:0.25 234:0.25 235:0.25 236:0.25 237:0.25 238:0.25 239:0.25 240:0.25 241:0.25 242:0.25 243:0.2667 244:0.2667 245:0.25 246:0.25 247:0.2667 248:0.2667 249:0.2667 250:0.2667 251:0.2667 252:0.2833 253:0.3333 254:0.35 255:0.35 256:0.4167 257:0.35 258:0.35 259:0.4333 260:0.35 261:0.3333 262:0.35 263:0.3333 264:0.3333 265:0.4167 266:0.5667 267:0.5667 268:0.5667 269:0.7 270:0.7 271:0.7 272:0.7 273:0.7167 274:0.7167 275:1 276:0.7167 277:0.7167 278:0.7167 279:0.7167 280:0.6 281:0.6 282:0.6 283:0.6 284:0.6 285:0.6 286:0.35 287:0.3333 288:0.35 289:0.35 290:0.3333 291:0.2167 292:0.2167 293:0.2167 294:0.2167 295:0.2167 296:0.2167 297:0.2167 298:0.2167 299:0.2167 300:0.2167 301:0.2167 302:0.2167 303:0.2167 304:0.2167 305:0.2167 306:0.2167 307:0.2167 308:0.2167 309:0.2167 310:0.2167 311:0.2167 312:0.2167 313:0.2167 314:0.2167 315:0.2333 316:0.2333 317:0.2333 318:0.2167 319:0.2167 320:0.2167 321:0.2167 322:0.2167 323:0.1167 324:0.1167 325:0.1167 326:0.1167 327:0.1167 328:0.1167 329:0.1167 330:0.1167 331:0.1167 332:0.1167 333:0.1167 334:0.1167 335:0.1167 336:0.1167 337:0.1167 338:0.1167 339:0.1167 340:0.1167 341:0.1167 342:0.1167 343:0.1167 344:0.1167 345:0.1167 346:0.1167 347:0.1167 348:0.1167 349:0.1167 350:0.1167 351:0.1167 352:0.1167 353:0.1167 354:0.1167 355:0.1167 356:0.1167 357:0.1 358:0.1 359:0.1 360:0.1
0.0007373997946089183 1:0.3333 2:0.3333 3:0.3333 4:0.3333 5:0.3333 6:0.3333 7:0.3333 8:0.3333 9:0.3333 10:0.3333 11:0.3333 12:0.3333 13:0.3333 14:0.3333 15:0.3333 16:0.3333 17:0.3333 18:0.3333 19:0.3333 20:0.3333 21:0.35 22:0.35 23:0.35 24:0.35 25:0.35 26:0.35 27:0.35 28:0.35 29:0.3667 30:0.3667 31:0.3667 32:0.3667 33:0.3667 34:0.3833 35:0.3833 36:0.3833 37:0.3833 38:0.4 39:0.4 40:0.4 41:0.4167 42:0.4167 43:0.4167 44:0.4333 45:0.4333 46:0.4333 47:0.45 48:0.45 49:0.4667 50:0.4667 51:0.4833 52:0.5 53:0.5 54:0.5167 55:0.5333 56:0.5333 57:0.55 58:0.5667 59:0.5833 60:0.5833 61:0.5833 62:0.6 63:0.6167 64:0.65 65:0.6667 66:0.6833 67:0.7167 68:0.75 69:0.7833 70:0.8167 71:0.85 72:0.9 73:0.9333 74:1 75:1 76:1 77:0.8 78:0.8 79:0.8 80:0.8 81:0.7833 82:0.7833 83:0.7833 84:0.7833 85:0.7833 86:0.7833 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:0.8667 107:0.8167 108:0.7667 109:0.7333 110:0.6833 111:0.6833 112:0.6667 113:0.6333 114:0.5667 115:0.55 116:0.5333 117:0.5167 118:0.5 119:0.4833 120:0.4667 121:0.45 122:0.3667 123:0.3667 124:0.35 125:0.35 126:0.35 127:0.35 128:0.35 129:0.35 130:0.35 131:0.35 132:0.35 133:0.3333 134:0.3333 135:0.3333 136:0.3167 137:0.3167 138:0.2833 139:0.2833 140:0.2833 141:0.2833 142:0.24557895 143:0.24557895 144:0.24557895 145:0.24557895 146:0.24557895 147:0.24557895 148:0.24557895 149:0.24557895 150:0.24557895 151:0.24557895 152:0.24557895 153:0.24557895 154:0.24557895 155:0.24557895 156:0.26315789 157:0.24999732 158:0.24999732 159:0.24999732 160:0.24999732 161:0.26789024 162:0.26789024 163:0.26789024 164:0.26789024 165:0.28567602 166:0.30356894 167:0.32146186 168:0.87496384 169:0.87496384 170:0.87496384 171:0.83928514 172:0.83928514 173:0.83928514 174:0.83928514 175:0.83928514 176:0.83928514 177:0.83928514 178:0.83928514 179:0.85717806 180:0.94642838 181:0.94642838 182:1 183:1 184:0.94642838 185:0.94642838 186:0.83928514 187:0.83928514 188:0.85717806 189:0.85717806 190:0.83928514 191:0.83928514 192:0.85717806 193:0.85717806 194:0.67857028 195:0.67857028 196:0.67857028 197:0.67857028 198:0.67857028 199:0.67857028 200:0.67857028 201:0.67857028 202:0.6964632 203:0.6964632 204:0.6964632 205:0.6964632 206:0.28567602 207:0.28567602 208:0.28567602 209:0.28567602 210:0.28567602 211:0.26789024 212:0.26789024 213:0.26789024 214:0.26789024 215:0.26789024 216:0.26789024 217:0.26789024 218:0.26789024 219:0.26789024 220:0.26789024 221:0.3167 222:0.3167 223:0.3167 224:0.3167 225:0.3167 226:0.3167 227:0.3167 228:0.3167 229:0.3167 230:0.3167 231:0.3333 232:0.3333 233:0.3333 234:0.35 235:0.35 236:0.3667 237:0.3667 238:0.3833 239:0.4 240:0.4 241:0.4167 242:0.4333 243:0.4333 244:0.4333 245:0.4333 246:0.45 247:0.4667 248:0.5333 249:0.55 250:0.5833 251:0.5833 252:0.5833 253:0.6167 254:0.65 255:0.7 256:0.7333 257:0.95 258:0.95 259:0.95 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:0.8333 296:0.7667 297:0.7333 298:0.7167 299:0.7 300:0.6667 301:0.65 302:0.6333 303:0.6167 304:0.6 305:0.5833 306:0.5667 307:0.55 308:0.55 309:0.5333 310:0.5167 311:0.5167 312:0.5 313:0.4833 314:0.4833 315:0.4667 316:0.4667 317:0.45 318:0.45 319:0.45 320:0.4333 321:0.4333 322:0.4333 323:0.4167 324:0.4167 325:0.4167 326:0.4 327:0.4 328:0.4 329:0.4 330:0.3833 331:0.3833 332:0.3833 333:0.3833 334:0.3833 335:0.3667 336:0.35 337:0.35 338:0.35 339:0.35 340:0.35 341:0.35 342:0.35 343:0.35 344:0.35 345:0.35 346:0.35 347:0.35 348:0.35 349:0.35 350:0.35 351:0.35 352:0.3333 353:0.3333 354:0.3333 355:0.3333 356:0.3333 357:0.3333 358:0.3333 359:0.3333 360:0.3333
0.8636109765598329 1:0.3167 2:0.3167 3:0.3167 4:0.3167 5:0.3167 6:0.3167 7:0.3167 8:0.3167 9:0.3167 10:0.3167 11:0.3167 12:0.3167 13:0.3167 14:0.3167 15:0.3167 16:0.3167 17:0.3167 18:0.3167 19:0.3167 20:0.3167 21:0.3333 22:0.3333 23:0.3333 24:0.3333 25:0.3333 26:0.3333 27:0.3333 28:0.3333 29:0.35 30:0.35 31:0.35 32:0.35 33:0.35 34:0.35 35:0.3667 36:0.3667 37:0.3667 38:0.3667 39:0.3667 40:0.3667 41:0.3667 42:0.3667 43:0.3833 44:0.3833 45:0.3833 46:0.4167 47:0.4333 48:0.4333 49:0.4333 50:0.45 51:0.45 52:0.45 53:0.45 54:0.4667 55:0.4667 56:0.4833 57:0.5 58:0.5 59:0.5167 60:0.5333 61:0.55 62:0.5667 63:0.5833 64:0.6 65:0.6333 66:0.65 67:0.6667 68:0.7 69:0.7333 70:0.7667 71:0.8 72:0.85 73:0.8833 74:0.9333 75:0.95 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:0.9333 108:0.8833 109:0.8333 110:0.8 111:0.75 112:0.7167 113:0.65 114:0.6167 115:0.6 116:0.5667 117:0.55 118:0.5333 119:0.5167 120:0.5 121:0.4833 122:0.4667 123:0.45 124:0.4167 125:0.4333 126:0.4167 127:0.3833 128:0.3833 129:0.3833 130:0.3833 131:0.3833 132:0.3667 133:0.3667 134:0.3667 135:0.35 136:0.35 137:0.35 138:0.3333 139:0.3333 140:0.3333 141:0.3167 142:0.28073684 143:0.28073684 144:0.28073684 145:0.28073684 146:0.28073684 147:0.28073684 148:0.28073684 149:0.28073684 150:0.28073684 151:0.28073684 152:0.28073684 153:0.28073684 154:0.28073684 155:0.28073684 156:0.29821053 157:0.30356894 158:0.28567602 159:0.28567602 160:0.30356894 161:0.30356894 162:0.30356894 163:0.30356894 164:0.32146186 165:0.33924764 166:0.91074968 167:0.91074968 168:0.91074968 169:0.92853546 170:0.92853546 171:0.87496384 172:0.87496384 173:0.87496384 174:0.87496384 175:0.87496384 176:0.87496384 177:0.87496384 178:0.87496384 179:0.9643213 180:0.9643213 181:0.9643213 182:0.9643213 183:0.9643213 184:0.85717806 185:0.85717806 186:0.85717806 187:0.85717806 188:0.85717806 189:0.85717806 190:0.85717806 191:0.7321419 192:0.71424898 193:0.67857028 194:0.67857028 195:0.6964632 196:0.67857028 197:0.67857028 198:0.32146186 199:0.30356894 200:0.30356894 201:0.30356894 202:0.30356894 203:0.28567602 204:0.26789024 205:0.24999732 206:0.26789024 207:0.26789024 208:0.26789024 209:0.24999732 210:0.24999732 211:0.26789024 212:0.24999732 213:0.24999732 214:0.26789024 215:0.24999732 216:0.24999732 217:0.24999732 218:0.24999732 219:0.24999732 220:0.26789024 221:0.3 222:0.3 223:0.3167 224:0.3167 225:0.3167 226:0.3167 227:0.3333 228:0.3333 229:0.3333 230:0.35 231:0.35 232:0.3667 233:0.3667 234:0.3833 235:0.3833 236:0.4 237:0.4 238:0.4167 239:0.4333 240:0.4333 241:0.45 242:0.4667 243:0.4833 244:0.5 245:0.5167 246:0.5333 247:0.55 248:0.5667 249:0.6 250:0.6333 251:0.65 252:0.6833 253:0.7333 254:0.7667 255:0.8167 256:0.8667 257:0.9167 258:0.9167 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:0.7833 295:0.75 296:0.7333 297:0.7 298:0.6833 299:0.65 300:0.6333 301:0.6167 302:0.6 303:0.5833 304:0.5667 305:0.55 306:0.5333 307:0.5 308:0.4833 309:0.4833 310:0.4667 311:0.45 312:0.45 313:0.4333 314:0.4333 315:0.4333 316:0.4167 317:0.4167 318:0.4 319:0.4 320:0.4 321:0.3833 322:0.3833 323:0.3833 324:0.3667 325:0.3667 326:0.3667 327:0.3667 328:0.35 329:0.35 330:0.35 331:0.35 332:0.35 333:0.35 334:0.3333 335:0.3333 336:0.3333 337:0.3333 338:0.3333 339:0.3333 340:0.3333 341:0.3333 342:0.3167 343:0.3167 344:0.3167 345:0.3167 346:0.3167 347:0.3167 348:0.3167 349:0.3167 350:0.3167 351:0.3167 352:0.3167 353:0.3167 354:0.3167 355:0.3167 356:0.3167 357:0.3167 358:0.3167 359:0.3167 360:0.3167
0.01691612721349328 1:0.6833 2:0.6833 3:0.6833 4:0.6833 5:0.6667 6:0.6667 7:0.65 8:0.65 9:0.65 10:0.65 11:0.65 12:0.65 13:0.65 14:0.6667 15:0.6667 16:0.7333 17:0.7333 18:0.7333 19:0.7333 20:0.7333 21:0.7333 22:0.7333 23:0.75 24:0.9167 25:0.9167 26:0.8833 27:0.8167 28:0.75 29:0.7333 30:0.7167 31:0.4833 32:0.3667 33:0.3667 34:0.3667 35:0.3667 36:0.3667 37:0.3667 38:0.3667 39:0.3667 40:0.3667 41:0.3667 42:0.3667 43:0.3667 44:0.3667 45:0.35 46:0.35 47:0.35 48:0.35 49:0.35 50:0.35 51:0.35 52:0.35 53:0.35 54:0.35 55:0.35 56:0.35 57:0.35 58:0.35 59:0.3667 60:0.4667 61:0.3833 62:0.3833 63:0.3833 64:0.3833 65:0.3833 66:0.3833 67:0.4167 68:0.3833 69:0.4167 70:0.4167 71:0.4167 72:0.4333 73:0.4333 74:0.4333 75:0.4333 76:0.4333 77:0.4333 78:0.4333 79:0.4333 80:0.4333 81:0.4333 82:0.4667 83:0.5333 84:0.9667 85:0.9667 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:0.7667 99:0.7667 100:0.5 101:0.5 102:0.4167 103:0.4167 104:0.4 105:0.3 106:0.2833 107:0.2833 108:0.2833 109:0.2833 110:0.2833 111:0.2167 112:0.2167 113:0.2167 114:0.2167 115:0.2167 116:0.2167 117:0.2167 118:0.2 119:0.2 120:0.1833 121:0.2 122:0.2 123:0.2 124:0.2 125:0.2 126:0.2 127:0.2 128:0.2 129:0.2 130:0.2 131:0.2 132:0.2 133:0.2 134:0.1167 135:0.1167 136:0.1167 137:0.1167 138:0.1167 139:0.1 140:0.1 141:0.1 142:0.052631579 143:0.052631579 144:0.052631579 145:0.070210526 146:0.070210526 147:0.070210526 148:0.070210526 149:0.070210526 150:0.052631579 151:0.052631579 152:0.052631579 153:0.070210526 154:0.070210526 155:0.070210526 156:0.070210526 157:0.053603763 158:0.053603763 159:0.053603763 160:0.035710842 161:0.053603763 162:0.053603763 163:0.053603763 164:0.053603763 165:0.053603763 166:0.035710842 167:0.035710842 168:0.035710842 169:0.053603763 170:0.053603763 171:0.035710842 172:0.035710842 173:0.035710842 174:0.035710842 175:0.035710842 176:0.035710842 177:0.035710842 178:0.035710842 179:0.035710842 180:0.035710842 181:0.035710842 182:0.035710842 183:0.035710842 184:0.035710842 185:0.035710842 186:0.035710842 187:0.035710842 188:0.035710842 189:0.035710842 190:0.035710842 191:0.035710842 192:0.035710842 193:0.035710842 194:0.035710842 195:0.035710842 196:0.035710842 197:0.035710842 198:0.035710842 199:0.035710842 200:0.035710842 201:0.035710842 202:0.035710842 203:0.035710842 204:0.035710842 205:0.035710842 206:0.035710842 207:0.035710842 208:0.035710842 209:0.035710842 210:0.035710842 211:0.035710842 212:0.035710842 213:0.035710842 214:0.035710842 215:0.035710842 216:0.035710842 217:0.035710842 218:0.035710842 219:0.035710842 220:0.035710842 221:0.1 222:0.1 223:0.1 224:0.1167 225:0.1167 226:0.1167 227:0.1167 228:0.1167 229:0.1167 230:0.1167 231:0.1167 232:0.1167 233:0.1167 234:0.1333 235:0.1333 236:0.1333 237:0.1333 238:0.1333 239:0.15 240:0.15 241:0.15 242:0.15 243:0.1667 244:0.1667 245:0.1667 246:0.1833 247:0.1833 248:0.1833 249:0.2167 250:0.2167 251:0.2167 252:0.2667 253:0.25 254:0.25 255:0.2667 256:0.35 257:0.45 258:0.45 259:0.45 260:0.45 261:0.45 262:0.55 263:0.55 264:0.6167 265:0.6667 266:0.6667 267:0.9167 268:1 269:0.9167 270:0.9 271:0.9 272:0.9 273:0.9 274:0.9 275:0.9 276:0.9 277:0.8 278:0.8 279:0.8 280:0.8 281:0.8 282:0.8 283:0.75 284:0.7333 285:0.65 286:0.6 287:0.5833 288:0.4833 289:0.4833 290:0.4833 291:0.4667 292:0.45 293:0.4167 294:0.4 295:0.4 296:0.4 297:0.4 298:0.4 299:0.4 300:0.3833 301:0.4 302:0.4 303:0.4 304:0.4 305:0.4 306:0.4167 307:0.4 308:0.4 309:0.4167 310:0.4167 311:0.4167 312:0.4167 313:0.4167 314:0.4167 315:0.4167 316:0.4 317:0.4 318:0.4 319:0.4 320:0.4 321:0.4 322:0.4 323:0.4 324:0.4 325:0.4 326:0.4 327:0.4 328:0.4 329:0.4 330:0.4 331:0.4167 332:0.4167 333:0.4167 334:0.4167 335:0.4333 336:0.4167 337:0.5 338:0.5 339:0.5 340:0.5 341:0.5 342:0.5 343:0.5 344:0.5 345:0.6333 346:0.6333 347:0.6333 348:0.6333 349:0.6333 350:0.65 351:0.7167 352:0.8 353:0.8167 354:0.6833 355:0.6833 356:0.6833 357:0.6833 358:0.6833 359:0.6833 360:0.6833
0.2535603430423138 1:0.5333 2:0.5333 3:0.5333 4:0.6333 5:0.6167 6:0.6167 7:0.6167 8:0.6167 9:0.6167 10:0.6 11:0.6 12:0.6 13:0.6 14:0.6 15:0.6 16:0.6 17:0.5833 18:0.5833 19:0.5667 20:0.5833 21:0.5667 22:0.5667 23:0.5833 24:0.5667 25:0.5833 26:0.5667 27:0.5833 28:0.6 29:0.65 30:0.4333 31:0.6167 32:0.4333 33:0.6 34:0.4333 35:0.6 36:0.4333 37:0.6 38:0.4333 39:0.4333 40:0.5667 41:0.5667 42:0.55 43:0.55 44:0.3167 45:0.3167 46:0.3167 47:0.3167 48:0.3167 49:0.3167 50:0.3167 51:0.3167 52:0.3167 53:0.3167 54:0.3167 55:0.3167 56:0.3167 57:0.3167 58:0.3167 59:0.3167 60:0.3167 61:0.3167 62:0.3333 63:0.3333 64:0.3333 65:0.3667 66:0.3333 67:0.3667 68:0.3333 69:0.3333 70:0.3667 71:0.3667 72:0.3667 73:0.3667 74:0.3667 75:0.4167 76:0.4167 77:0.4167 78:0.4167 79:0.4167 80:0.4167 81:0.4167 82:0.4167 83:0.4167 84:0.4667 85:0.5 86:0.5 87:1 88:1 89:0.6667 90:0.6667 91:0.6667 92:0.6667 93:0.6667 94:0.6667 95:0.6667 96:1 97:1 98:0.9167 99:0.7833 100:0.7833 101:0.7833 102:0.6833 103:0.55 104:0.55 105:0.4667 106:0.5333 107:0.3833 108:0.4 109:0.4 110:0.4 111:0.3167 112:0.3 113:0.2833 114:0.2833 115:0.2833 116:0.25 117:0.25 118:0.2333 119:0.2333 120:0.2333 121:0.2333 122:0.2333 123:0.2333 124:0.2333 125:0.2333 126:0.1833 127:0.1833 128:0.2 129:0.2 130:0.2 131:0.2 132:0.2 133:0.2 134:0.2 135:0.2 136:0.2 137:0.2 138:0.2 139:0.2 140:0.2 141:0.2 142:0.15789474 143:0.15789474 144:0.10526316 145:0.10526316 146:0.087684211 147:0.10526316 148:0.10526316 149:0.10526316 150:0.10526316 151:0.10526316 152:0.10526316 153:0.10526316 154:0.10526316 155:0.10526316 156:0.10526316 157:0.089282462 158:0.089282462 159:0.089282462 160:0.089282462 161:0.089282462 162:0.089282462 163:0.089282462 164:0.089282462 165:0.089282462 166:0.089282462 167:0.089282462 168:0.089282462 169:0.089282462 170:0.089282462 171:0.071389541 172:0.089282462 173:0.089282462 174:0.089282462 175:0.089282462 176:0.089282462 177:0.089282462 178:0.089282462 179:0.089282462 180:0.089282462 181:0.089282462 182:0.089282462 183:0.089282462 184:0.089282462 185:0.089282462 186:0.089282462 187:0.089282462 188:0.089282462 189:0.089282462 190:0.089282462 191:0.089282462 192:0.089282462 193:0.089282462 194:0.089282462 195:0.089282462 196:0.089282462 197:0.089282462 198:0.089282462 199:0.089282462 200:0.089282462 201:0.089282462 202:0.089282462 203:0.089282462 204:0.089282462 205:0.089282462 206:0.089282462 207:0.10717538 208:0.10717538 209:0.10717538 210:0.10717538 211:0.10717538 212:0.10717538 213:0.10717538 214:0.10717538 215:0.10717538 216:0.10717538 217:0.10717538 218:0.10717538 219:0.10717538 220:0.10717538 221:0.1667 222:0.1667 223:0.1667 224:0.1667 225:0.15 226:0.1667 227:0.25 228:0.25 229:0.25 230:0.2333 231:0.25 232:0.25 233:0.2333 234:0.2333 235:0.25 236:0.25 237:0.25 238:0.25 239:0.25 240:0.25 241:0.25 242:0.25 243:0.25 244:0.25 245:0.3 246:0.3 247:0.3 248:0.3 249:0.3 250:0.3 251:0.3167 252:0.3167 253:0.3167 254:0.3167 255:0.45 256:0.4333 257:0.45 258:0.4833 259:0.5 260:0.5 261:0.5667 262:0.6167 263:0.65 264:0.8333 265:0.9333 266:0.6333 267:0.6333 268:0.6333 269:0.6333 270:0.6333 271:0.6333 272:0.6333 273:0.6333 274:0.6333 275:0.6333 276:0.6333 277:0.6333 278:0.8 279:0.8 280:0.8 281:0.7667 282:0.65 283:0.6 284:0.5667 285:0.5833 286:0.4833 287:0.45 288:0.4167 289:0.4167 290:0.4167 291:0.4167 292:0.4 293:0.3833 294:0.4 295:0.3833 296:0.4 297:0.3833 298:0.4 299:0.4 300:0.4 301:0.4 302:0.3833 303:0.4 304:0.4 305:0.4 306:0.4167 307:0.4333 308:0.4167 309:0.4333 310:0.4167 311:0.4167 312:0.4167 313:0.4 314:0.4 315:0.4 316:0.4 317:0.4 318:0.4 319:0.4 320:0.4 321:0.4 322:0.4 323:0.4 324:0.4 325:0.4 326:0.4 327:0.4 328:0.4 329:0.4 330:0.4 331:0.4167 332:0.4167 333:0.4167 334:0.4167 335:0.4667 336:0.4833 337:0.4833 338:0.4833 339:0.4667 340:0.4833 341:0.4667 342:0.4833 343:0.6167 344:0.6167 345:0.6167 346:0.6167 347:0.6167 348:0.6333 349:0.6833 350:0.7333 351:0.8 352:0.55 353:0.55 354:0.55 355:0.5333 356:0.5333 357:0.5333 358:0.5333 359:0.5333 360:0.5333
0.1593974518798796 1:1 2:1 3:1 4:1 5:1 6:1 7:1 8:1 9:1 10:1 11:1 12:1 13:1 14:1 15:1 16:1 17:1 18:1 19:1 20:1 21:0.3167 22:0.3 23:0.2833 24:0.2833 25:0.2667 26:0.25 27:0.25 28:0.2667 29:0.2667 30:0.25 31:0.2667 32:0.2667 33:0.2667 34:0.2667 35:0.2667 36:0.2667 37:0.25 38:0.2667 39:0.2667 40:0.25 41:0.25 42:0.2667 43:0.2667 44:0.2667 45:0.2667 46:0.2833 47:0.2833 48:0.2833 49:0.2833 50:0.3 51:0.3 52:0.3 53:0.3 54:0.3 55:0.3 56:0.3 57:0.3333 58:0.3333 59:0.3333 60:0.3333 61:0.3833 62:0.4 63:0.4 64:0.4167 65:0.4333 66:0.45 67:0.4667 68:0.4833 69:0.5167 70:0.5333 71:0.55 72:0.5833 73:0.6167 74:0.65 75:0.7167 76:0.7667 77:0.7833 78:0.9167 79:0.9667 80:0.9667 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:0.8 104:0.8 105:0.7167 106:0.6833 107:0.65 108:0.6167 109:0.6167 110:0.5333 111:0.5167 112:0.4833 113:0.4667 114:0.4667 115:0.4667 116:0.4667 117:0.4333 118:0.4167 119:0.4 120:0.4 121:0.35 122:0.3333 123:0.3333 124:0.3167 125:0.3167 126:0.3 127:0.3 128:0.3 129:0.2833 130:0.2833 131:0.2833 132:0.2667 133:0.2667 134:0.2667 135:0.25 136:0.25 137:0.25 138:0.25 139:0.25 140:0.2333 141:0.2333 142:0.19294737 143:0.19294737 144:0.19294737 145:0.17547368 146:0.17547368 147:0.17547368 148:0.17547368 149:0.17547368 150:0.17547368 151:0.17547368 152:0.17547368 153:0.17547368 154:0.17547368 155:0.15789474 156:0.15789474 157:0.14285408 158:0.14285408 159:0.14285408 160:0.14285408 161:0.14285408 162:0.14285408 163:0.14285408 164:0.14285408 165:0.14285408 166:0.14285408 167:0.14285408 168:0.14285408 169:0.14285408 170:0.14285408 171:0.14285408 172:0.14285408 173:0.14285408 174:0.14285408 175:0.14285408 176:0.14285408 177:0.14285408 178:0.14285408 179:0.14285408 180:0.14285408 181:0.14285408 182:0.14285408 183:0.14285408 184:0.14285408 185:0.14285408 186:0.14285408 187:0.14285408 188:0.14285408 189:0.14285408 190:0.14285408 191:0.14285408 192:0.14285408 193:0.14285408 194:0.14285408 195:0.14285408 196:0.14285408 197:0.14285408 198:0.14285408 199:0.14285408 200:0.14285408 201:0.14285408 202:0.14285408 203:0.14285408 204:0.14285408 205:0.14285408 206:0.14285408 207:0.14285408 208:0.160747 209:0.160747 210:0.160747 211:0.160747 212:0.160747 213:0.160747 214:0.160747 215:0.160747 216:0.160747 217:0.160747 218:0.17853278 219:0.17853278 220:0.17853278 221:0.2333 222:0.2333 223:0.25 224:0.25 225:0.25 226:0.25 227:0.25 228:0.2667 229:0.2667 230:0.2667 231:0.2833 232:0.2833 233:0.2833 234:0.3 235:0.3 236:0.3 237:0.3167 238:0.3167 239:0.3333 240:0.3333 241:0.35 242:0.35 243:0.3667 244:0.35 245:0.4 246:0.4167 247:0.4333 248:0.45 249:0.4667 250:0.4833 251:0.5167 252:0.5333 253:0.5667 254:0.6 255:0.6333 256:0.6667 257:0.7167 258:0.7667 259:0.8333 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:0.9167 284:0.85 285:0.7833 286:0.7333 287:0.7 288:0.65 289:0.6167 290:0.5833 291:0.55 292:0.5333 293:0.5167 294:0.4833 295:0.4667 296:0.45 297:0.4333 298:0.4167 299:0.4 300:0.4 301:0.3833 302:0.3667 303:0.3667 304:0.35 305:0.35 306:0.3333 307:0.3333 308:0.3167 309:0.3167 310:0.3 311:0.3 312:0.3 313:0.2833 314:0.2833 315:0.2833 316:0.2833 317:0.2667 318:0.2667 319:0.2667 320:0.2667 321:0.25 322:0.25 323:0.25 324:0.25 325:0.25 326:0.25 327:0.2333 328:0.2333 329:0.2333 330:0.2333 331:0.2333 332:0.2333 333:0.2333 334:0.2333 335:0.2333 336:0.2333 337:0.2333 338:0.2333 339:0.2333 340:0.2333 341:0.2333 342:0.2333 343:0.2333 344:0.2333 345:0.2333 346:0.2333 347:0.2333 348:0.2333 349:0.2333 350:0.2333 351:0.2333 352:0.3 353:0.3333 354:0.3333 355:0.3333 356:0.3333 357:0.3333 358:0.3333 359:0.3333 360:1
0.5026215130059279 1:1 2:1 3:1 4:1 5:1 6:1 7:1 8:1 9:1 10:1 11:1 12:1 13:1 14:0.25 15:0.25 16:0.25 17:0.25 18:0.25 19:0.2333 20:0.2333 21:0.25 22:0.25 23:0.2333 24:0.25 25:0.25 26:0.25 27:0.25 28:0.25 29:0.25 30:0.25 31:0.25 32:0.25 33:0.25 34:0.25 35:0.2333 36:0.25 37:0.25 38:0.25 39:0.25 40:0.25 41:0.25 42:0.2667 43:0.2667 44:0.2667 45:0.2667 46:0.2833 47:0.2833 48:0.2833 49:0.2833 50:0.3 51:0.3 52:0.3 53:0.3 54:0.3 55:0.3 56:0.3 57:0.35 58:0.35 59:0.3667 60:0.3667 61:0.3833 62:0.4 63:0.4 64:0.4167 65:0.4333 66:0.45 67:0.4667 68:0.4833 69:0.5167 70:0.5333 71:0.55 72:0.5833 73:0.6167 74:0.65 75:0.7333 76:0.7333 77:0.7833 78:0.8167 79:0.8333 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:0.75 104:0.7667 105:0.7167 106:0.7 107:0.7 108:0.65 109:0.5833 110:0.5333 111:0.5167 112:0.5 113:0.5 114:0.4833 115:0.4667 116:0.45 117:0.45 118:0.3833 119:0.3833 120:0.3833 121:0.3833 122:0.3667 123:0.3667 124:0.35 125:0.35 126:0.3 127:0.3 128:0.3 129:0.2833 130:0.2833 131:0.2833 132:0.2667 133:0.2667 134:0.2667 135:0.2667 136:0.2667 137:0.2667 138:0.2667 139:0.2667 140:0.2333 141:0.2333 142:0.19294737 143:0.19294737 144:0.19294737 145:0.17547368 146:0.17547368 147:0.17547368 148:0.17547368 149:0.17547368 150:0.17547368 151:0.17547368 152:0.17547368 153:0.17547368 154:0.17547368 155:0.15789474 156:0.15789474 157:0.14285408 158:0.14285408 159:0.14285408 160:0.14285408 161:0.14285408 162:0.14285408 163:0.14285408 164:0.14285408 165:0.14285408 166:0.14285408 167:0.14285408 168:0.14285408 169:0.14285408 170:0.14285408 171:0.14285408 172:0.14285408 173:0.14285408 174:0.14285408 175:0.14285408 176:0.14285408 177:0.14285408 178:0.14285408 179:0.14285408 180:0.14285408 181:0.14285408 182:0.14285408 183:0.14285408 184:0.14285408 185:0.14285408 186:0.14285408 187:0.14285408 188:0.14285408 189:0.14285408 190:0.14285408 191:0.14285408 192:0.14285408 193:0.14285408 194:0.14285408 195:0.14285408 196:0.14285408 197:0.14285408 198:0.14285408 199:0.14285408 200:0.14285408 201:0.14285408 202:0.14285408 203:0.14285408 204:0.14285408 205:0.14285408 206:0.14285408 207:0.14285408 208:0.160747 209:0.160747 210:0.160747 211:0.160747 212:0.160747 213:0.160747 214:0.160747 215:0.160747 216:0.160747 217:0.160747 218:0.17853278 219:0.17853278 220:0.17853278 221:0.2333 222:0.2333 223:0.25 224:0.25 225:0.25 226:0.25 227:0.25 228:0.2667 229:0.2667 230:0.2667 231:0.2833 232:0.2833 233:0.2833 234:0.3 235:0.3 236:0.3 237:0.3167 238:0.3167 239:0.3333 240:0.3333 241:0.35 242:0.3667 243:0.3667 244:0.3833 245:0.3833 246:0.3833 247:0.3833 248:0.3833 249:0.4667 250:0.4833 251:0.5167 252:0.5333 253:0.5667 254:0.6 255:0.6333 256:0.6667 257:0.7167 258:0.7667 259:0.8333 260:0.9167 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:0.9167 284:0.85 285:0.7833 286:0.7333 287:0.7 288:0.65 289:0.6167 290:0.5833 291:0.55 292:0.5333 293:0.5167 294:0.4833 295:0.4667 296:0.45 297:0.4333 298:0.4167 299:0.4 300:0.4 301:0.3833 302:0.3667 303:0.3667 304:0.35 305:0.35 306:0.3333 307:0.3333 308:0.3167 309:0.3167 310:0.3 311:0.3 312:0.3 313:0.2833 314:0.2833 315:0.2833 316:0.2833 317:0.2667 318:0.2667 319:0.2667 320:0.2667 321:0.25 322:0.25 323:0.25 324:0.25 325:0.25 326:0.25 327:0.25 328:0.25 329:0.25 330:0.25 331:0.25 332:0.25 333:0.25 334:0.25 335:0.25 336:0.25 337:0.25 338:0.25 339:0.25 340:0.25 341:0.2667 342:0.3 343:0.3 344:0.3 345:0.3 346:0.3 347:0.3 348:0.3333 349:0.3333 350:0.3333 351:0.35 352:0.3333 353:0.3167 354:1 355:1 356:1 357:1 358:1 359:1 360:1
1.159492380339165 1:1 2:1 3:1 4:1 5:1 6:1 7:1 8:1 9:1 10:1 11:1 12:0.2167 13:0.2167 14:0.2167 15:0.2167 16:0.2167 17:0.2 18:0.2 19:0.1833 20:0.1833 21:0.1833 22:0.2 23:0.2 24:0.1833 25:0.1833 26:0.2 27:0.2 28:0.2 29:0.1833 30:0.2 31:0.2 32:0.2 33:0.1833 34:0.1833 35:0.1833 36:0.2 37:0.2 38:0.1833 39:0.1833 40:0.1833 41:0.2 42:0.2 43:0.2 44:0.2 45:0.2 46:0.2 47:0.2167 48:0.2167 49:0.2167 50:0.2167 51:0.2167 52:0.2333 53:0.2333 54:0.2333 55:0.25 56:0.25 57:0.25 58:0.25 59:0.25 60:0.25 61:0.25 62:0.25 63:0.3 64:0.3167 65:0.3167 66:0.3333 67:0.35 68:0.3667 69:0.4167 70:0.4 71:0.4167 72:0.4333 73:0.45 74:0.4833 75:0.4833 76:0.4833 77:0.5833 78:0.6333 79:0.6667 80:0.6667 81:0.7167 82:0.9 83:0.9 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:0.7667 108:0.7667 109:0.7667 110:0.7833 111:0.7 112:0.6667 113:0.65 114:0.6167 115:0.6 116:0.5667 117:0.5667 118:0.5333 119:0.5333 120:0.5 121:0.4833 122:0.4667 123:0.45 124:0.45 125:0.4333 126:0.4167 127:0.4167 128:0.4 129:0.4 130:0.3833 131:0.3833 132:0.3667 133:0.3667 134:0.3667 135:0.35 136:0.35 137:0.35 138:0.3333 139:0.3333 140:0.3333 141:0.3167 142:0.28073684 143:0.28073684 144:0.28073684 145:0.26315789 146:0.26315789 147:0.26315789 148:0.26315789 149:0.26315789 150:0.22810526 151:0.22810526 152:0.22810526 153:0.22810526 154:0.22810526 155:0.22810526 156:0.22810526 157:0.21431862 158:0.1964257 159:0.1964257 160:0.1964257 161:0.1964257 162:0.1964257 163:0.1964257 164:0.1964257 165:0.1964257 166:0.1964257 167:0.1964257 168:0.1964257 169:0.1964257 170:0.1964257 171:0.1964257 172:0.1964257 173:0.1964257 174:0.1964257 175:0.1964257 176:0.1964257 177:0.1964257 178:0.1964257 179:0.1964257 180:0.1964257 181:0.1964257 182:0.1964257 183:0.1964257 184:0.1964257 185:0.1964257 186:0.1964257 187:0.1964257 188:0.1964257 189:0.1964257 190:0.1964257 191:0.1964257 192:0.1964257 193:0.1964257 194:0.1964257 195:0.1964257 196:0.1964257 197:0.1964257 198:0.1964257 199:0.1964257 200:0.1964257 201:0.1964257 202:0.1964257 203:0.1964257 204:0.1964257 205:0.21431862 206:0.21431862 207:0.21431862 208:0.21431862 209:0.21431862 210:0.21431862 211:0.21431862 212:0.21431862 213:0.2321044 214:0.2321044 215:0.2321044 216:0.2321044 217:0.2321044 218:0.2321044 219:0.24999732 220:0.24999732 221:0.3 222:0.3 223:0.3167 224:0.3167 225:0.3167 226:0.3167 227:0.3333 228:0.3333 229:0.3333 230:0.35 231:0.35 232:0.3667 233:0.3667 234:0.3833 235:0.3833 236:0.4 237:0.4 238:0.4167 239:0.4167 240:0.4167 241:0.4167 242:0.4167 243:0.4167 244:0.4167 245:0.5167 246:0.5333 247:0.55 248:0.5667 249:0.6 250:0.6333 251:0.65 252:0.6833 253:0.7333 254:0.7667 255:0.8167 256:0.8667 257:0.9333 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:0.95 281:0.8167 282:0.7333 283:0.6833 284:0.6333 285:0.5833 286:0.55 287:0.5167 288:0.4833 289:0.45 290:0.4333 291:0.4167 292:0.4 293:0.3833 294:0.3667 295:0.35 296:0.3333 297:0.3167 298:0.3167 299:0.3 300:0.3 301:0.2833 302:0.2833 303:0.2667 304:0.2667 305:0.25 306:0.25 307:0.25 308:0.2333 309:0.2333 310:0.2333 311:0.2167 312:0.2167 313:0.2167 314:0.2167 315:0.2167 316:0.2 317:0.2 318:0.2167 319:0.2167 320:0.2167 321:0.2 322:0.2167 323:0.2167 324:0.2167 325:0.2 326:0.2167 327:0.2167 328:0.2167 329:0.2167 330:0.2 331:0.2167 332:0.2167 333:0.2 334:0.2 335:0.2167 336:0.2167 337:0.2167 338:0.2667 339:0.2667 340:0.2667 341:0.2667 342:0.2667 343:0.2667 344:0.2667 345:0.2667 346:0.2667 347:0.2667 348:0.2667 349:0.3333 350:0.3333 351:0.3333 352:0.3333 353:0.3167 354:0.3333 355:1 356:1 357:1 358:1 359:1 360:1
2 1:0.25 2:0.25 3:0.3 4:0.3 5:0.3 6:0.3333 7:0.3333 8:0.3667 9:0.3667 10:0.4 11:0.4 12:0.4167 13:0.4167 14:0.9167 15:0.9 16:0.9 17:0.9 18:0.9 19:0.9 20:0.9 21:1 22:1 23:1 24:0.1833 25:0.1833 26:0.1833 27:0.1833 28:0.1833 29:0.1833 30:0.1833 31:0.1833 32:0.1833 33:0.1833 34:0.1833 35:0.1833 36:0.1833 37:0.1833 38:0.1833 39:0.1833 40:0.1833 41:0.1833 42:0.1833 43:0.1833 44:0.1833 45:0.1833 46:0.1833 47:0.1833 48:0.1833 49:0.1833 50:0.1833 51:0.1833 52:0.1833 53:0.1833 54:0.1833 55:0.1833 56:0.1833 57:0.2 58:0.2 59:0.2 60:0.2167 61:0.2167 62:0.2167 63:0.2333 64:0.2333 65:0.25 66:0.25 67:0.2667 68:0.2833 69:0.2833 70:0.3 71:0.3167 72:0.3333 73:0.35 74:0.3667 75:0.3833 76:0.4167 77:0.4167 78:0.4167 79:0.4333 80:0.4833 81:0.5167 82:0.5833 83:0.65 84:0.75 85:0.8667 86:0.9333 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:0.8 111:0.8 112:0.7667 113:0.75 114:0.7 115:0.7167 116:0.65 117:0.6333 118:0.6 119:0.5833 120:0.5667 121:0.55 122:0.5333 123:0.5167 124:0.5 125:0.5 126:0.4833 127:0.4667 128:0.4667 129:0.45 130:0.4333 131:0.4333 132:0.4167 133:0.4167 134:0.4 135:0.4 136:0.4 137:0.3833 138:0.3833 139:0.3833 140:0.3667 141:0.3667 142:0.33336842 143:0.31578947 144:0.31578947 145:0.31578947 146:0.31578947 147:0.29821053 148:0.29821053 149:0.29821053 150:0.29821053 151:0.29821053 152:0.29821053 153:0.28073684 154:0.28073684 155:0.28073684 156:0.26315789 157:0.24999732 158:0.24999732 159:0.24999732 160:0.2321044 161:0.2321044 162:0.2321044 163:0.2321044 164:0.2321044 165:0.2321044 166:0.2321044 167:0.2321044 168:0.2321044 169:0.2321044 170:0.2321044 171:0.2321044 172:0.2321044 173:0.2321044 174:0.2321044 175:0.2321044 176:0.2321044 177:0.2321044 178:0.2321044 179:0.2321044 180:0.2321044 181:0.2321044 182:0.2321044 183:0.2321044 184:0.2321044 185:0.2321044 186:0.2321044 187:0.2321044 188:0.2321044 189:0.2321044 190:0.2321044 191:0.2321044 192:0.2321044 193:0.2321044 194:0.2321044 195:0.2321044 196:0.2321044 197:0.2321044 198:0.2321044 199:0.2321044 200:0.2321044 201:0.2321044 202:0.2321044 203:0.24999732 204:0.24999732 205:0.24999732 206:0.24999732 207:0.24999732 208:0.24999732 209:0.24999732 210:0.24999732 211:0.26789024 212:0.26789024 213:0.26789024 214:0.26789024 215:0.26789024 216:0.26789024 217:0.28567602 218:0.28567602 219:0.28567602 220:0.28567602 221:0.35 222:0.35 223:0.35 224:0.3667 225:0.3667 226:0.3667 227:0.3833 228:0.3833 229:0.3833 230:0.4 231:0.4 232:0.4 233:0.4 234:0.4 235:0.4 236:0.4 237:0.4 238:0.4833 239:0.4833 240:0.5 241:0.5167 242:0.5333 243:0.55 244:0.55 245:0.55 246:0.5667 247:0.6 248:0.6167 249:0.65 250:0.6667 251:0.7 252:0.7333 253:0.7833 254:0.8167 255:0.8667 256:0.9333 257:0.9667 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:0.9 280:0.8 281:0.7167 282:0.65 283:0.6 284:0.55 285:0.5167 286:0.4833 287:0.3833 288:0.3667 289:0.35 290:0.3333 291:0.3167 292:0.3 293:0.2833 294:0.2833 295:0.2667 296:0.25 297:0.25 298:0.2333 299:0.2333 300:0.2167 301:0.2167 302:0.2167 303:0.2 304:0.2 305:0.2 306:0.1833 307:0.1833 308:0.1833 309:0.1833 310:0.1833 311:0.1667 312:0.1667 313:0.1667 314:0.1667 315:0.1667 316:0.1667 317:0.15 318:0.1667 319:0.1667 320:0.1667 321:0.1667 322:0.1667 323:0.1667 324:0.1667 325:0.1667 326:0.1667 327:0.1667 328:0.1667 329:0.1667 330:0.1667 331:0.1667 332:0.1667 333:0.1667 334:0.1667 335:0.1667 336:0.1667 337:0.1667 338:0.1667 339:0.15 340:0.1667 341:0.1667 342:0.1833 343:0.1833 344:0.1833 345:0.1833 346:0.1833 347:0.1833 348:0.1833 349:0.2 350:0.2167 351:0.2167 352:0.2 353:0.2 354:0.2 355:0.2167 356:0.2167 357:0.2167 358:0.2167 359:0.2333 360:0.25
1.039765474099854 1:1 2:1 3:1 4:1 5:1 6:0.4667 7:0.45 8:0.3333 9:0.3 10:0.3 11:0.3 12:0.3 13:0.3 14:0.25 15:0.25 16:0.25 17:0.25 18:0.25 19:0.25 20:0.25 21:0.25 22:0.25 23:0.25 24:0.2333 25:0.2167 26:0.2167 27:0.2167 28:0.2167 29:0.2333 30:0.2167 31:0.2167 32:0.2333 33:0.2333 34:0.2167 35:0.2167 36:0.2333 37:0.2333 38:0.2167 39:0.2 40:0.2 41:0.2 42:0.2167 43:0.2167 44:0.2 45:0.2 46:0.35 47:0.35 48:0.2 49:0.2 50:0.2 51:0.2167 52:0.2167 53:0.2 54:0.2 55:0.2167 56:0.2 57:0.2 58:0.2 59:0.2 60:0.2167 61:0.2167 62:0.2167 63:0.2167 64:0.2167 65:0.2167 66:0.2167 67:0.2167 68:0.2167 69:0.2167 70:0.2167 71:0.2167 72:0.5333 73:0.5333 74:0.5333 75:0.5333 76:0.5333 77:0.5333 78:0.5333 79:0.5333 80:0.5333 81:0.5333 82:0.5333 83:0.5333 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:0.45 113:0.45 114:0.45 115:0.45 116:0.45 117:0.45 118:0.45 119:0.45 120:0.45 121:0.45 122:0.45 123:0.45 124:0.45 125:0.3167 126:0.3167 127:0.3167 128:0.3167 129:0.3167 130:0.3 131:0.3167 132:0.3167 133:0.3167 134:0.3167 135:0.3167 136:0.3167 137:0.3167 138:0.3167 139:0.3167 140:0.3167 141:0.3167 142:0.26315789 143:0.64915789 144:0.64915789 145:0.31578947 146:0.31578947 147:0.31578947 148:0.31578947 149:0.31578947 150:0.31578947 151:0.31578947 152:0.31578947 153:0.19294737 154:0.19294737 155:0.19294737 156:0.17547368 157:0.160747 158:0.160747 159:0.17853278 160:0.17853278 161:0.17853278 162:0.160747 163:0.17853278 164:0.17853278 165:0.17853278 166:0.160747 167:0.17853278 168:0.17853278 169:0.17853278 170:0.160747 171:0.17853278 172:0.160747 173:0.160747 174:0.160747 175:0.17853278 176:0.26789024 177:0.26789024 178:0.26789024 179:0.26789024 180:0.26789024 181:0.26789024 182:0.26789024 183:0.26789024 184:0.26789024 185:0.26789024 186:0.4286051 187:0.4286051 188:0.4286051 189:0.4286051 190:0.21431862 191:0.1964257 192:0.1964257 193:0.1964257 194:0.1964257 195:0.1964257 196:0.1964257 197:0.1964257 198:0.1964257 199:0.1964257 200:0.1964257 201:0.1964257 202:0.1964257 203:0.1964257 204:0.1964257 205:0.1964257 206:0.1964257 207:0.1964257 208:0.1964257 209:0.1964257 210:0.1964257 211:0.1964257 212:0.26789024 213:0.21431862 214:0.21431862 215:0.26789024 216:0.21431862 217:0.1964257 218:0.21431862 219:0.26789024 220:0.1964257 221:0.25 222:0.35 223:0.35 224:0.35 225:0.35 226:0.35 227:0.35 228:0.35 229:0.35 230:0.35 231:0.35 232:0.35 233:0.35 234:0.35 235:0.4667 236:0.4667 237:0.4667 238:0.4667 239:0.4667 240:0.4667 241:0.4667 242:0.4667 243:0.4667 244:0.4667 245:0.4667 246:0.6 247:0.6 248:0.6 249:0.6 250:0.6 251:0.6 252:0.75 253:0.75 254:0.75 255:0.75 256:0.75 257:0.9 258:0.9 259:0.9 260:0.9 261:0.9 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:0.25 274:0.25 275:0.25 276:0.25 277:0.2333 278:0.2333 279:0.2333 280:0.2333 281:0.2333 282:0.2333 283:0.25 284:0.25 285:0.2333 286:0.25 287:0.25 288:0.25 289:0.2333 290:0.2333 291:0.45 292:0.2333 293:0.2333 294:0.2333 295:0.2333 296:0.3167 297:0.3167 298:0.3167 299:0.3167 300:0.3167 301:0.3167 302:0.3167 303:0.3167 304:0.3167 305:0.3167 306:0.3167 307:0.3 308:0.3167 309:0.3167 310:0.3167 311:0.3167 312:0.3667 313:0.3667 314:0.3667 315:0.35 316:0.35 317:0.35 318:0.3333 319:0.3333 320:0.3333 321:0.3333 322:0.3333 323:0.3333 324:0.3167 325:0.3 326:0.3 327:0.3 328:0.3 329:0.3 330:0.3 331:0.3 332:0.3 333:0.3 334:0.3 335:0.3 336:0.3 337:0.3 338:0.3 339:0.3 340:0.3 341:0.3 342:0.3 343:0.3 344:0.3167 345:0.3167 346:0.3167 347:0.3167 348:0.3333 349:0.35 350:0.3833 351:0.6667 352:0.6667 353:0.6667 354:0.95 355:0.9833 356:1 357:1 358:1 359:1 360:1
0.3143866473536532 1:0.2333 2:0.2333 3:0.2333 4:0.2333 5:0.1333 6:0.1333 7:0.1333 8:0.1333 9:0.1333 10:0.1333 11:0.1333 12:0.1333 13:0.1333 14:0.1333 15:0.15 16:0.15 17:0.15 18:0.1333 19:0.1333 20:0.1333 21:0.15 22:0.15 23:0.15 24:0.1333 25:0.1333 26:0.1333 27:0.1333 28:0.15 29:0.15 30:0.1333 31:0.1333 32:0.1333 33:0.1333 34:0.1333 35:0.1333 36:0.1333 37:0.15 38:0.15 39:0.2 40:0.2 41:0.2 42:0.2 43:0.1833 44:0.2 45:0.2 46:0.2 47:0.2 48:0.2 49:0.2 50:0.2 51:0.2 52:0.2 53:0.2 54:0.2 55:0.2 56:0.2 57:0.2 58:0.2 59:0.2 60:0.2 61:0.2 62:0.1833 63:0.2 64:0.2 65:0.25 66:0.25 67:0.4 68:0.4 69:0.4 70:0.4 71:0.4 72:0.4 73:0.4 74:0.4 75:0.3833 76:0.4333 77:0.4333 78:0.4333 79:0.4333 80:0.4333 81:0.4333 82:0.7333 83:0.7333 84:0.8667 85:0.8667 86:0.8833 87:0.8833 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:0.8333 102:0.8333 103:0.8333 104:0.7333 105:0.7333 106:0.7333 107:0.5667 108:0.5667 109:0.5667 110:0.5667 111:0.5667 112:0.4333 113:0.4167 114:0.4167 115:0.4167 116:0.3 117:0.2833 118:0.2833 119:0.2833 120:0.2833 121:0.2833 122:0.2833 123:0.2667 124:0.2667 125:0.2667 126:0.2667 127:0.2667 128:0.2667 129:0.2667 130:0.2667 131:0.2667 132:0.2667 133:0.2667 134:0.2667 135:0.2667 136:0.2667 137:0.2667 138:0.2667 139:0.2667 140:0.2667 141:0.3833 142:0.35084211 143:0.35084211 144:0.35084211 145:0.35084211 146:0.26315789 147:0.26315789 148:0.26315789 149:0.26315789 150:0.26315789 151:0.26315789 152:0.26315789 153:0.26315789 154:0.26315789 155:0.26315789 156:0.26315789 157:0.24999732 158:0.24999732 159:0.24999732 160:0.24999732 161:0.24999732 162:0.24999732 163:0.24999732 164:0.37503348 165:0.39281926 166:0.39281926 167:0.39281926 168:0.39281926 169:0.39281926 170:0.39281926 171:0.39281926 172:0.41071218 173:0.41071218 174:0.48217672 175:0.48217672 176:0.48217672 177:0.48217672 178:0.48217672 179:0.48217672 180:0.48217672 181:0.57142704 182:0.67857028 183:0.85717806 184:0.82139222 185:0.82139222 186:0.78571352 187:0.78571352 188:0.78571352 189:0.78571352 190:0.78571352 191:0.78571352 192:0.80360644 193:0.80360644 194:0.80360644 195:0.83928514 196:0.83928514 197:0.83928514 198:0.83928514 199:0.82139222 200:0.82139222 201:0.82139222 202:0.82139222 203:0.78571352 204:0.78571352 205:0.78571352 206:0.78571352 207:0.78571352 208:0.78571352 209:0.82139222 210:0.82139222 211:0.83928514 212:0.83928514 213:0.83928514 214:0.83928514 215:0.80360644 216:0.60710574 217:0.60710574 218:0.60710574 219:0.60710574 220:0.48217672 221:0.5167 222:0.5167 223:0.5167 224:0.5167 225:0.5167 226:0.4167 227:0.4167 228:0.4 229:0.4167 230:0.4 231:0.4167 232:0.4167 233:0.4167 234:0.4167 235:0.4 236:0.4167 237:0.4 238:0.55 239:0.5667 240:0.55 241:0.4167 242:0.4167 243:0.4333 244:0.4167 245:0.4333 246:0.4167 247:0.4167 248:0.4167 249:0.4167 250:0.4167 251:0.4167 252:0.4333 253:0.5833 254:0.5833 255:0.5833 256:0.5833 257:0.5833 258:0.75 259:0.75 260:0.75 261:0.9167 262:0.9167 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:0.6 283:0.6 284:0.6 285:0.6 286:0.4333 287:0.45 288:0.4333 289:0.4333 290:0.4333 291:0.4333 292:0.3 293:0.3 294:0.3 295:0.3 296:0.3 297:0.3 298:0.3 299:0.3 300:0.3 301:0.3 302:0.3 303:0.3 304:0.3 305:0.3 306:0.3 307:0.3 308:0.3167 309:0.4 310:0.4 311:0.1667 312:0.1667 313:0.1667 314:0.1667 315:0.1667 316:0.1667 317:0.15 318:0.1667 319:0.1667 320:0.1667 321:0.1667 322:0.1667 323:0.1667 324:0.1667 325:0.1667 326:0.1667 327:0.1667 328:0.1667 329:0.1667 330:0.1667 331:0.1667 332:0.1667 333:0.1667 334:0.1667 335:0.1667 336:0.1667 337:0.1667 338:0.1667 339:0.15 340:0.2667 341:0.2667 342:0.2833 343:0.35 344:0.2333 345:0.2333 346:0.2333 347:0.2333 348:0.2333 349:0.2333 350:0.2333 351:0.2333 352:0.2333 353:0.2333 354:0.2333 355:0.2333 356:0.2333 357:0.2333 358:0.2333 359:0.2333 360:0.2333
0.2290950938655975 1:0.1333 2:0.1333 3:0.1333 4:0.1333 5:0.1333 6:0.1333 7:0.1333 8:0.1333 9:0.1333 10:0.1333 11:0.1333 12:0.1333 13:0.1333 14:0.1333 15:0.1333 16:0.1333 17:0.1333 18:0.1333 19:0.1333 20:0.1333 21:0.1333 22:0.1333 23:0.1333 24:0.1333 25:0.1333 26:0.1333 27:0.1333 28:0.1333 29:0.1333 30:0.2667 31:0.2667 32:0.25 33:0.25 34:0.25 35:0.4 36:0.2167 37:0.2167 38:0.2167 39:0.2 40:0.2 41:0.2 42:0.2167 43:0.2167 44:0.2 45:0.2 46:0.2167 47:0.2167 48:0.2 49:0.2 50:0.2 51:0.2 52:0.2 53:0.2 54:0.2 55:0.2 56:0.2 57:0.2 58:0.2 59:0.2 60:0.2 61:0.2 62:0.2 63:0.2 64:0.2 65:0.2 66:0.2 67:0.2 68:0.2 69:0.2 70:0.2 71:0.35 72:0.3333 73:0.35 74:0.35 75:0.3333 76:0.4667 77:0.4833 78:0.4833 79:0.4833 80:0.4833 81:0.4833 82:0.4833 83:0.4833 84:0.4667 85:0.6167 86:0.7167 87:0.7167 88:0.95 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:0.8333 106:0.6667 107:0.6667 108:0.6667 109:0.6667 110:0.6667 111:0.5167 112:0.5167 113:0.3833 114:0.3833 115:0.3833 116:0.3833 117:0.3833 118:0.35 119:0.3333 120:0.35 121:0.35 122:0.35 123:0.35 124:0.35 125:0.35 126:0.35 127:0.3333 128:0.35 129:0.35 130:0.3333 131:0.35 132:0.35 133:0.35 134:0.4 135:0.4 136:0.4 137:0.4 138:0.3333 139:0.3333 140:0.3333 141:0.3333 142:0.31578947 143:0.21052632 144:0.21052632 145:0.21052632 146:0.21052632 147:0.21052632 148:0.21052632 149:0.21052632 150:0.21052632 151:0.21052632 152:0.21052632 153:0.21052632 154:0.21052632 155:0.21052632 156:0.21052632 157:0.1964257 158:0.1964257 159:0.1964257 160:0.1964257 161:0.21431862 162:0.21431862 163:0.1964257 164:0.1964257 165:0.21431862 166:0.2321044 167:0.28567602 168:0.28567602 169:0.28567602 170:0.28567602 171:0.28567602 172:0.32146186 173:0.32146186 174:0.32146186 175:0.32146186 176:0.32146186 177:0.32146186 178:0.41071218 179:0.41071218 180:0.4286051 181:0.44639088 182:0.48217672 183:0.48217672 184:0.62499866 185:0.67857028 186:0.87496384 187:1 188:0.98210708 189:0.98210708 190:0.98210708 191:0.98210708 192:0.98210708 193:1 194:1 195:1 196:1 197:1 198:1 199:1 200:1 201:1 202:1 203:1 204:1 205:1 206:1 207:1 208:1 209:1 210:0.75003482 211:0.75003482 212:0.60710574 213:0.60710574 214:0.60710574 215:0.60710574 216:0.60710574 217:0.55353412 218:0.48217672 219:0.4642838 220:0.4642838 221:0.4833 222:0.4667 223:0.3833 224:0.3667 225:0.3667 226:0.3667 227:0.35 228:0.3667 229:0.3667 230:0.3667 231:0.3667 232:0.3667 233:0.3667 234:0.3667 235:0.35 236:0.3667 237:0.3667 238:0.3667 239:0.3667 240:0.3667 241:0.3667 242:0.3667 243:0.3667 244:0.3833 245:0.45 246:0.45 247:0.45 248:0.4333 249:0.45 250:0.4333 251:0.45 252:0.4333 253:0.45 254:0.4333 255:0.45 256:0.4333 257:0.4667 258:0.4667 259:0.4667 260:0.4667 261:0.4667 262:0.4667 263:0.4667 264:0.4667 265:0.4667 266:0.4667 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:0.95 283:0.7667 284:0.5833 285:0.5833 286:0.5667 287:0.5667 288:0.5667 289:0.45 290:0.4333 291:0.4333 292:0.4333 293:0.4333 294:0.4333 295:0.4333 296:0.4333 297:0.2833 298:0.2833 299:0.2833 300:0.2833 301:0.2833 302:0.2833 303:0.2833 304:0.2833 305:0.2833 306:0.2833 307:0.2833 308:0.2833 309:0.2833 310:0.2833 311:0.2833 312:0.2833 313:0.2833 314:0.1833 315:0.1833 316:0.1833 317:0.1833 318:0.1833 319:0.1667 320:0.1667 321:0.1667 322:0.1833 323:0.1833 324:0.1833 325:0.1833 326:0.1833 327:0.1833 328:0.1833 329:0.1833 330:0.1833 331:0.1833 332:0.1833 333:0.1833 334:0.1833 335:0.1833 336:0.1667 337:0.1833 338:0.1833 339:0.1833 340:0.1667 341:0.1667 342:0.25 343:0.25 344:0.25 345:0.25 346:0.25 347:0.25 348:0.25 349:0.25 350:0.25 351:0.25 352:0.25 353:0.15 354:0.15 355:0.15 356:0.15 357:0.15 358:0.1333 359:0.1333 360:0.1333
0.05004219948586586 1:0.06667 2:0.06667 3:0.06667 4:0.06667 5:0.06667 6:0.06667 7:0.06667 8:0.06667 9:0.06667 10:0.06667 11:0.06667 12:0.06667 13:0.06667 14:0.06667 15:0.06667 16:0.06667 17:0.06667 18:0.06667 19:0.06667 20:0.06667 21:0.06667 22:0.06667 23:0.06667 24:0.06667 25:0.06667 26:0.06667 27:0.06667 28:0.06667 29:0.06667 30:0.06667 31:0.06667 32:0.06667 33:0.06667 34:0.06667 35:0.06667 36:0.06667 37:0.06667 38:0.06667 39:0.08333 40:0.08333 41:0.08333 42:0.08333 43:0.08333 44:0.08333 45:0.08333 46:0.08333 47:0.08333 48:0.08333 49:0.08333 50:0.08333 51:0.08333 52:0.08333 53:0.1 54:0.08333 55:0.08333 56:0.08333 57:0.08333 58:0.08333 59:0.08333 60:0.08333 61:0.08333 62:0.08333 63:0.08333 64:0.08333 65:0.1667 66:0.1667 67:0.1667 68:0.1667 69:0.15 70:0.1667 71:0.1667 72:0.1833 73:0.1833 74:0.2 75:0.2 76:0.2167 77:0.2333 78:0.25 79:0.3 80:0.3 81:0.3 82:0.3 83:0.3 84:0.3 85:0.3 86:0.3 87:0.9333 88:0.9333 89:0.9333 90:0.7167 91:0.7167 92:0.7167 93:0.7167 94:0.7167 95:0.6167 96:0.6167 97:0.6167 98:0.4667 99:0.4167 100:0.4167 101:0.4167 102:0.4167 103:0.4167 104:0.4167 105:0.3667 106:0.3667 107:0.3667 108:0.3667 109:0.3667 110:0.3833 111:0.3667 112:0.3833 113:0.3667 114:0.3667 115:0.3667 116:0.3667 117:0.3667 118:0.3833 119:0.4 120:0.4167 121:0.3167 122:0.3167 123:0.3167 124:0.3167 125:0.3167 126:0.3167 127:0.3167 128:0.3167 129:0.3167 130:0.3167 131:0.3167 132:0.3167 133:0.3167 134:0.3167 135:0.3167 136:0.3167 137:0.4167 138:0.4167 139:0.4167 140:0.4167 141:0.4167 142:0.386 143:0.35084211 144:0.35084211 145:0.35084211 146:0.35084211 147:0.33336842 148:0.31578947 149:0.31578947 150:0.31578947 151:0.31578947 152:0.31578947 153:0.33336842 154:0.31578947 155:0.31578947 156:0.31578947 157:0.30356894 158:0.30356894 159:0.30356894 160:0.30356894 161:0.32146186 162:0.33924764 163:0.33924764 164:0.33924764 165:0.33924764 166:0.33924764 167:0.33924764 168:0.33924764 169:0.33924764 170:0.33924764 171:0.33924764 172:0.33924764 173:0.37503348 174:0.37503348 175:0.37503348 176:1 177:1 178:1 179:1 180:1 181:1 182:1 183:1 184:1 185:1 186:1 187:1 188:1 189:1 190:1 191:1 192:1 193:1 194:1 195:1 196:1 197:1 198:1 199:1 200:1 201:1 202:1 203:1 204:1 205:0.39281926 206:0.37503348 207:0.39281926 208:0.37503348 209:0.39281926 210:0.37503348 211:0.37503348 212:0.37503348 213:0.37503348 214:0.39281926 215:0.37503348 216:0.37503348 217:0.37503348 218:0.37503348 219:0.32146186 220:0.24999732 221:0.3167 222:0.3167 223:0.2333 224:0.2333 225:0.25 226:0.25 227:0.25 228:0.25 229:0.25 230:0.25 231:0.25 232:0.25 233:0.25 234:0.25 235:0.2333 236:0.25 237:0.25 238:0.25 239:0.2333 240:0.25 241:0.25 242:0.25 243:0.4 244:0.2667 245:0.2667 246:0.4 247:0.2667 248:0.2667 249:0.4 250:0.2667 251:0.2667 252:0.4 253:0.2667 254:0.2667 255:0.2667 256:0.7333 257:0.7333 258:0.7333 259:0.7333 260:0.7333 261:0.9 262:0.9 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:0.2333 278:0.2167 279:0.2167 280:0.2167 281:0.2333 282:0.2167 283:0.2167 284:0.2167 285:0.2167 286:0.2167 287:0.2 288:0.2 289:0.2 290:0.2 291:0.2 292:0.2 293:0.2 294:0.2 295:0.2167 296:0.2167 297:0.2 298:0.2 299:0.2 300:0.2167 301:0.2 302:0.2 303:0.2 304:0.2167 305:0.2 306:0.2 307:0.2 308:0.2 309:0.2 310:0.2 311:0.2 312:0.2167 313:0.2167 314:0.2 315:0.2 316:0.2 317:0.2167 318:0.2 319:0.2 320:0.2 321:0.2167 322:0.2167 323:0.2 324:0.2 325:0.1833 326:0.1833 327:0.1667 328:0.1667 329:0.15 330:0.1667 331:0.1667 332:0.1667 333:0.1667 334:0.06667 335:0.06667 336:0.06667 337:0.06667 338:0.06667 339:0.06667 340:0.06667 341:0.06667 342:0.06667 343:0.06667 344:0.06667 345:0.06667 346:0.06667 347:0.06667 348:0.06667 349:0.06667 350:0.06667 351:0.06667 352:0.06667 353:0.06667 354:0.06667 355:0.06667 356:0.06667 357:0.06667 358:0.06667 359:0.06667 360:0.06667
0.1559958130597964 1:0.1333 2:0.1333 3:0.1333 4:0.1333 5:0.1167 6:0.08333 7:0.08333 8:0.08333 9:0.08333 10:0.08333 11:0.08333 12:0.08333 13:0.1 14:0.1 15:0.1 16:0.08333 17:0.08333 18:0.08333 19:0.08333 20:0.08333 21:0.08333 22:0.08333 23:0.08333 24:0.08333 25:0.08333 26:0.08333 27:0.08333 28:0.08333 29:0.08333 30:0.08333 31:0.08333 32:0.08333 33:0.08333 34:0.1 35:0.08333 36:0.1 37:0.08333 38:0.08333 39:0.08333 40:0.08333 41:0.08333 42:0.08333 43:0.08333 44:0.08333 45:0.08333 46:0.08333 47:0.08333 48:0.08333 49:0.08333 50:0.08333 51:0.08333 52:0.08333 53:0.1 54:0.08333 55:0.08333 56:0.08333 57:0.08333 58:0.08333 59:0.08333 60:0.08333 61:0.08333 62:0.08333 63:0.08333 64:0.08333 65:0.1333 66:0.1333 67:0.15 68:0.15 69:0.2333 70:0.2333 71:0.2333 72:0.2333 73:0.2333 74:0.25 75:0.2667 76:0.2833 77:0.3 78:0.45 79:0.45 80:0.45 81:0.45 82:0.45 83:0.45 84:1 85:1 86:0.6333 87:0.6333 88:0.6333 89:0.6333 90:0.6333 91:0.6333 92:0.6333 93:0.6333 94:0.5333 95:0.5333 96:0.4667 97:0.4667 98:0.4667 99:0.4333 100:0.4333 101:0.4333 102:0.4333 103:0.4333 104:0.4333 105:0.4333 106:0.4167 107:0.4333 108:0.4167 109:0.4333 110:0.4333 111:0.4333 112:0.4667 113:0.4333 114:0.3667 115:0.3667 116:0.3667 117:0.3667 118:0.3667 119:0.3667 120:0.3667 121:0.3667 122:0.3667 123:0.3667 124:0.3667 125:0.3667 126:0.3667 127:0.3667 128:0.3667 129:0.4167 130:0.4167 131:0.4 132:0.4 133:0.4167 134:0.4 135:0.4167 136:0.4 137:0.3833 138:0.3833 139:0.3833 140:0.3667 141:0.3833 142:0.33336842 143:0.35084211 144:0.35084211 145:0.33336842 146:0.35084211 147:0.33336842 148:0.35084211 149:0.35084211 150:0.33336842 151:0.36842105 152:0.36842105 153:0.36842105 154:0.36842105 155:0.35084211 156:0.36842105 157:0.33924764 158:0.35714056 159:0.33924764 160:0.35714056 161:0.37503348 162:0.39281926 163:0.41071218 164:0.41071218 165:0.41071218 166:0.44639088 167:0.7678206 168:0.91074968 169:0.91074968 170:0.91074968 171:1 172:1 173:1 174:1 175:1 176:1 177:1 178:1 179:1 180:1 181:1 182:0.94642838 183:0.7321419 184:0.7321419 185:0.7321419 186:0.7321419 187:0.53574834 188:0.55353412 189:0.53574834 190:0.55353412 191:0.55353412 192:0.53574834 193:0.55353412 194:0.35714056 195:0.33924764 196:0.2321044 197:0.21431862 198:0.21431862 199:0.21431862 200:0.2321044 201:0.21431862 202:0.21431862 203:0.2321044 204:0.21431862 205:0.21431862 206:0.1964257 207:0.1964257 208:0.21431862 209:0.21431862 210:0.12496116 211:0.14285408 212:0.14285408 213:0.14285408 214:0.14285408 215:0.14285408 216:0.14285408 217:0.14285408 218:0.14285408 219:0.14285408 220:0.14285408 221:0.2 222:0.2 223:0.2 224:0.2 225:0.2 226:0.2 227:0.2 228:0.2 229:0.1833 230:0.2 231:0.3167 232:0.9 233:0.3167 234:0.3167 235:0.3333 236:0.3167 237:0.3167 238:0.3333 239:0.3333 240:0.3333 241:0.3333 242:0.3333 243:0.3333 244:0.3333 245:0.3167 246:0.3333 247:0.3333 248:0.3167 249:0.35 250:0.35 251:0.5 252:0.5 253:0.5 254:0.5 255:0.5 256:0.5 257:0.5 258:0.5 259:0.5 260:0.5 261:0.5167 262:0.5167 263:0.8833 264:0.8833 265:0.8667 266:1 267:1 268:1 269:0.55 270:0.55 271:0.4833 272:0.4833 273:0.35 274:0.1667 275:0.1667 276:0.1667 277:0.1667 278:0.1667 279:0.1667 280:0.1667 281:0.1667 282:0.1667 283:0.1667 284:0.2 285:0.1667 286:0.15 287:0.15 288:0.15 289:0.15 290:0.15 291:0.15 292:0.15 293:0.15 294:0.15 295:0.15 296:0.15 297:0.15 298:0.15 299:0.15 300:0.15 301:0.15 302:0.15 303:0.1667 304:0.15 305:0.15 306:0.15 307:0.15 308:0.15 309:0.15 310:0.15 311:0.15 312:0.15 313:0.15 314:0.15 315:0.1667 316:0.1667 317:0.1667 318:0.15 319:0.1667 320:0.1667 321:0.1667 322:0.15 323:0.15 324:0.15 325:0.1667 326:0.1667 327:0.1667 328:0.1667 329:0.15 330:0.1667 331:0.1667 332:0.1667 333:0.1667 334:0.1667 335:0.1667 336:0.1667 337:0.1667 338:0.1667 339:0.1667 340:0.1667 341:0.1667 342:0.15 343:0.15 344:0.15 345:0.15 346:0.15 347:0.15 348:0.15 349:0.15 350:0.15 351:0.15 352:0.15 353:0.15 354:0.15 355:0.15 356:0.15 357:0.15 358:0.1333 359:0.1333 360:0.1333
0.2963829117426119 1:0.2833 2:0.2833 3:0.2667 4:0.2667 5:0.2667 6:0.2667 7:0.2333 8:0.2167 9:0.2167 10:0.2167 11:0.2333 12:0.2167 13:0.2333 14:0.2333 15:0.2333 16:0.2167 17:0.2333 18:0.2333 19:0.2333 20:0.2167 21:0.2333 22:0.2333 23:0.2333 24:0.2167 25:0.2167 26:0.2167 27:0.2333 28:0.2333 29:0.2333 30:0.2333 31:0.2333 32:0.2333 33:0.2333 34:0.2333 35:0.3167 36:0.3167 37:0.3 38:0.3167 39:0.3167 40:0.3167 41:0.3167 42:0.3333 43:0.3333 44:0.3333 45:0.7667 46:0.5333 47:0.5333 48:0.5333 49:0.5333 50:0.5333 51:0.45 52:0.4333 53:0.4333 54:0.4333 55:0.4333 56:0.4333 57:0.4167 58:0.4333 59:0.4167 60:0.4333 61:0.4167 62:0.4167 63:0.4167 64:0.4167 65:0.4167 66:0.4167 67:0.4167 68:0.4167 69:0.4167 70:0.4167 71:0.4167 72:0.4167 73:0.4167 74:0.4167 75:0.45 76:0.4333 77:1 78:1 79:1 80:1 81:1 82:1 83:0.2667 84:0.2667 85:0.2 86:0.2 87:0.2 88:0.2 89:0.2 90:0.2 91:0.2 92:0.2 93:0.2 94:0.1833 95:0.1833 96:0.1833 97:0.1833 98:0.1833 99:0.1833 100:0.1833 101:0.1833 102:0.1833 103:0.1833 104:0.1833 105:0.1833 106:0.1833 107:0.1833 108:0.1833 109:0.1833 110:0.1833 111:0.1833 112:0.1833 113:0.1833 114:0.1833 115:0.1833 116:0.1833 117:0.1833 118:0.1833 119:0.1833 120:0.1833 121:0.1833 122:0.1833 123:0.1833 124:0.1833 125:0.1833 126:0.1833 127:0.1833 128:0.1833 129:0.1833 130:0.1833 131:0.1833 132:0.1833 133:0.1833 134:0.1833 135:0.1833 136:0.1833 137:0.1833 138:0.1833 139:0.1833 140:0.2 141:0.2167 142:0.17547368 143:0.17547368 144:0.17547368 145:0.17547368 146:0.17547368 147:0.17547368 148:0.17547368 149:0.17547368 150:0.17547368 151:0.17547368 152:0.17547368 153:0.17547368 154:0.17547368 155:0.17547368 156:0.17547368 157:0.160747 158:0.160747 159:0.160747 160:0.160747 161:0.160747 162:0.33924764 163:0.32146186 164:0.32146186 165:0.32146186 166:0.32146186 167:0.32146186 168:0.37503348 169:0.37503348 170:0.37503348 171:0.37503348 172:0.37503348 173:0.37503348 174:0.37503348 175:0.37503348 176:0.37503348 177:0.37503348 178:0.44639088 179:1 180:1 181:1 182:1 183:1 184:0.87496384 185:0.87496384 186:0.66067736 187:0.62499866 188:0.60710574 189:0.4999625 190:0.4999625 191:0.4999625 192:0.4999625 193:0.32146186 194:0.32146186 195:0.32146186 196:0.160747 197:0.14285408 198:0.14285408 199:0.12496116 200:0.12496116 201:0.12496116 202:0.14285408 203:0.14285408 204:0.12496116 205:0.12496116 206:0.14285408 207:0.14285408 208:0.14285408 209:0.12496116 210:0.12496116 211:0.14285408 212:0.14285408 213:0.12496116 214:0.12496116 215:0.12496116 216:0.12496116 217:0.12496116 218:0.12496116 219:0.12496116 220:0.12496116 221:0.2 222:0.2 223:0.1833 224:0.2 225:0.2 226:0.2 227:0.2 228:0.2 229:0.1833 230:0.2 231:0.2 232:0.2 233:0.2 234:0.2 235:0.1833 236:0.1833 237:0.2 238:0.2 239:0.2 240:0.2 241:0.2 242:0.1833 243:0.2 244:0.2 245:0.2167 246:0.2167 247:0.2167 248:0.2333 249:0.2333 250:0.2333 251:0.2333 252:0.2333 253:0.2333 254:0.25 255:0.25 256:0.25 257:0.25 258:0.25 259:0.25 260:0.25 261:0.25 262:0.25 263:0.25 264:0.25 265:0.25 266:0.25 267:0.25 268:0.25 269:0.25 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:0.7333 283:0.7333 284:0.7333 285:0.6 286:0.6 287:0.6 288:0.6 289:0.6 290:0.6 291:0.6 292:0.45 293:0.45 294:0.45 295:0.45 296:0.45 297:0.45 298:0.45 299:0.45 300:0.45 301:0.45 302:0.4667 303:0.8 304:0.8 305:0.8 306:1 307:1 308:1 309:0.9667 310:0.9167 311:0.9 312:0.9 313:0.6 314:0.6 315:0.6 316:0.6 317:0.6 318:0.6 319:0.6 320:0.6 321:0.3667 322:0.1833 323:0.1833 324:0.1833 325:0.1833 326:0.1833 327:0.1833 328:0.1833 329:0.1833 330:0.1833 331:0.1833 332:0.1833 333:0.1833 334:0.1833 335:0.1833 336:0.1833 337:0.1833 338:0.1833 339:0.1833 340:0.1833 341:0.1833 342:0.1833 343:0.1833 344:0.1833 345:0.1833 346:0.1833 347:0.1833 348:0.1833 349:0.2 350:0.2167 351:0.2333 352:0.2833 353:0.2833 354:0.2833 355:0.2833 356:0.2833 357:0.2833 358:0.2833 359:0.2833 360:0.2833
0.1731260321218585 1:0.4667 2:0.4667 3:0.2333 4:0.2167 5:0.2167 6:0.2167 7:0.2167 8:0.2167 9:0.2167 10:0.2167 11:0.2167 12:0.2167 13:0.2167 14:0.2167 15:0.2167 16:0.2167 17:0.2167 18:0.2167 19:0.2167 20:0.2167 21:0.2167 22:0.2167 23:0.2167 24:0.2167 25:0.2167 26:0.2167 27:0.2333 28:0.2333 29:0.2333 30:0.25 31:0.1833 32:0.1833 33:0.1667 34:0.1667 35:0.1667 36:0.1667 37:0.1667 38:0.1667 39:0.1667 40:0.1667 41:0.1667 42:0.1667 43:0.1667 44:0.1667 45:0.1667 46:0.1667 47:0.1667 48:0.1667 49:0.1667 50:0.1667 51:0.1667 52:0.1667 53:0.1667 54:0.1667 55:0.1667 56:0.1667 57:0.1667 58:0.1667 59:0.1667 60:0.1833 61:0.1833 62:0.1833 63:0.3 64:0.3 65:0.3 66:0.3 67:0.3 68:0.3 69:0.3 70:0.3 71:0.3 72:0.3 73:0.3 74:0.3 75:0.3 76:0.3 77:0.3 78:0.4667 79:0.4667 80:0.4667 81:0.4667 82:0.4667 83:0.4667 84:0.4667 85:0.7667 86:0.95 87:1 88:1 89:1 90:1 91:1 92:1 93:0.45 94:0.45 95:0.4333 96:0.4333 97:0.25 98:0.25 99:0.25 100:0.2667 101:0.1333 102:0.1333 103:0.1333 104:0.1333 105:0.1333 106:0.1333 107:0.1333 108:0.1333 109:0.1333 110:0.1333 111:0.1333 112:0.1333 113:0.1333 114:0.1333 115:0.1333 116:0.1333 117:0.1333 118:0.1333 119:0.1333 120:0.1333 121:0.1333 122:0.1333 123:0.1333 124:0.1333 125:0.1333 126:0.1333 127:0.1333 128:0.1333 129:0.1333 130:0.1333 131:0.1333 132:0.1333 133:0.1333 134:0.1333 135:0.1333 136:0.1333 137:0.1333 138:0.1333 139:0.1333 140:0.15 141:0.15 142:0.10526316 143:0.10526316 144:0.10526316 145:0.10526316 146:0.10526316 147:0.10526316 148:0.10526316 149:0.10526316 150:0.10526316 151:0.10526316 152:0.10526316 153:0.10526316 154:0.10526316 155:0.10526316 156:0.10526316 157:0.089282462 158:0.089282462 159:0.089282462 160:0.089282462 161:0.089282462 162:0.089282462 163:0.089282462 164:0.089282462 165:0.089282462 166:0.089282462 167:0.10717538 168:0.12496116 169:0.12496116 170:0.12496116 171:0.12496116 172:0.10717538 173:0.10717538 174:0.14285408 175:0.160747 176:0.160747 177:0.160747 178:0.160747 179:0.160747 180:0.160747 181:0.160747 182:0.160747 183:0.160747 184:0.1964257 185:0.1964257 186:0.1964257 187:0.58931996 188:0.58931996 189:0.60710574 190:0.58931996 191:0.58931996 192:0.60710574 193:0.58931996 194:0.60710574 195:0.57142704 196:0.57142704 197:0.57142704 198:0.44639088 199:0.44639088 200:0.44639088 201:0.44639088 202:0.44639088 203:0.33924764 204:0.35714056 205:0.33924764 206:0.33924764 207:0.33924764 208:0.33924764 209:0.24999732 210:0.24999732 211:0.26789024 212:0.24999732 213:0.24999732 214:0.24999732 215:0.2321044 216:0.2321044 217:0.24999732 218:0.2321044 219:0.2321044 220:0.24999732 221:0.2833 222:0.2833 223:0.3 224:0.2833 225:0.2833 226:0.3 227:0.2833 228:0.2833 229:0.2833 230:0.5167 231:0.5167 232:1 233:0.4167 234:0.4167 235:0.4167 236:0.4167 237:0.4167 238:0.3167 239:0.3167 240:0.3167 241:0.3167 242:0.3167 243:0.3167 244:0.3167 245:0.3167 246:0.3167 247:0.3167 248:0.3167 249:0.3 250:0.2833 251:0.3167 252:0.3 253:0.3 254:0.3 255:0.3 256:0.3 257:0.3 258:0.3 259:0.3 260:0.3 261:0.3 262:0.3 263:0.4333 264:0.4333 265:0.4333 266:0.4333 267:0.4333 268:0.7667 269:0.7667 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:0.9 281:0.7167 282:0.65 283:0.6 284:0.55 285:0.45 286:0.4167 287:0.4333 288:0.4167 289:0.4 290:0.4 291:0.4 292:0.4 293:0.2833 294:0.2833 295:0.2667 296:0.2667 297:0.2833 298:0.2667 299:0.2667 300:0.25 301:0.25 302:0.25 303:0.2333 304:0.2333 305:0.2333 306:0.2167 307:0.2167 308:0.2167 309:0.2167 310:0.2167 311:0.2167 312:0.2167 313:0.2167 314:0.2167 315:0.2167 316:0.2167 317:0.2167 318:0.2167 319:0.2167 320:0.2167 321:0.2167 322:0.2167 323:0.2167 324:0.2167 325:0.2167 326:0.2167 327:0.2333 328:0.2333 329:0.3 330:0.3 331:0.3333 332:0.35 333:0.3333 334:0.3333 335:0.35 336:0.3333 337:0.35 338:0.3333 339:0.3333 340:0.35 341:0.3667 342:0.3667 343:0.3667 344:0.3667 345:0.5833 346:0.5833 347:0.5833 348:0.5833 349:1 350:1 351:1 352:1 353:1 354:1 355:1 356:1 357:1 358:1 359:1 360:1
0.162438470934677 1:0.6 2:0.6 3:0.6 4:0.55 5:0.55 6:0.55 7:0.25 8:0.25 9:0.25 10:0.2667 11:0.25 12:0.2167 13:0.2167 14:0.2167 15:0.2167 16:0.2167 17:0.2 18:0.2 19:0.2 20:0.2 21:0.2 22:0.2 23:0.2 24:0.1833 25:0.1833 26:0.1833 27:0.1833 28:0.1833 29:0.1833 30:0.1833 31:0.1833 32:0.1833 33:0.1833 34:0.1833 35:0.1833 36:0.1833 37:0.1833 38:0.1833 39:0.1833 40:0.1833 41:0.1833 42:0.1833 43:0.1833 44:0.1833 45:0.1833 46:0.1833 47:0.1833 48:0.1833 49:0.1833 50:0.1833 51:0.1833 52:0.1833 53:0.1833 54:0.1833 55:0.1833 56:0.1833 57:0.2 58:0.2167 59:0.2 60:0.2 61:0.2 62:0.2167 63:0.2167 64:0.2 65:0.2 66:0.2 67:0.2 68:0.2 69:0.2 70:0.2 71:0.2 72:0.2 73:0.2 74:0.2 75:0.2 76:0.2 77:0.2 78:0.2 79:0.2 80:0.2 81:0.2 82:0.2 83:0.2 84:0.2 85:0.2 86:0.2 87:0.2 88:0.2 89:0.2 90:0.2 91:0.2 92:0.2 93:0.2 94:1 95:1 96:1 97:1 98:0.8333 99:0.6667 100:0.3667 101:0.3667 102:0.3667 103:0.3667 104:0.3333 105:0.3333 106:0.3333 107:0.3333 108:0.3333 109:0.3333 110:0.3333 111:0.3333 112:0.2 113:0.2 114:0.1833 115:0.1833 116:0.1833 117:0.1833 118:0.1833 119:0.1833 120:0.1833 121:0.1833 122:0.1833 123:0.1833 124:0.1833 125:0.1833 126:0.1833 127:0.1833 128:0.1833 129:0.1833 130:0.1833 131:0.1833 132:0.1833 133:0.1833 134:0.1833 135:0.1833 136:0.1833 137:0.1833 138:0.1833 139:0.1833 140:0.2 141:0.2167 142:0.19294737 143:0.24557895 144:0.24557895 145:0.24557895 146:0.24557895 147:0.24557895 148:0.24557895 149:0.24557895 150:0.24557895 151:0.24557895 152:0.75442105 153:1 154:1 155:1 156:1 157:1 158:1 159:1 160:1 161:1 162:1 163:1 164:1 165:0.87496384 166:0.87496384 167:0.87496384 168:0.87496384 169:0.87496384 170:0.91074968 171:0.89285676 172:0.26789024 173:0.26789024 174:0.26789024 175:0.26789024 176:0.26789024 177:0.26789024 178:0.26789024 179:0.26789024 180:0.26789024 181:0.26789024 182:0.26789024 183:0.26789024 184:0.26789024 185:0.26789024 186:1 187:1 188:1 189:1 190:1 191:1 192:1 193:0.91074968 194:0.91074968 195:0.91074968 196:0.91074968 197:0.80360644 198:0.80360644 199:0.30356894 200:0.30356894 201:0.26789024 202:0.26789024 203:0.26789024 204:0.26789024 205:0.26789024 206:0.26789024 207:0.26789024 208:0.26789024 209:0.26789024 210:0.26789024 211:0.26789024 212:0.2321044 213:0.2321044 214:0.2321044 215:0.2321044 216:0.2321044 217:0.21431862 218:0.2321044 219:0.2321044 220:0.2321044 221:0.2833 222:0.2833 223:0.2833 224:0.2833 225:0.2833 226:0.2833 227:0.2667 228:0.2833 229:0.2833 230:0.2667 231:0.3 232:0.3 233:0.3 234:0.3 235:0.3 236:0.3 237:0.2833 238:0.2833 239:0.2833 240:0.2833 241:0.2833 242:0.2833 243:0.2833 244:0.2833 245:0.2833 246:0.2833 247:0.2833 248:0.2833 249:0.2667 250:0.2833 251:0.2833 252:0.2833 253:0.2833 254:0.2833 255:0.2833 256:0.2833 257:0.2833 258:0.2833 259:0.2833 260:0.2833 261:0.2833 262:0.2833 263:0.3167 264:0.3333 265:0.3333 266:0.3333 267:0.5167 268:0.5167 269:0.8 270:0.8167 271:1 272:1 273:1 274:1 275:1 276:0.7833 277:0.7667 278:0.75 279:0.65 280:0.6 281:0.6 282:0.5833 283:0.35 284:0.35 285:0.35 286:0.35 287:0.3333 288:0.3167 289:0.3167 290:0.3167 291:0.3167 292:0.3167 293:0.3167 294:0.3167 295:0.3167 296:0.3167 297:0.3167 298:0.2333 299:0.2333 300:0.2333 301:0.2333 302:0.2333 303:0.2333 304:0.2333 305:0.2333 306:0.2333 307:0.2333 308:0.2333 309:0.2333 310:0.2333 311:0.2333 312:0.2333 313:0.2333 314:0.2333 315:0.2333 316:0.2333 317:0.2333 318:0.2333 319:0.2333 320:0.3 321:0.3 322:0.3 323:0.3 324:0.3 325:0.3 326:0.3 327:0.3167 328:0.4333 329:0.4333 330:0.4333 331:0.4333 332:0.4333 333:0.4333 334:0.4333 335:0.4333 336:0.4333 337:0.4333 338:0.4333 339:0.4333 340:0.4333 341:0.5667 342:0.5667 343:0.5667 344:0.5667 345:0.5667 346:0.7167 347:0.7167 348:0.7167 349:0.7167 350:0.7333 351:0.8167 352:0.8167 353:0.8167 354:0.8167 355:1 356:1 357:1 358:0.6333 359:0.6167 360:0.6167
0.1065198608830187 1:1 2:1 3:1 4:0.8833 5:0.8833 6:0.8667 7:0.8667 8:0.8667 9:0.8667 10:0.6167 11:0.6167 12:0.6 13:0.6 14:0.6 15:0.6 16:0.6 17:0.6 18:0.4167 19:0.4 20:0.4 21:0.3167 22:0.3 23:0.3 24:0.3 25:0.3 26:0.3 27:0.3 28:0.3 29:0.3 30:0.3 31:0.3 32:0.2833 33:0.2833 34:0.2833 35:0.2833 36:0.2833 37:0.2667 38:0.2833 39:0.2833 40:0.2833 41:0.2833 42:0.2667 43:0.2833 44:0.2833 45:0.2667 46:0.2833 47:0.2667 48:0.2833 49:0.2833 50:0.2667 51:0.2833 52:0.2833 53:0.2833 54:0.2833 55:0.2667 56:1 57:1 58:1 59:0.9167 60:0.9167 61:1 62:0.9 63:0.9 64:0.9 65:0.9 66:0.9 67:0.95 68:0.95 69:0.95 70:0.5833 71:0.5667 72:0.5667 73:0.5667 74:0.5833 75:0.5667 76:0.5667 77:0.5833 78:0.5667 79:0.75 80:0.6833 81:0.6833 82:0.6833 83:0.6833 84:0.6833 85:0.6833 86:0.6833 87:0.7 88:1 89:1 90:1 91:1 92:1 93:0.7667 94:0.4667 95:0.4667 96:0.4667 97:0.4167 98:0.4167 99:0.4167 100:0.2833 101:0.2833 102:0.2833 103:0.2833 104:0.2833 105:0.2833 106:0.2833 107:0.2833 108:0.2833 109:0.2833 110:0.2833 111:0.2833 112:0.2833 113:0.2667 114:0.2833 115:0.2833 116:0.2833 117:0.2833 118:0.2833 119:0.3 120:0.3 121:0.3167 122:0.3167 123:0.3167 124:0.3167 125:0.35 126:0.35 127:0.35 128:0.35 129:0.35 130:0.2333 131:0.2333 132:0.2333 133:0.2333 134:0.2333 135:0.2333 136:0.2333 137:0.2333 138:0.2333 139:0.2333 140:0.2333 141:0.2333 142:0.19294737 143:0.19294737 144:0.19294737 145:0.19294737 146:0.19294737 147:0.19294737 148:0.19294737 149:0.19294737 150:0.21052632 151:0.21052632 152:0.21052632 153:0.21052632 154:0.21052632 155:0.21052632 156:0.21052632 157:0.55353412 158:0.55353412 159:0.89285676 160:0.89285676 161:0.89285676 162:0.89285676 163:1 164:1 165:1 166:1 167:1 168:0.9643213 169:0.9643213 170:0.9643213 171:0.9643213 172:0.9643213 173:1 174:1 175:1 176:1 177:1 178:1 179:1 180:0.1964257 181:0.1964257 182:0.1964257 183:0.1964257 184:0.1964257 185:0.1964257 186:0.1964257 187:0.1964257 188:0.1964257 189:0.1964257 190:0.1964257 191:0.1964257 192:0.160747 193:0.160747 194:0.160747 195:0.160747 196:0.160747 197:0.160747 198:0.160747 199:0.160747 200:0.160747 201:0.160747 202:0.160747 203:0.160747 204:0.160747 205:0.160747 206:0.160747 207:0.160747 208:0.160747 209:0.160747 210:0.160747 211:0.160747 212:0.160747 213:0.17853278 214:0.17853278 215:0.17853278 216:0.17853278 217:0.160747 218:0.17853278 219:0.14285408 220:0.14285408 221:0.2 222:0.2333 223:0.25 224:0.2 225:0.2 226:0.2 227:0.2 228:0.2 229:0.2 230:0.2 231:0.2 232:0.1833 233:0.1833 234:0.1833 235:0.1833 236:0.1833 237:0.1833 238:0.1833 239:0.1833 240:0.1833 241:0.1833 242:0.1833 243:0.1833 244:0.1833 245:0.1833 246:0.1833 247:0.1833 248:0.1833 249:0.1833 250:0.1833 251:0.1833 252:0.1833 253:0.1833 254:0.1833 255:0.1833 256:0.1833 257:0.1833 258:0.1833 259:0.3833 260:0.3833 261:0.3833 262:0.3833 263:0.3833 264:0.3833 265:0.3833 266:0.3833 267:0.3833 268:0.3833 269:0.3833 270:1 271:1 272:1 273:1 274:1 275:0.6833 276:0.6667 277:0.65 278:0.6333 279:0.6333 280:0.5833 281:0.55 282:0.55 283:0.45 284:0.45 285:0.45 286:0.4333 287:0.45 288:0.4333 289:0.45 290:0.4333 291:0.45 292:0.4333 293:0.45 294:0.2333 295:0.2167 296:0.2167 297:0.2167 298:0.2167 299:0.2333 300:0.2167 301:0.2167 302:0.2333 303:0.2333 304:0.2167 305:0.2167 306:0.2333 307:0.2333 308:0.2167 309:0.2167 310:0.2167 311:0.2333 312:0.2167 313:0.2167 314:0.1833 315:0.1833 316:0.1833 317:0.1833 318:0.1833 319:0.1667 320:0.1667 321:0.1667 322:0.1833 323:0.1833 324:0.1833 325:0.1833 326:0.1833 327:0.1833 328:0.1833 329:0.1833 330:0.1833 331:0.1667 332:0.1833 333:0.1833 334:0.1833 335:0.1833 336:0.1667 337:0.1833 338:0.1833 339:0.1833 340:0.1667 341:0.1667 342:0.2333 343:0.2333 344:0.25 345:0.4167 346:0.4167 347:0.4167 348:0.4167 349:0.4167 350:0.4167 351:0.5667 352:0.5667 353:0.5667 354:0.7333 355:0.7167 356:0.8167 357:0.8167 358:0.8167 359:0.8167 360:1
1.036833816007162 1:0.4833 2:0.4833 3:0.4833 4:0.5 5:0.5 6:0.5167 7:0.5167 8:0.5167 9:0.5167 10:0.5667 11:0.55 12:0.55 13:0.5167 14:0.5167 15:0.5167 16:0.4833 17:0.4833 18:0.4833 19:0.35 20:0.3333 21:0.3333 22:0.3333 23:0.3333 24:0.3167 25:0.3333 26:0.3333 27:0.3167 28:0.3333 29:0.3333 30:0.3333 31:0.3333 32:0.3333 33:0.3333 34:0.3333 35:0.3167 36:0.3167 37:0.4667 38:0.4667 39:0.4667 40:0.3833 41:0.35 42:0.35 43:0.35 44:0.35 45:0.35 46:0.35 47:0.35 48:0.35 49:0.35 50:0.35 51:0.35 52:0.35 53:0.35 54:0.35 55:0.35 56:0.35 57:0.35 58:0.35 59:0.3667 60:0.3667 61:0.3833 62:0.4 63:0.4 64:0.4167 65:0.4333 66:0.4333 67:0.4333 68:0.45 69:0.45 70:0.45 71:0.45 72:0.45 73:0.45 74:0.6833 75:0.6833 76:0.6833 77:0.8167 78:0.8167 79:0.8333 80:0.8333 81:0.9333 82:0.9333 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:0.9333 106:0.8667 107:0.8167 108:0.7667 109:0.7667 110:0.5833 111:0.5833 112:0.5833 113:0.55 114:0.55 115:0.55 116:0.55 117:0.4667 118:0.4667 119:0.4667 120:0.4667 121:0.4667 122:0.4333 123:0.4333 124:0.4167 125:0.4 126:0.4 127:0.3833 128:0.3833 129:0.3833 130:0.3833 131:0.3833 132:0.3833 133:0.3833 134:0.3833 135:0.3833 136:0.3833 137:0.3833 138:0.3833 139:0.3833 140:0.3833 141:0.3833 142:0.35084211 143:0.50873684 144:0.49126316 145:0.49126316 146:0.47368421 147:0.47368421 148:0.47368421 149:0.47368421 150:0.47368421 151:0.47368421 152:0.33336842 153:0.33336842 154:0.29821053 155:0.29821053 156:0.29821053 157:0.28567602 158:0.28567602 159:0.28567602 160:0.28567602 161:0.28567602 162:0.28567602 163:0.28567602 164:0.28567602 165:0.28567602 166:0.28567602 167:0.28567602 168:0.28567602 169:0.30356894 170:0.41071218 171:0.41071218 172:0.4286051 173:0.41071218 174:0.41071218 175:0.41071218 176:0.4286051 177:0.4286051 178:0.4286051 179:0.4286051 180:0.4286051 181:0.44639088 182:0.44639088 183:0.44639088 184:0.4642838 185:0.4642838 186:0.4999625 187:0.4999625 188:0.4999625 189:0.4999625 190:0.4999625 191:0.4999625 192:0.4999625 193:0.51785542 194:0.55353412 195:0.57142704 196:1 197:1 198:1 199:1 200:1 201:1 202:1 203:1 204:1 205:1 206:0.94642838 207:0.94642838 208:0.94642838 209:0.82139222 210:0.78571352 211:0.80360644 212:0.80360644 213:0.78571352 214:0.64289158 215:0.62499866 216:0.62499866 217:0.62499866 218:0.62499866 219:0.62499866 220:0.62499866 221:0.65 222:0.65 223:0.6667 224:0.6333 225:0.6333 226:0.6333 227:0.6333 228:0.6333 229:0.6333 230:0.6333 231:0.6333 232:0.7667 233:0.7667 234:0.7833 235:0.7833 236:0.8 237:0.8 238:0.8 239:0.8167 240:0.8333 241:0.85 242:0.85 243:0.8667 244:0.8833 245:0.9 246:0.9333 247:0.9667 248:0.8 249:0.8 250:0.7833 251:0.7833 252:0.7833 253:0.7833 254:0.7833 255:0.7833 256:0.7833 257:0.7833 258:0.85 259:0.95 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:0.85 286:0.85 287:0.85 288:0.8167 289:0.8 290:0.8 291:0.8 292:0.8 293:0.8 294:0.8 295:0.8 296:0.9333 297:0.6667 298:0.6667 299:0.6667 300:0.6667 301:0.6667 302:0.6667 303:0.6667 304:0.7333 305:0.7333 306:0.7167 307:0.7167 308:0.7167 309:0.7 310:0.7 311:0.7 312:0.7 313:0.7 314:0.7 315:0.7 316:0.7 317:0.7 318:0.7 319:0.65 320:0.65 321:0.65 322:0.65 323:0.65 324:0.65 325:0.65 326:0.7 327:0.7 328:0.7167 329:0.7333 330:0.75 331:0.75 332:0.7667 333:0.7667 334:0.7667 335:0.7667 336:0.7667 337:0.7667 338:0.9333 339:0.9333 340:1 341:1 342:1 343:1 344:1 345:1 346:1 347:1 348:1 349:1 350:1 351:1 352:1 353:1 354:0.7 355:0.4833 356:0.4833 357:0.4833 358:0.4833 359:0.4833 360:0.4833
0.08175412114013921 1:1 2:1 3:1 4:1 5:1 6:0.8667 7:0.8667 8:0.8 9:0.4167 10:0.4167 11:0.4167 12:0.4167 13:0.4167 14:0.4167 15:0.4167 16:0.4167 17:0.4167 18:0.4167 19:0.4167 20:0.4167 21:0.4167 22:0.4167 23:0.5 24:0.5 25:0.5 26:0.5 27:0.5 28:0.5 29:0.5333 30:0.5333 31:0.6 32:0.6 33:0.6167 34:0.6 35:0.5833 36:0.6 37:0.5833 38:0.5667 39:0.5833 40:0.5667 41:0.5833 42:0.5833 43:0.5667 44:0.5833 45:0.5667 46:0.5833 47:0.6 48:0.6 49:0.6167 50:0.6333 51:0.6333 52:0.65 53:0.6667 54:0.6833 55:0.7 56:0.7667 57:0.7667 58:0.9 59:0.9 60:0.4667 61:0.4667 62:0.4667 63:0.4667 64:0.4667 65:0.4667 66:0.4667 67:0.4667 68:0.4667 69:0.4667 70:0.4833 71:0.5 72:0.5 73:0.5167 74:0.5833 75:0.5833 76:0.5833 77:0.5833 78:0.6333 79:0.6833 80:0.7333 81:0.7833 82:0.8 83:0.9667 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:0.9167 103:0.9167 104:0.7667 105:0.7167 106:0.6667 107:0.6667 108:0.6667 109:0.5667 110:0.5833 111:0.5667 112:0.5333 113:0.5333 114:0.5333 115:0.5333 116:0.5333 117:0.5333 118:0.5333 119:0.5333 120:0.5333 121:0.5333 122:0.9 123:0.9 124:0.8833 125:0.8833 126:0.8833 127:0.8667 128:0.8667 129:0.8667 130:0.8667 131:0.85 132:0.85 133:0.8333 134:0.8167 135:0.8167 136:0.8167 137:0.7667 138:0.75 139:0.7333 140:0.7333 141:0.6 142:0.57894737 143:0.54389474 144:0.54389474 145:0.52631579 146:0.52631579 147:0.52631579 148:0.52631579 149:0.50873684 150:0.43863158 151:0.43863158 152:0.43863158 153:0.43863158 154:0.43863158 155:0.43863158 156:0.43863158 157:0.4286051 158:0.4286051 159:0.4286051 160:0.44639088 161:0.48217672 162:0.48217672 163:0.48217672 164:0.48217672 165:0.48217672 166:0.48217672 167:0.48217672 168:0.48217672 169:0.48217672 170:0.48217672 171:0.48217672 172:0.51785542 173:0.51785542 174:0.58931996 175:0.58931996 176:0.7321419 177:0.75003482 178:1 179:1 180:1 181:1 182:1 183:1 184:1 185:1 186:1 187:1 188:0.83928514 189:0.66067736 190:0.58931996 191:0.58931996 192:0.58931996 193:0.58931996 194:0.58931996 195:0.58931996 196:0.58931996 197:0.58931996 198:0.58931996 199:0.41071218 200:0.39281926 201:0.39281926 202:0.39281926 203:0.39281926 204:0.39281926 205:0.39281926 206:0.39281926 207:0.39281926 208:0.39281926 209:0.39281926 210:0.39281926 211:0.41071218 212:0.41071218 213:0.41071218 214:0.41071218 215:0.4286051 216:0.4286051 217:0.4286051 218:0.44639088 219:0.4642838 220:0.48217672 221:0.5167 222:0.55 223:0.55 224:0.5667 225:0.6 226:0.6 227:0.6167 228:0.6333 229:0.6333 230:0.65 231:0.65 232:0.65 233:0.65 234:0.65 235:0.65 236:0.65 237:0.65 238:0.6667 239:0.6833 240:0.4667 241:0.4667 242:0.4667 243:0.4667 244:0.4667 245:0.4667 246:0.4667 247:0.4667 248:0.4667 249:0.4667 250:0.4833 251:0.55 252:0.55 253:0.55 254:0.55 255:0.5667 256:0.5833 257:0.5833 258:0.6333 259:0.6833 260:0.7333 261:0.7333 262:0.8 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:0.9167 284:0.85 285:0.8 286:0.6667 287:0.6333 288:0.6 289:0.6 290:0.5333 291:0.5167 292:0.4833 293:0.4667 294:0.45 295:0.4333 296:0.4333 297:0.4333 298:0.4333 299:0.4333 300:0.4333 301:0.4333 302:0.4333 303:0.4333 304:0.4333 305:0.4333 306:0.45 307:0.8167 308:0.7667 309:0.7167 310:0.7 311:0.6833 312:0.6833 313:0.6333 314:0.6333 315:0.6167 316:0.6 317:0.6 318:0.5833 319:0.5833 320:0.5667 321:0.5667 322:0.55 323:0.55 324:0.55 325:0.55 326:0.55 327:0.55 328:0.5333 329:0.5333 330:0.5333 331:0.5333 332:0.5333 333:0.45 334:0.45 335:0.45 336:0.45 337:0.45 338:0.45 339:0.45 340:0.45 341:0.45 342:0.45 343:0.45 344:0.5333 345:0.5333 346:0.5333 347:0.5333 348:0.55 349:0.55 350:0.5667 351:0.7167 352:0.9667 353:1 354:1 355:1 356:1 357:1 358:1 359:1 360:1
0.02981194483291762 1:1 2:1 3:1 4:1 5:1 6:1 7:1 8:1 9:1 10:0.9167 11:0.9 12:0.8333 13:0.8333 14:0.7 15:0.7 16:0.7 17:0.4667 18:0.4667 19:0.4667 20:0.4667 21:0.4667 22:0.4667 23:0.4667 24:0.4667 25:0.4667 26:0.4667 27:0.4667 28:0.4667 29:0.5667 30:0.55 31:0.5667 32:0.5667 33:0.5833 34:0.6 35:0.6667 36:0.6667 37:0.6667 38:0.65 39:0.6333 40:0.65 41:0.6333 42:0.65 43:0.65 44:0.6333 45:0.65 46:0.65 47:0.6333 48:0.65 49:0.6667 50:0.6833 51:0.6833 52:0.7 53:0.7167 54:0.7667 55:0.7667 56:0.7667 57:0.8 58:0.9667 59:0.9667 60:0.9833 61:0.5333 62:0.55 63:0.5333 64:0.55 65:0.55 66:0.55 67:0.55 68:0.5333 69:0.55 70:0.5833 71:0.5833 72:0.5833 73:0.65 74:0.65 75:0.65 76:0.6667 77:0.75 78:0.8 79:0.8333 80:0.8167 81:0.9 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:0.8167 102:0.75 103:0.7 104:0.6333 105:0.6333 106:0.6167 107:0.6167 108:0.6167 109:0.5667 110:0.5833 111:0.5667 112:0.5667 113:0.5833 114:0.5667 115:0.5833 116:0.5667 117:0.9667 118:0.9333 119:0.9333 120:0.9167 121:0.9167 122:0.9167 123:0.9 124:0.9 125:0.9 126:0.8833 127:0.8833 128:0.8833 129:0.85 130:0.85 131:0.8167 132:0.8 133:0.7833 134:0.75 135:0.7333 136:0.5833 137:0.5833 138:0.5833 139:0.5333 140:0.5333 141:0.4667 142:0.43863158 143:0.43863158 144:0.43863158 145:0.43863158 146:0.43863158 147:0.43863158 148:0.43863158 149:0.43863158 150:0.43863158 151:0.43863158 152:0.43863158 153:0.49126316 154:0.47368421 155:0.47368421 156:0.47368421 157:0.4642838 158:0.4642838 159:0.4642838 160:0.4642838 161:0.4642838 162:0.4642838 163:0.48217672 164:0.57142704 165:0.57142704 166:0.57142704 167:0.57142704 168:0.57142704 169:0.57142704 170:0.71424898 171:0.71424898 172:0.7321419 173:0.89285676 174:0.89285676 175:1 176:1 177:1 178:1 179:1 180:1 181:1 182:1 183:0.78571352 184:0.53574834 185:0.53574834 186:0.53574834 187:0.53574834 188:0.53574834 189:0.53574834 190:0.53574834 191:0.53574834 192:0.33924764 193:0.33924764 194:0.33924764 195:0.33924764 196:0.33924764 197:0.33924764 198:0.33924764 199:0.33924764 200:0.33924764 201:0.33924764 202:0.33924764 203:0.33924764 204:0.33924764 205:0.33924764 206:0.33924764 207:0.35714056 208:0.35714056 209:0.35714056 210:0.35714056 211:0.35714056 212:0.37503348 213:0.37503348 214:0.37503348 215:0.39281926 216:0.41071218 217:0.41071218 218:0.41071218 219:0.4286051 220:0.44639088 221:0.5 222:0.5 223:0.5333 224:0.55 225:0.55 226:0.5667 227:0.5667 228:0.5833 229:0.5833 230:0.5833 231:0.5833 232:0.5833 233:0.5667 234:0.5833 235:0.5833 236:0.5667 237:0.5833 238:0.5833 239:0.5833 240:0.3833 241:0.4 242:0.4 243:0.4 244:0.4 245:0.3833 246:0.4 247:0.3833 248:0.4 249:0.3833 250:0.4 251:0.4 252:0.4 253:0.4 254:0.4833 255:0.4833 256:0.4833 257:0.5167 258:0.5167 259:0.5167 260:0.5667 261:0.6167 262:0.6167 263:0.65 264:0.75 265:0.9667 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:0.9333 286:0.8667 287:0.8167 288:0.7667 289:0.75 290:0.7 291:0.65 292:0.5833 293:0.5667 294:0.5667 295:0.5167 296:0.5 297:0.4667 298:0.4667 299:0.45 300:0.4333 301:0.4167 302:0.4167 303:0.4167 304:0.4167 305:0.4167 306:0.4167 307:0.4167 308:0.4167 309:0.4167 310:0.4167 311:0.4167 312:0.4167 313:0.4167 314:0.7333 315:0.7167 316:0.6833 317:0.6667 318:0.65 319:0.6167 320:0.6167 321:0.6 322:0.6 323:0.5833 324:0.5833 325:0.5833 326:0.5667 327:0.5667 328:0.55 329:0.55 330:0.55 331:0.5333 332:0.55 333:0.5333 334:0.55 335:0.5333 336:0.5333 337:0.5333 338:0.5333 339:0.5333 340:0.5333 341:0.5333 342:0.5333 343:0.4667 344:0.4667 345:0.4667 346:0.4667 347:0.4667 348:0.4667 349:0.4667 350:0.4667 351:0.4667 352:0.4667 353:0.55 354:0.5667 355:0.5667 356:0.5667 357:0.7167 358:1 359:1 360:1
0.137213548154081 1:1 2:1 3:1 4:1 5:0.9 6:0.8833 7:0.4333 8:0.4333 9:0.4333 10:0.4333 11:0.4333 12:0.4333 13:0.4333 14:0.4333 15:0.4333 16:0.4333 17:0.4333 18:0.45 19:0.5333 20:0.5333 21:0.5333 22:0.5333 23:0.5333 24:0.5333 25:0.5333 26:0.5333 27:0.6333 28:0.6333 29:0.6333 30:0.6333 31:0.6333 32:0.6333 33:0.6167 34:0.6 35:0.6 36:0.6 37:0.6 38:0.6 39:0.6 40:0.6 41:0.6 42:0.6 43:0.6 44:0.6167 45:0.6167 46:0.6333 47:0.6333 48:0.65 49:0.6667 50:0.6833 51:0.6833 52:0.7 53:0.7167 54:0.7333 55:0.4667 56:0.4667 57:0.4667 58:0.4667 59:0.4667 60:0.4667 61:0.4667 62:0.4667 63:0.4667 64:0.4667 65:0.4667 66:0.5 67:0.5167 68:0.5167 69:0.5167 70:0.5667 71:0.5667 72:0.5833 73:0.5667 74:0.6 75:0.6333 76:0.6667 77:0.6667 78:0.7667 79:0.75 80:0.8167 81:0.9 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:0.9167 102:0.8 103:0.6833 104:0.6333 105:0.6333 106:0.6333 107:0.5333 108:0.5333 109:0.5333 110:0.5333 111:0.5167 112:0.5167 113:0.5167 114:0.5167 115:0.5167 116:0.5167 117:0.5167 118:0.5167 119:0.5167 120:0.5167 121:0.5167 122:0.8667 123:0.8667 124:0.85 125:0.85 126:0.85 127:0.85 128:0.85 129:0.8333 130:0.8333 131:0.8167 132:0.8 133:0.7833 134:0.7667 135:0.7667 136:0.75 137:0.7167 138:0.7 139:0.6833 140:0.5667 141:0.5667 142:0.50873684 143:0.50873684 144:0.49126316 145:0.50873684 146:0.45610526 147:0.47368421 148:0.45610526 149:0.47368421 150:0.40347368 151:0.40347368 152:0.40347368 153:0.40347368 154:0.40347368 155:0.40347368 156:0.40347368 157:0.39281926 158:0.39281926 159:0.39281926 160:0.39281926 161:0.44639088 162:0.44639088 163:0.44639088 164:0.44639088 165:0.44639088 166:0.44639088 167:0.44639088 168:0.44639088 169:0.44639088 170:0.44639088 171:0.44639088 172:0.44639088 173:0.4642838 174:0.44639088 175:0.55353412 176:0.55353412 177:0.55353412 178:0.71424898 179:0.71424898 180:1 181:1 182:1 183:1 184:1 185:1 186:1 187:1 188:1 189:0.62499866 190:0.60710574 191:0.60710574 192:0.55353412 193:0.55353412 194:0.55353412 195:0.55353412 196:0.55353412 197:0.55353412 198:0.55353412 199:0.55353412 200:0.39281926 201:0.39281926 202:0.39281926 203:0.37503348 204:0.37503348 205:0.37503348 206:0.37503348 207:0.37503348 208:0.37503348 209:0.37503348 210:0.37503348 211:0.37503348 212:0.37503348 213:0.37503348 214:0.37503348 215:0.37503348 216:0.39281926 217:0.39281926 218:0.39281926 219:0.39281926 220:0.41071218 221:0.45 222:0.4833 223:0.4833 224:0.5 225:0.5 226:0.5167 227:0.55 228:0.55 229:0.5667 230:0.6 231:0.6167 232:0.6333 233:0.6333 234:0.65 235:0.6333 236:0.6333 237:0.6333 238:0.6333 239:0.6333 240:0.6333 241:0.6333 242:0.6333 243:0.65 244:0.4667 245:0.4667 246:0.4667 247:0.4667 248:0.4667 249:0.4667 250:0.4667 251:0.4667 252:0.4667 253:0.4667 254:0.4667 255:0.4667 256:0.4833 257:0.55 258:0.55 259:0.6167 260:0.6167 261:0.6167 262:0.65 263:0.65 264:0.75 265:0.8667 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:0.95 286:0.8833 287:0.8167 288:0.7833 289:0.7333 290:0.6833 291:0.65 292:0.6333 293:0.55 294:0.5333 295:0.5333 296:0.5333 297:0.4667 298:0.4667 299:0.4667 300:0.4667 301:0.4667 302:0.4667 303:0.4667 304:0.4667 305:0.4667 306:0.4667 307:0.4667 308:0.4833 309:0.8333 310:0.7833 311:0.7667 312:0.75 313:0.7167 314:0.7 315:0.6667 316:0.65 317:0.65 318:0.6333 319:0.6167 320:0.6167 321:0.6 322:0.6 323:0.5833 324:0.5833 325:0.5833 326:0.5833 327:0.5833 328:0.5833 329:0.5667 330:0.5667 331:0.5667 332:0.5667 333:0.5667 334:0.5 335:0.5 336:0.5 337:0.5 338:0.5 339:0.5 340:0.5 341:0.5 342:0.5 343:0.5 344:0.5 345:0.5667 346:0.5833 347:0.5833 348:0.5833 349:0.6 350:0.7333 351:0.75 352:1 353:1 354:1 355:1 356:1 357:1 358:1 359:1 360:1
0.2253674431456161 1:1 2:1 3:1 4:1 5:1 6:1 7:1 8:1 9:1 10:1 11:1 12:0.9167 13:0.9167 14:0.8667 15:0.8667 16:0.8667 17:0.8667 18:0.8667 19:0.8667 20:0.8667 21:0.6667 22:0.6667 23:0.65 24:0.6167 25:0.6 26:0.6 27:0.5833 28:0.5667 29:0.5667 30:0.5667 31:0.5667 32:0.5667 33:0.55 34:0.5333 35:0.55 36:0.55 37:0.55 38:0.55 39:0.5333 40:0.55 41:0.5333 42:0.55 43:0.55 44:0.55 45:0.55 46:0.5833 47:0.6 48:0.6 49:0.6 50:0.6 51:0.6 52:0.6 53:1 54:1 55:1 56:1 57:1 58:1 59:1 60:1 61:1 62:1 63:1 64:1 65:1 66:1 67:1 68:1 69:1 70:1 71:1 72:1 73:1 74:1 75:1 76:0.8833 77:0.8833 78:0.8833 79:0.8833 80:0.8833 81:0.8833 82:0.8833 83:0.8833 84:0.8833 85:0.9 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:0.9333 104:0.9333 105:0.9333 106:0.9333 107:0.9333 108:0.65 109:0.6167 110:0.5833 111:0.5833 112:0.5833 113:0.5833 114:0.5833 115:0.5833 116:0.5833 117:0.5833 118:0.5833 119:0.5833 120:0.5833 121:0.5833 122:0.5833 123:0.5833 124:0.7833 125:0.7667 126:0.75 127:0.7333 128:0.7333 129:0.7167 130:0.7167 131:0.7167 132:0.7167 133:0.7167 134:0.7167 135:0.7167 136:0.7167 137:0.7167 138:0.7333 139:0.7333 140:0.7167 141:0.7333 142:0.71926316 143:0.73684211 144:0.75442105 145:0.77189474 146:1 147:1 148:1 149:1 150:1 151:1 152:1 153:1 154:1 155:1 156:1 157:1 158:1 159:1 160:1 161:1 162:1 163:1 164:1 165:1 166:1 167:1 168:1 169:1 170:1 171:1 172:1 173:1 174:1 175:1 176:1 177:1 178:1 179:1 180:1 181:1 182:1 183:1 184:1 185:1 186:1 187:1 188:1 189:1 190:1 191:1 192:1 193:1 194:1 195:0.78571352 196:0.78571352 197:0.53574834 198:0.51785542 199:0.51785542 200:0.51785542 201:0.51785542 202:0.51785542 203:0.51785542 204:0.51785542 205:0.51785542 206:0.51785542 207:0.51785542 208:0.51785542 209:0.51785542 210:0.53574834 211:0.75003482 212:0.7678206 213:0.7678206 214:0.4999625 215:0.51785542 216:0.51785542 217:0.51785542 218:0.51785542 219:0.4999625 220:0.51785542 221:0.5333 222:0.55 223:0.55 224:0.55 225:0.55 226:0.5667 227:0.5667 228:0.5833 229:0.5833 230:0.6 231:0.6167 232:0.7833 233:0.7667 234:0.7833 235:0.7833 236:0.7833 237:0.7833 238:0.7833 239:0.7833 240:0.7833 241:0.7833 242:0.8 243:0.8 244:1 245:1 246:1 247:1 248:1 249:1 250:1 251:1 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:1 296:0.9667 297:0.9667 298:0.9667 299:0.9667 300:0.9667 301:0.9833 302:1 303:1 304:0.6833 305:0.6833 306:0.6833 307:0.6667 308:0.6667 309:0.6667 310:0.6667 311:0.6667 312:0.6667 313:0.6667 314:0.6833 315:1 316:1 317:1 318:1 319:1 320:1 321:1 322:1 323:1 324:1 325:0.65 326:1 327:0.65 328:0.65 329:1 330:1 331:0.65 332:1 333:1 334:1 335:1 336:1 337:1 338:1 339:1 340:1 341:1 342:1 343:1 344:1 345:1 346:1 347:1 348:1 349:1 350:1 351:1 352:1 353:1 354:1 355:1 356:1 357:1 358:1 359:1 360:1
0.3176739970396059 1:1 2:1 3:1 4:1 5:1 6:1 7:1 8:1 9:1 10:1 11:1 12:0.9333 13:0.8667 14:0.85 15:0.8167 16:0.8167 17:0.8167 18:0.8167 19:0.8167 20:0.8167 21:0.8167 22:0.8333 23:0.6 24:0.6167 25:0.6 26:0.5667 27:0.55 28:0.55 29:0.55 30:0.5333 31:0.5167 32:0.5333 33:0.5167 34:0.5 35:0.5 36:0.5 37:0.5 38:0.5 39:0.5 40:0.5 41:0.5 42:0.5 43:0.5 44:0.5 45:0.5 46:0.5 47:0.5 48:0.3667 49:0.3667 50:0.3667 51:0.3667 52:0.3667 53:0.35 54:0.35 55:0.35 56:0.35 57:0.35 58:0.35 59:0.35 60:0.35 61:0.35 62:0.35 63:0.35 64:0.35 65:0.35 66:0.35 67:0.35 68:0.3667 69:0.3833 70:0.4 71:0.4167 72:0.4333 73:0.45 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:0.9 82:0.9 83:0.9 84:0.9 85:0.9 86:0.9 87:0.9 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:0.9333 107:0.9333 108:0.9333 109:0.9167 110:0.9167 111:0.9167 112:0.6667 113:0.65 114:0.65 115:0.6 116:0.5667 117:0.5667 118:0.5667 119:0.5833 120:0.5667 121:0.5667 122:0.5667 123:0.5667 124:0.5833 125:0.5833 126:0.5833 127:0.6 128:0.8 129:0.7667 130:0.75 131:0.75 132:0.75 133:0.75 134:0.75 135:0.75 136:0.75 137:0.75 138:0.75 139:0.75 140:0.75 141:0.75 142:0.73684211 143:0.75442105 144:0.75442105 145:0.77189474 146:0.78947368 147:0.78947368 148:1 149:1 150:1 151:1 152:1 153:1 154:1 155:1 156:1 157:1 158:1 159:1 160:1 161:1 162:1 163:1 164:1 165:1 166:1 167:1 168:1 169:1 170:1 171:1 172:1 173:1 174:1 175:1 176:1 177:1 178:1 179:1 180:1 181:1 182:1 183:1 184:1 185:1 186:1 187:1 188:1 189:1 190:1 191:1 192:1 193:0.57142704 194:0.57142704 195:0.55353412 196:0.55353412 197:0.53574834 198:0.53574834 199:0.53574834 200:0.4999625 201:0.51785542 202:0.51785542 203:0.51785542 204:0.51785542 205:0.4999625 206:0.51785542 207:0.4999625 208:0.57142704 209:0.80360644 210:0.80360644 211:0.82139222 212:0.60710574 213:0.60710574 214:0.60710574 215:0.60710574 216:0.60710574 217:0.58931996 218:0.58931996 219:0.60710574 220:0.58931996 221:0.6167 222:0.6333 223:0.6167 224:0.6333 225:0.6333 226:0.6333 227:0.6333 228:0.65 229:0.6667 230:0.8167 231:0.25 232:0.25 233:0.25 234:0.2333 235:0.2167 236:0.2333 237:0.2333 238:0.2333 239:0.2333 240:0.2333 241:0.2333 242:0.2333 243:0.2333 244:0.2333 245:0.2333 246:0.2333 247:0.2333 248:0.2333 249:0.2333 250:0.2333 251:0.2333 252:0.2333 253:0.2333 254:0.25 255:0.2667 256:0.2833 257:0.3 258:0.3333 259:0.35 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:0.95 294:0.95 295:0.95 296:0.95 297:0.95 298:0.9833 299:0.9833 300:1 301:0.6833 302:0.6667 303:0.6667 304:0.6667 305:0.6667 306:0.6667 307:0.6667 308:0.6667 309:1 310:1 311:1 312:1 313:1 314:1 315:1 316:1 317:1 318:1 319:1 320:1 321:1 322:1 323:1 324:1 325:0.65 326:1 327:0.65 328:0.65 329:1 330:1 331:0.65 332:1 333:1 334:1 335:1 336:1 337:1 338:1 339:1 340:1 341:1 342:1 343:1 344:1 345:1 346:1 347:1 348:1 349:1 350:1 351:1 352:1 353:1 354:1 355:1 356:1 357:1 358:1 359:1 360:1
0.405102162945035 1:0.5167 2:0.5167 3:0.5167 4:0.5167 5:0.5167 6:0.5167 7:0.5167 8:0.5167 9:0.5167 10:0.5167 11:0.5167 12:0.5167 13:0.5167 14:0.5 15:0.5 16:0.5 17:0.5 18:0.5 19:0.5 20:0.5 21:0.5 22:0.5 23:0.5167 24:0.5167 25:0.5167 26:0.5167 27:0.4 28:0.5167 29:0.4 30:0.4167 31:0.4 32:0.4167 33:0.55 34:0.4 35:0.5667 36:0.4 37:0.5833 38:0.5833 39:0.5833 40:0.6 41:0.6 42:0.6167 43:0.6167 44:0.6333 45:0.65 46:0.65 47:0.6667 48:0.6833 49:0.6833 50:0.7 51:0.7167 52:0.7333 53:0.75 54:0.7667 55:0.7833 56:0.8 57:0.4167 58:0.85 59:0.4167 60:0.4167 61:0.4167 62:0.4167 63:0.4333 64:0.4167 65:0.4333 66:0.4167 67:0.4333 68:0.4333 69:0.4333 70:0.4333 71:0.4833 72:0.4833 73:0.4833 74:0.4833 75:0.4833 76:0.4833 77:0.4833 78:0.4833 79:0.5667 80:0.5667 81:0.5667 82:0.5667 83:0.5667 84:0.6667 85:0.6667 86:0.6667 87:0.7167 88:0.8667 89:0.9167 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:0.9167 105:0.85 106:0.85 107:0.85 108:0.75 109:0.75 110:0.6 111:0.6 112:0.6 113:0.6 114:0.6 115:0.6 116:0.6 117:0.6 118:0.6 119:0.6 120:0.6 121:0.6 122:0.6 123:0.6333 124:0.9833 125:0.9167 126:0.9167 127:0.9167 128:0.9 129:0.8833 130:0.8667 131:0.85 132:0.85 133:0.4667 134:0.4667 135:0.4667 136:0.4667 137:0.4667 138:0.4667 139:0.4667 140:0.4667 141:0.4667 142:0.43863158 143:0.45610526 144:0.45610526 145:0.70178947 146:0.70178947 147:0.70178947 148:0.70178947 149:0.70178947 150:0.70178947 151:0.70178947 152:0.70178947 153:0.70178947 154:0.70178947 155:0.71926316 156:0.71926316 157:0.71424898 158:0.7321419 159:0.7321419 160:0.75003482 161:0.7678206 162:0.7678206 163:0.7678206 164:0.80360644 165:0.80360644 166:0.82139222 167:0.83928514 168:0.85717806 169:0.89285676 170:0.91074968 171:0.92853546 172:1 173:0.82139222 174:0.82139222 175:0.82139222 176:0.82139222 177:0.82139222 178:0.82139222 179:0.82139222 180:1 181:1 182:1 183:1 184:1 185:1 186:1 187:1 188:1 189:1 190:1 191:1 192:1 193:1 194:1 195:1 196:1 197:1 198:1 199:1 200:0.98210708 201:0.89285676 202:0.89285676 203:0.89285676 204:0.89285676 205:0.89285676 206:0.89285676 207:1 208:0.92853546 209:0.89285676 210:0.89285676 211:0.91074968 212:0.85717806 213:0.82139222 214:0.80360644 215:0.80360644 216:0.78571352 217:0.4286051 218:0.39281926 219:0.39281926 220:0.39281926 221:0.4333 222:0.4167 223:0.4167 224:0.4167 225:0.4167 226:0.4167 227:0.4167 228:0.4167 229:0.4167 230:0.4167 231:0.4167 232:0.4167 233:0.4167 234:0.4167 235:0.4167 236:0.4167 237:0.6167 238:0.7667 239:0.75 240:0.7667 241:0.7667 242:0.6833 243:0.6833 244:0.8 245:0.7833 246:0.6833 247:0.6833 248:0.7833 249:0.7833 250:0.7833 251:0.85 252:0.9 253:0.9333 254:0.9333 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:0.9333 271:0.7667 272:0.6167 273:0.6167 274:0.6167 275:0.6 276:0.5167 277:0.5167 278:0.5167 279:0.5167 280:0.5167 281:0.5167 282:0.5167 283:0.4667 284:0.4667 285:0.4667 286:0.4667 287:0.4667 288:0.4667 289:0.4667 290:0.4667 291:0.4667 292:0.5833 293:0.5833 294:0.5833 295:0.5833 296:0.6 297:0.6 298:0.6 299:0.6 300:0.6 301:0.6 302:0.6 303:0.6167 304:0.6167 305:0.6167 306:0.6333 307:0.6333 308:0.6333 309:0.6333 310:0.6333 311:0.65 312:0.65 313:0.4833 314:0.4833 315:0.4833 316:0.4833 317:0.4833 318:0.4833 319:0.4833 320:0.4833 321:0.4833 322:0.4833 323:0.4833 324:0.55 325:0.55 326:0.55 327:0.5167 328:0.5167 329:0.5167 330:0.5 331:0.5 332:0.5 333:0.5 334:0.4833 335:0.4833 336:0.4833 337:0.4833 338:0.4833 339:0.4833 340:0.4833 341:0.4833 342:0.4833 343:0.4833 344:0.4833 345:0.5 346:0.5 347:0.5167 348:0.5167 349:0.5167 350:0.5167 351:0.5167 352:0.5167 353:0.5167 354:0.5167 355:0.5167 356:0.5167 357:0.5167 358:0.5167 359:0.5167 360:0.5167
0.02923343901896431 1:0.6833 2:0.6833 3:0.6833 4:1 5:1 6:1 7:1 8:1 9:1 10:1 11:1 12:1 13:1 14:1 15:1 16:1 17:1 18:0.8833 19:0.8833 20:0.8833 21:0.8 22:0.4833 23:0.4833 24:0.4833 25:0.4667 26:0.4833 27:0.4667 28:0.4833 29:0.4667 30:0.4833 31:0.4667 32:0.4167 33:0.4167 34:0.4167 35:0.4 36:0.4167 37:0.4 38:0.4167 39:0.4167 40:0.4167 41:0.4167 42:0.4 43:0.4167 44:0.4 45:0.5333 46:0.5333 47:0.5333 48:0.5333 49:0.5333 50:0.5333 51:0.5167 52:0.5333 53:0.5333 54:0.5333 55:0.5333 56:0.5333 57:0.5333 58:0.5333 59:0.55 60:0.55 61:0.55 62:0.55 63:0.55 64:0.5667 65:0.55 66:0.5667 67:0.5833 68:0.5833 69:0.6 70:0.6 71:0.6 72:0.6167 73:0.6167 74:0.65 75:0.6667 76:0.5 77:0.4833 78:0.4833 79:0.4833 80:0.4833 81:0.4833 82:0.4833 83:0.4833 84:0.4833 85:0.4833 86:0.4833 87:0.4833 88:0.4833 89:0.5 90:0.5 91:0.5667 92:0.6833 93:0.6833 94:0.6833 95:0.9167 96:0.95 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:1 118:1 119:0.9833 120:0.9833 121:0.9667 122:0.8833 123:0.8667 124:0.85 125:0.7667 126:0.75 127:0.7333 128:0.7 129:0.6167 130:0.6167 131:0.5833 132:0.5833 133:0.5667 134:0.55 135:0.55 136:0.55 137:0.55 138:0.55 139:0.55 140:0.55 141:0.55 142:0.52631579 143:0.52631579 144:0.54389474 145:0.54389474 146:0.54389474 147:0.68421053 148:0.68421053 149:0.68421053 150:0.68421053 151:0.59652632 152:0.59652632 153:0.43863158 154:0.43863158 155:0.43863158 156:0.43863158 157:0.4286051 158:0.4286051 159:0.4286051 160:0.4286051 161:0.4286051 162:0.4286051 163:0.4286051 164:0.44639088 165:0.53574834 166:0.53574834 167:0.53574834 168:0.53574834 169:0.53574834 170:0.53574834 171:0.53574834 172:0.53574834 173:0.53574834 174:0.53574834 175:0.53574834 176:0.53574834 177:0.53574834 178:0.53574834 179:0.53574834 180:0.53574834 181:0.53574834 182:0.53574834 183:0.53574834 184:0.53574834 185:0.53574834 186:0.53574834 187:0.53574834 188:0.53574834 189:0.6964632 190:0.7321419 191:0.7321419 192:0.7321419 193:0.7321419 194:0.7321419 195:0.75003482 196:1 197:1 198:1 199:1 200:1 201:1 202:1 203:1 204:1 205:1 206:0.9643213 207:0.9643213 208:0.9643213 209:0.9643213 210:0.7678206 211:0.7678206 212:0.7678206 213:0.7678206 214:0.7678206 215:0.7678206 216:0.78571352 217:1 218:0.57142704 219:0.57142704 220:0.57142704 221:0.6 222:0.6 223:0.6 224:0.6 225:0.6 226:0.6 227:0.6667 228:0.7333 229:0.7333 230:0.7167 231:0.7167 232:0.7 233:0.7 234:0.6833 235:0.6833 236:0.6833 237:0.6833 238:0.6833 239:0.6833 240:0.6833 241:0.5833 242:0.55 243:0.5667 244:0.55 245:0.55 246:0.5667 247:0.55 248:0.55 249:0.55 250:0.65 251:0.6333 252:0.6167 253:0.6167 254:0.6167 255:0.6167 256:0.6167 257:0.6167 258:0.6167 259:0.6167 260:0.6333 261:0.6333 262:0.6667 263:0.6667 264:0.7333 265:0.7167 266:0.7333 267:0.8333 268:0.8667 269:0.95 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:0.9167 296:0.8 297:0.7333 298:0.6833 299:0.6167 300:0.6333 301:0.6167 302:0.6 303:0.6167 304:0.6167 305:0.6 306:0.6167 307:0.6 308:0.6 309:0.6167 310:0.8167 311:0.8 312:0.5 313:0.4833 314:0.4833 315:0.4833 316:0.4833 317:0.4833 318:0.5 319:0.4833 320:0.5 321:0.4833 322:0.5667 323:0.5667 324:0.5667 325:0.55 326:0.55 327:0.55 328:0.55 329:0.5333 330:0.55 331:0.5333 332:0.5333 333:0.5333 334:0.5333 335:0.5333 336:0.5333 337:0.5333 338:0.5333 339:0.5333 340:0.5333 341:0.5333 342:0.5333 343:0.5333 344:0.5333 345:0.5333 346:0.5333 347:0.5167 348:0.5333 349:0.5167 350:0.5333 351:0.5167 352:0.5333 353:0.5333 354:0.5167 355:0.55 356:0.55 357:0.55 358:0.55 359:0.55 360:0.55
0.3738030152924388 1:0.5167 2:0.5167 3:0.5167 4:0.5167 5:0.5167 6:0.55 7:0.55 8:0.55 9:0.55 10:0.55 11:0.6833 12:0.6833 13:0.7 14:1 15:1 16:1 17:1 18:1 19:1 20:1 21:1 22:1 23:1 24:1 25:1 26:1 27:1 28:0.9 29:0.8833 30:0.8833 31:0.8833 32:0.8833 33:0.4833 34:0.4833 35:0.4833 36:0.4833 37:0.4833 38:0.4833 39:0.4833 40:0.4833 41:0.4833 42:0.4833 43:0.4333 44:0.4333 45:0.4333 46:0.4333 47:0.4333 48:0.4333 49:0.4333 50:0.4333 51:0.4333 52:0.4333 53:0.4333 54:0.4333 55:0.45 56:0.55 57:0.55 58:0.55 59:0.55 60:0.55 61:0.55 62:0.55 63:0.55 64:0.5667 65:0.55 66:0.5667 67:0.5667 68:0.5667 69:0.5667 70:0.5833 71:0.5833 72:0.5833 73:0.5833 74:0.6 75:0.6 76:0.6 77:0.6167 78:0.6333 79:0.6333 80:0.65 81:0.65 82:0.6833 83:0.6833 84:0.7333 85:0.7167 86:0.75 87:0.8 88:0.8 89:0.8333 90:0.8667 91:0.9167 92:0.95 93:1 94:1 95:1 96:0.85 97:0.7833 98:0.7833 99:0.7833 100:0.7833 101:0.8333 102:0.8 103:0.9833 104:0.9833 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:1 118:1 119:1 120:1 121:1 122:1 123:1 124:1 125:1 126:1 127:1 128:0.9833 129:0.8833 130:0.8667 131:0.85 132:0.75 133:0.7333 134:0.7333 135:0.6667 136:0.6333 137:0.6167 138:0.6167 139:0.6 140:0.6 141:0.5833 142:0.56136842 143:0.56136842 144:0.56136842 145:0.56136842 146:0.56136842 147:0.56136842 148:0.56136842 149:0.56136842 150:0.56136842 151:0.56136842 152:0.70178947 153:0.70178947 154:0.70178947 155:0.70178947 156:0.47368421 157:0.4642838 158:0.4642838 159:0.4642838 160:0.4642838 161:0.4642838 162:0.4642838 163:0.4642838 164:0.4642838 165:0.4642838 166:0.4642838 167:0.55353412 168:0.53574834 169:0.53574834 170:0.53574834 171:0.53574834 172:0.53574834 173:0.53574834 174:0.53574834 175:0.53574834 176:0.53574834 177:0.53574834 178:0.53574834 179:0.53574834 180:0.53574834 181:0.55353412 182:0.55353412 183:0.55353412 184:0.51785542 185:0.51785542 186:0.51785542 187:0.51785542 188:0.51785542 189:0.51785542 190:0.51785542 191:0.51785542 192:0.53574834 193:0.53574834 194:0.6964632 195:0.71424898 196:0.71424898 197:0.71424898 198:0.71424898 199:0.7321419 200:0.7321419 201:1 202:1 203:1 204:1 205:1 206:1 207:1 208:1 209:1 210:1 211:1 212:0.94642838 213:0.94642838 214:0.94642838 215:0.94642838 216:0.75003482 217:0.75003482 218:0.75003482 219:0.75003482 220:0.75003482 221:0.6833 222:0.7 223:0.5833 224:0.5833 225:0.5833 226:0.5833 227:0.5833 228:0.5833 229:0.5833 230:0.5833 231:0.5833 232:0.6 233:0.6167 234:0.6833 235:0.6833 236:0.6833 237:0.6833 238:0.6833 239:0.6667 240:0.65 241:0.65 242:0.65 243:0.65 244:0.65 245:0.65 246:0.65 247:0.65 248:0.5333 249:0.5333 250:0.5333 251:0.5333 252:0.5333 253:0.5333 254:0.5333 255:0.5333 256:0.55 257:0.6167 258:0.5833 259:0.5833 260:0.5833 261:0.5833 262:0.5833 263:0.5833 264:0.5833 265:0.5833 266:0.5833 267:0.5833 268:0.5833 269:0.6167 270:0.6167 271:0.6667 272:0.7 273:0.75 274:0.75 275:0.8 276:0.9 277:0.9333 278:0.9667 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:1 296:1 297:1 298:1 299:1 300:1 301:1 302:1 303:1 304:0.8667 305:0.8167 306:0.7167 307:0.6333 308:0.6 309:0.5833 310:0.5833 311:0.5833 312:0.5833 313:0.5833 314:0.5833 315:0.5833 316:0.5833 317:0.5833 318:0.5833 319:0.5833 320:0.5833 321:0.4667 322:0.4667 323:0.4667 324:0.4667 325:0.4667 326:0.4667 327:0.4667 328:0.4667 329:0.4667 330:0.4667 331:0.4667 332:0.4667 333:0.55 334:0.55 335:0.5333 336:0.5333 337:0.5333 338:0.5333 339:0.5333 340:0.5167 341:0.5167 342:0.5167 343:0.5167 344:0.5167 345:0.5167 346:0.5167 347:0.5167 348:0.5167 349:0.5167 350:0.5167 351:0.5167 352:0.5167 353:0.5167 354:0.5167 355:0.5167 356:0.5167 357:0.5167 358:0.5167 359:0.5167 360:0.5167
0.8099883035993928 1:0.5 2:0.5 3:0.5 4:0.5 5:0.5 6:0.5 7:0.5 8:0.5 9:0.5 10:0.5 11:0.5 12:0.5167 13:0.5167 14:0.5167 15:0.5167 16:0.5167 17:0.5167 18:0.5167 19:0.5167 20:0.5167 21:0.5167 22:0.5167 23:0.55 24:0.5667 25:0.5667 26:0.55 27:1 28:1 29:1 30:1 31:1 32:1 33:1 34:1 35:1 36:1 37:1 38:1 39:1 40:1 41:1 42:0.9333 43:0.9333 44:0.9333 45:0.85 46:0.8667 47:0.7333 48:0.7 49:0.6833 50:0.7 51:0.5333 52:0.5333 53:0.5333 54:0.5333 55:0.5333 56:0.5333 57:0.5333 58:0.5333 59:0.4833 60:0.4833 61:0.5 62:0.4833 63:0.5 64:0.4833 65:0.4833 66:0.4833 67:0.4833 68:0.4833 69:0.6167 70:0.6167 71:0.6167 72:0.6167 73:0.6167 74:0.6167 75:0.6333 76:0.6333 77:0.6333 78:0.6333 79:0.6333 80:0.65 81:0.65 82:0.65 83:0.65 84:0.6667 85:0.6667 86:0.6667 87:0.6833 88:0.7 89:0.7167 90:0.7167 91:0.7333 92:0.7667 93:0.7833 94:0.8167 95:0.8167 96:0.8333 97:0.95 98:0.95 99:0.95 100:0.9667 101:0.8167 102:0.8167 103:0.7667 104:0.7667 105:0.7833 106:0.7833 107:0.7833 108:0.7667 109:0.8 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:1 118:1 119:1 120:1 121:1 122:1 123:1 124:1 125:1 126:1 127:1 128:1 129:1 130:1 131:1 132:1 133:1 134:1 135:0.95 136:0.9333 137:0.85 138:0.8 139:0.75 140:0.7167 141:0.7 142:0.66663158 143:0.614 144:0.614 145:0.614 146:0.614 147:0.614 148:0.614 149:0.614 150:0.614 151:0.614 152:0.614 153:0.63157895 154:0.75442105 155:0.73684211 156:0.75442105 157:0.48217672 158:0.48217672 159:0.48217672 160:0.48217672 161:0.48217672 162:0.48217672 163:0.48217672 164:0.48217672 165:0.4642838 166:0.48217672 167:0.48217672 168:0.55353412 169:0.55353412 170:0.55353412 171:0.55353412 172:0.55353412 173:0.55353412 174:0.55353412 175:0.55353412 176:0.55353412 177:0.55353412 178:0.55353412 179:0.55353412 180:0.55353412 181:0.55353412 182:0.53574834 183:0.53574834 184:0.53574834 185:0.53574834 186:0.53574834 187:0.53574834 188:0.53574834 189:0.53574834 190:0.53574834 191:0.53574834 192:0.53574834 193:0.53574834 194:0.66067736 195:0.66067736 196:0.67857028 197:0.6964632 198:0.71424898 199:0.71424898 200:0.71424898 201:0.71424898 202:0.71424898 203:1 204:1 205:1 206:1 207:1 208:1 209:1 210:1 211:1 212:1 213:1 214:1 215:1 216:0.91074968 217:0.91074968 218:0.91074968 219:0.91074968 220:0.91074968 221:0.9167 222:0.9167 223:0.9833 224:0.9833 225:0.5167 226:0.5333 227:0.5167 228:0.5333 229:0.5333 230:0.5333 231:0.5333 232:0.5167 233:0.5333 234:0.5667 235:0.5667 236:0.5667 237:0.6333 238:0.6333 239:0.6333 240:0.6167 241:0.6333 242:0.6167 243:0.5833 244:0.5833 245:0.5833 246:0.5833 247:0.5833 248:0.5833 249:0.5833 250:0.5833 251:0.4667 252:0.4667 253:0.4667 254:0.4667 255:0.4667 256:0.4667 257:0.4667 258:0.4667 259:0.4667 260:0.4667 261:0.4667 262:0.4667 263:0.5167 264:0.5167 265:0.5167 266:0.5167 267:0.5167 268:0.5167 269:0.5167 270:0.5167 271:0.5167 272:0.5167 273:0.5167 274:0.5167 275:0.5167 276:0.5333 277:0.5333 278:0.55 279:0.5667 280:0.5667 281:0.6 282:0.6333 283:0.7167 284:0.75 285:0.7667 286:0.8167 287:0.8833 288:0.9167 289:0.9833 290:1 291:1 292:1 293:1 294:1 295:1 296:1 297:1 298:1 299:1 300:1 301:1 302:1 303:1 304:1 305:1 306:1 307:1 308:1 309:1 310:1 311:1 312:1 313:1 314:0.95 315:0.85 316:0.8167 317:0.7333 318:0.7 319:0.65 320:0.6167 321:0.5833 322:0.5333 323:0.5333 324:0.5167 325:0.5333 326:0.5167 327:0.5167 328:0.5333 329:0.5167 330:0.5333 331:0.5167 332:0.5333 333:0.5333 334:0.5333 335:0.5333 336:0.5333 337:0.6833 338:0.6333 339:0.4333 340:0.4167 341:0.4167 342:0.4167 343:0.4167 344:0.4167 345:0.4167 346:0.4167 347:0.4167 348:0.4167 349:0.4167 350:0.4167 351:0.4333 352:0.5 353:0.5 354:0.5 355:0.5 356:0.5 357:0.5 358:0.5 359:0.5 360:0.5
-0.05641373374437366 1:0.08333 2:0.08333 3:0.08333 4:0.08333 5:0.08333 6:0.08333 7:0.08333 8:0.08333 9:0.08333 10:0.08333 11:0.08333 12:0.08333 13:0.08333 14:0.08333 15:0.08333 16:0.08333 17:0.08333 18:0.08333 19:0.08333 20:0.08333 21:0.08333 22:0.08333 23:0.08333 24:0.08333 25:0.08333 26:0.08333 27:0.08333 28:0.08333 29:0.08333 30:0.08333 31:0.08333 32:0.08333 33:0.08333 34:0.08333 35:0.08333 36:0.08333 37:0.08333 38:0.08333 39:0.08333 40:0.08333 41:0.08333 42:0.08333 43:0.08333 44:0.08333 45:0.08333 46:0.08333 47:0.08333 48:0.08333 49:0.08333 50:0.1 51:0.1 52:0.1 53:0.1 54:0.1 55:0.1 56:0.1 57:0.1 58:0.1167 59:0.1167 60:0.1167 61:0.1167 62:0.1167 63:0.1167 64:0.1167 65:0.1333 66:0.1333 67:0.1333 68:0.1167 69:0.1167 70:0.1167 71:0.1167 72:0.1833 73:0.1833 74:0.1833 75:0.1833 76:0.1833 77:0.1833 78:0.1833 79:0.2 80:0.2167 81:0.2333 82:0.2667 83:0.3 84:0.3333 85:0.4 86:0.4667 87:0.5833 88:0.9 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:0.7833 97:0.7833 98:0.7833 99:0.7833 100:0.7833 101:0.7833 102:0.7833 103:0.7167 104:0.7 105:0.5833 106:0.55 107:0.55 108:0.4833 109:0.45 110:0.4333 111:0.4167 112:0.4 113:0.3833 114:0.3667 115:0.35 116:0.3333 117:0.3167 118:0.3167 119:0.3 120:0.3 121:0.2833 122:0.2833 123:0.2667 124:0.2667 125:0.25 126:0.25 127:0.25 128:0.2333 129:0.2333 130:0.2333 131:0.2167 132:0.2167 133:0.2167 134:0.2167 135:0.2167 136:0.2 137:0.2 138:0.2 139:0.2 140:0.2 141:0.2 142:0.14031579 143:0.14031579 144:0.14031579 145:0.14031579 146:0.14031579 147:0.14031579 148:0.14031579 149:0.14031579 150:0.14031579 151:0.12284211 152:0.12284211 153:0.12284211 154:0.12284211 155:0.12284211 156:0.12284211 157:0.10717538 158:0.10717538 159:0.10717538 160:0.10717538 161:0.10717538 162:0.10717538 163:0.10717538 164:0.10717538 165:0.10717538 166:0.10717538 167:0.10717538 168:0.10717538 169:0.10717538 170:0.10717538 171:0.10717538 172:0.10717538 173:0.10717538 174:0.10717538 175:0.10717538 176:0.10717538 177:0.10717538 178:0.10717538 179:0.10717538 180:0.10717538 181:0.10717538 182:0.10717538 183:0.10717538 184:0.10717538 185:0.10717538 186:0.10717538 187:0.10717538 188:0.10717538 189:0.10717538 190:0.10717538 191:0.10717538 192:0.10717538 193:0.10717538 194:0.10717538 195:0.10717538 196:0.10717538 197:0.10717538 198:0.10717538 199:0.10717538 200:0.10717538 201:0.10717538 202:0.10717538 203:0.10717538 204:0.10717538 205:0.10717538 206:0.10717538 207:0.10717538 208:0.10717538 209:0.10717538 210:0.10717538 211:0.10717538 212:0.12496116 213:0.12496116 214:0.12496116 215:0.12496116 216:0.12496116 217:0.12496116 218:0.12496116 219:0.12496116 220:0.12496116 221:0.2 222:0.2 223:0.2 224:0.2 225:0.2 226:0.2 227:0.2167 228:0.2167 229:0.2167 230:0.2167 231:0.2167 232:0.2333 233:0.2333 234:0.2333 235:0.25 236:0.25 237:0.25 238:0.2667 239:0.2667 240:0.2833 241:0.2833 242:0.3 243:0.3 244:0.3167 245:0.3167 246:0.3333 247:0.35 248:0.3667 249:0.3833 250:0.4 251:0.4167 252:0.4333 253:0.45 254:0.4833 255:0.5167 256:0.55 257:0.5833 258:0.6 259:0.6 260:0.65 261:0.8167 262:0.9 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:0.8333 276:0.6667 277:0.55 278:0.4667 279:0.4167 280:0.3667 281:0.3333 282:0.3 283:0.2833 284:0.25 285:0.2333 286:0.2167 287:0.2 288:0.2 289:0.1833 290:0.1833 291:0.1667 292:0.1667 293:0.15 294:0.15 295:0.15 296:0.1333 297:0.1333 298:0.1333 299:0.1167 300:0.1167 301:0.1167 302:0.1167 303:0.1167 304:0.1167 305:0.1 306:0.1 307:0.1 308:0.1 309:0.1 310:0.1 311:0.1 312:0.1 313:0.08333 314:0.08333 315:0.08333 316:0.08333 317:0.08333 318:0.08333 319:0.08333 320:0.08333 321:0.08333 322:0.08333 323:0.08333 324:0.08333 325:0.08333 326:0.08333 327:0.08333 328:0.08333 329:0.08333 330:0.08333 331:0.08333 332:0.08333 333:0.08333 334:0.08333 335:0.08333 336:0.08333 337:0.08333 338:0.08333 339:0.08333 340:0.08333 341:0.08333 342:0.08333 343:0.08333 344:0.08333 345:0.08333 346:0.08333 347:0.08333 348:0.08333 349:0.08333 350:0.08333 351:0.08333 352:0.08333 353:0.08333 354:0.08333 355:0.08333 356:0.08333 357:0.08333 358:0.08333 359:0.08333 360:0.08333
-0.2669211188117933 1:0.06667 2:0.06667 3:0.06667 4:0.06667 5:0.06667 6:0.06667 7:0.06667 8:0.06667 9:0.06667 10:0.06667 11:0.06667 12:0.06667 13:0.06667 14:0.06667 15:0.06667 16:0.06667 17:0.06667 18:0.06667 19:0.06667 20:0.06667 21:0.06667 22:0.06667 23:0.06667 24:0.06667 25:0.06667 26:0.06667 27:0.06667 28:0.06667 29:0.06667 30:0.06667 31:0.06667 32:0.06667 33:0.06667 34:0.06667 35:0.06667 36:0.06667 37:0.06667 38:0.06667 39:0.06667 40:0.06667 41:0.06667 42:0.06667 43:0.06667 44:0.06667 45:0.06667 46:0.06667 47:0.06667 48:0.06667 49:0.06667 50:0.06667 51:0.06667 52:0.06667 53:0.06667 54:0.06667 55:0.06667 56:0.06667 57:0.08333 58:0.08333 59:0.08333 60:0.08333 61:0.08333 62:0.08333 63:0.08333 64:0.08333 65:0.1 66:0.1 67:0.1 68:0.1 69:0.1167 70:0.1167 71:0.1167 72:0.1333 73:0.1333 74:0.1333 75:0.15 76:0.15 77:0.1667 78:0.1833 79:0.2 80:0.2167 81:0.2333 82:0.2167 83:0.2167 84:0.2167 85:0.2667 86:0.3167 87:0.35 88:0.4667 89:0.5667 90:0.5667 91:0.7833 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:0.7833 106:0.6667 107:0.6333 108:0.5333 109:0.5333 110:0.4833 111:0.4833 112:0.4833 113:0.4167 114:0.4 115:0.3833 116:0.3667 117:0.3667 118:0.35 119:0.3333 120:0.3333 121:0.3167 122:0.3 123:0.3 124:0.3 125:0.2833 126:0.2833 127:0.2667 128:0.2667 129:0.2667 130:0.25 131:0.25 132:0.25 133:0.2333 134:0.2333 135:0.2333 136:0.2 137:0.2 138:0.2167 139:0.2167 140:0.2167 141:0.2 142:0.17547368 143:0.17547368 144:0.15789474 145:0.14031579 146:0.14031579 147:0.14031579 148:0.14031579 149:0.14031579 150:0.14031579 151:0.12284211 152:0.12284211 153:0.12284211 154:0.12284211 155:0.12284211 156:0.12284211 157:0.10717538 158:0.10717538 159:0.10717538 160:0.10717538 161:0.10717538 162:0.10717538 163:0.10717538 164:0.10717538 165:0.10717538 166:0.10717538 167:0.10717538 168:0.10717538 169:0.10717538 170:0.10717538 171:0.10717538 172:0.10717538 173:0.10717538 174:0.10717538 175:0.10717538 176:0.10717538 177:0.10717538 178:0.10717538 179:0.10717538 180:0.10717538 181:0.10717538 182:0.10717538 183:0.10717538 184:0.10717538 185:0.10717538 186:0.10717538 187:0.10717538 188:0.10717538 189:0.10717538 190:0.10717538 191:0.10717538 192:0.10717538 193:0.10717538 194:0.10717538 195:0.10717538 196:0.10717538 197:0.10717538 198:0.10717538 199:0.10717538 200:0.10717538 201:0.10717538 202:0.10717538 203:0.10717538 204:0.10717538 205:0.10717538 206:0.10717538 207:0.10717538 208:0.10717538 209:0.10717538 210:0.10717538 211:0.10717538 212:0.12496116 213:0.12496116 214:0.12496116 215:0.12496116 216:0.12496116 217:0.12496116 218:0.12496116 219:0.12496116 220:0.12496116 221:0.2 222:0.2 223:0.2 224:0.2 225:0.2 226:0.2 227:0.2167 228:0.2167 229:0.2167 230:0.2167 231:0.2167 232:0.2333 233:0.2333 234:0.2333 235:0.25 236:0.25 237:0.25 238:0.2667 239:0.2667 240:0.2833 241:0.2833 242:0.3 243:0.3 244:0.3167 245:0.3167 246:0.3333 247:0.35 248:0.3667 249:0.3833 250:0.4 251:0.4167 252:0.4333 253:0.45 254:0.4667 255:0.4667 256:0.4833 257:0.5167 258:0.55 259:0.6 260:0.65 261:0.7167 262:0.8667 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:0.8333 276:0.6667 277:0.55 278:0.4667 279:0.4167 280:0.3667 281:0.3333 282:0.3 283:0.2833 284:0.25 285:0.2333 286:0.2167 287:0.2 288:0.2 289:0.1833 290:0.1833 291:0.1667 292:0.1667 293:0.15 294:0.15 295:0.15 296:0.1333 297:0.1333 298:0.08333 299:0.08333 300:0.08333 301:0.08333 302:0.08333 303:0.08333 304:0.08333 305:0.08333 306:0.06667 307:0.06667 308:0.06667 309:0.06667 310:0.06667 311:0.06667 312:0.06667 313:0.06667 314:0.06667 315:0.06667 316:0.06667 317:0.06667 318:0.06667 319:0.06667 320:0.06667 321:0.06667 322:0.06667 323:0.06667 324:0.06667 325:0.06667 326:0.06667 327:0.06667 328:0.06667 329:0.06667 330:0.06667 331:0.06667 332:0.06667 333:0.06667 334:0.06667 335:0.06667 336:0.06667 337:0.06667 338:0.06667 339:0.06667 340:0.06667 341:0.06667 342:0.06667 343:0.06667 344:0.06667 345:0.06667 346:0.06667 347:0.06667 348:0.06667 349:0.06667 350:0.06667 351:0.06667 352:0.06667 353:0.06667 354:0.06667 355:0.06667 356:0.06667 357:0.06667 358:0.06667 359:0.06667 360:0.06667
-0.1833006335014134 1:0.06667 2:0.06667 3:0.06667 4:0.06667 5:0.06667 6:0.06667 7:0.06667 8:0.06667 9:0.06667 10:0.06667 11:0.06667 12:0.06667 13:0.06667 14:0.06667 15:0.06667 16:0.06667 17:0.06667 18:0.06667 19:0.06667 20:0.06667 21:0.06667 22:0.06667 23:0.06667 24:0.06667 25:0.06667 26:0.06667 27:0.06667 28:0.06667 29:0.08333 30:0.08333 31:0.08333 32:0.08333 33:0.08333 34:0.08333 35:0.08333 36:0.08333 37:0.08333 38:0.08333 39:0.08333 40:0.08333 41:0.08333 42:0.08333 43:0.08333 44:0.08333 45:0.08333 46:0.08333 47:0.08333 48:0.08333 49:0.08333 50:0.1 51:0.1 52:0.1 53:0.1 54:0.1 55:0.1 56:0.1 57:0.1 58:0.1167 59:0.1167 60:0.1167 61:0.1167 62:0.1167 63:0.1167 64:0.1167 65:0.1167 66:0.1167 67:0.1 68:0.1 69:0.1167 70:0.1167 71:0.1167 72:0.1333 73:0.1333 74:0.1333 75:0.15 76:0.15 77:0.1667 78:0.1833 79:0.2 80:0.2167 81:0.2333 82:0.2667 83:0.3167 84:0.3333 85:0.4 86:0.5 87:0.6667 88:0.8167 89:0.8167 90:1 91:1 92:1 93:1 94:1 95:1 96:0.7 97:0.4 98:0.4 99:0.4333 100:0.3833 101:0.3333 102:0.3 103:0.2833 104:0.25 105:0.2333 106:0.2167 107:0.2 108:0.2 109:0.1833 110:0.1833 111:0.1667 112:0.1667 113:0.15 114:0.15 115:0.15 116:0.1333 117:0.1333 118:0.1333 119:0.1167 120:0.1167 121:0.1167 122:0.1167 123:0.1167 124:0.1167 125:0.1 126:0.06667 127:0.06667 128:0.06667 129:0.06667 130:0.06667 131:0.06667 132:0.06667 133:0.06667 134:0.06667 135:0.06667 136:0.06667 137:0.06667 138:0.06667 139:0.06667 140:0.06667 141:0.06667 142:0.017547368 143:0.017547368 144:0.017547368 145:0.017547368 146:0.017547368 147:0.017547368 148:0.017547368 149:0.017547368 150:0.017547368 151:0.017547368 152:0.017547368 153:0.017547368 154:0.017547368 155:0.017547368 156:0.017547368 221:0.06667 222:0.06667 223:0.06667 224:0.06667 225:0.06667 226:0.06667 227:0.06667 228:0.06667 229:0.06667 230:0.06667 231:0.06667 232:0.06667 233:0.06667 234:0.06667 235:0.06667 236:0.06667 237:0.1 238:0.1167 239:0.1167 240:0.1167 241:0.1167 242:0.1167 243:0.1167 244:0.1167 245:0.1167 246:0.1167 247:0.1 248:0.1 249:0.1167 250:0.1167 251:0.1167 252:0.1333 253:0.1333 254:0.1333 255:0.15 256:0.15 257:0.1667 258:0.1833 259:0.2 260:0.2167 261:0.2333 262:0.2667 263:0.3 264:0.3333 265:0.4 266:0.6 267:0.6 268:0.7833 269:1 270:1 271:1 272:1 273:1 274:1 275:0.8333 276:0.6667 277:0.55 278:0.4667 279:0.4167 280:0.3667 281:0.3333 282:0.3 283:0.2833 284:0.25 285:0.2333 286:0.2167 287:0.2 288:0.2 289:0.1833 290:0.1833 291:0.1667 292:0.1667 293:0.15 294:0.15 295:0.15 296:0.1333 297:0.1333 298:0.1333 299:0.1167 300:0.1167 301:0.1167 302:0.1167 303:0.1167 304:0.1167 305:0.1 306:0.1 307:0.1 308:0.1 309:0.1 310:0.1 311:0.1 312:0.1 313:0.08333 314:0.08333 315:0.08333 316:0.08333 317:0.08333 318:0.08333 319:0.08333 320:0.08333 321:0.08333 322:0.08333 323:0.08333 324:0.06667 325:0.06667 326:0.06667 327:0.06667 328:0.06667 329:0.06667 330:0.06667 331:0.06667 332:0.06667 333:0.06667 334:0.06667 335:0.06667 336:0.06667 337:0.06667 338:0.06667 339:0.06667 340:0.06667 341:0.06667 342:0.06667 343:0.06667 344:0.06667 345:0.06667 346:0.06667 347:0.06667 348:0.06667 349:0.06667 350:0.06667 351:0.06667 352:0.06667 353:0.06667 354:0.06667 355:0.06667 356:0.06667 357:0.06667 358:0.06667 359:0.06667 360:0.06667
-2 1:0.08333 2:0.08333 3:0.08333 4:0.08333 5:0.08333 6:0.08333 7:0.08333 8:0.08333 9:0.08333 10:0.08333 11:0.08333 12:0.08333 13:0.08333 14:0.08333 15:0.08333 16:0.08333 17:0.08333 18:0.08333 19:0.08333 20:0.08333 21:0.08333 22:0.08333 23:0.08333 24:0.08333 25:0.08333 26:0.08333 27:0.08333 28:0.08333 29:0.08333 30:0.08333 31:0.08333 32:0.08333 33:0.08333 34:0.08333 35:0.08333 36:0.08333 37:0.08333 38:0.08333 39:0.08333 40:0.08333 41:0.08333 42:0.08333 43:0.08333 44:0.08333 45:0.08333 46:0.08333 47:0.08333 48:0.08333 49:0.08333 50:0.1 51:0.1 52:0.1 53:0.1 54:0.1 55:0.1 56:0.1 57:0.1 58:0.1167 59:0.1167 60:0.1167 61:0.1167 62:0.1167 63:0.1167 64:0.1333 65:0.1333 66:0.1333 67:0.15 68:0.15 69:0.15 70:0.1667 71:0.1667 72:0.1833 73:0.1833 74:0.1833 75:0.1833 76:0.1833 77:0.1833 78:0.1833 79:0.2 80:0.2167 81:0.2333 82:0.2667 83:0.3 84:0.3333 85:0.4333 86:0.5 87:0.5833 88:0.8 89:1 90:1 91:1 92:1 93:1 94:0.7833 95:0.65 96:0.5333 97:0.4 98:0.3667 99:0.3 100:0.2667 101:0.2333 102:0.2167 103:0.2167 104:0.2167 105:0.2167 106:0.2167 107:0.2 108:0.2 109:0.1833 110:0.1833 111:0.1667 112:0.1667 113:0.15 114:0.15 115:0.15 116:0.1333 117:0.1333 118:0.1333 119:0.1167 120:0.1167 121:0.1167 122:0.1167 123:0.1167 124:0.1167 125:0.1 126:0.06667 127:0.06667 128:0.06667 129:0.06667 130:0.06667 131:0.06667 132:0.06667 133:0.06667 134:0.06667 135:0.06667 136:0.06667 137:0.06667 138:0.06667 139:0.06667 140:0.06667 141:0.06667 142:0.017547368 143:0.017547368 144:0.017547368 145:0.017547368 146:0.017547368 147:0.017547368 148:0.017547368 149:0.017547368 150:0.017547368 151:0.017547368 152:0.017547368 153:0.017547368 154:0.017547368 155:0.017547368 156:0.017547368 221:0.06667 222:0.06667 223:0.06667 224:0.06667 225:0.06667 226:0.06667 227:0.06667 228:0.06667 229:0.06667 230:0.06667 231:0.06667 232:0.06667 233:0.06667 234:0.06667 235:0.06667 236:0.06667 237:0.08333 238:0.08333 239:0.08333 240:0.08333 241:0.08333 242:0.08333 243:0.08333 244:0.08333 245:0.1 246:0.1 247:0.1 248:0.1 249:0.1167 250:0.1167 251:0.1167 252:0.1333 253:0.1333 254:0.1333 255:0.15 256:0.15 257:0.1667 258:0.1833 259:0.2 260:0.2167 261:0.2333 262:0.2667 263:0.3 264:0.3333 265:0.4 266:0.5833 267:0.5833 268:0.7833 269:1 270:1 271:1 272:1 273:1 274:1 275:0.8333 276:0.6667 277:0.55 278:0.5333 279:0.4167 280:0.3667 281:0.3333 282:0.3 283:0.2833 284:0.25 285:0.2333 286:0.2167 287:0.2 288:0.2 289:0.1833 290:0.1833 291:0.1667 292:0.1667 293:0.15 294:0.15 295:0.15 296:0.1333 297:0.1333 298:0.1333 299:0.1167 300:0.1167 301:0.1167 302:0.1167 303:0.1167 304:0.1167 305:0.1 306:0.1 307:0.1 308:0.1 309:0.1 310:0.1 311:0.1 312:0.1 313:0.08333 314:0.08333 315:0.08333 316:0.08333 317:0.08333 318:0.08333 319:0.08333 320:0.08333 321:0.08333 322:0.08333 323:0.08333 324:0.08333 325:0.08333 326:0.08333 327:0.08333 328:0.08333 329:0.08333 330:0.08333 331:0.08333 332:0.08333 333:0.08333 334:0.08333 335:0.08333 336:0.08333 337:0.08333 338:0.08333 339:0.08333 340:0.08333 341:0.08333 342:0.08333 343:0.08333 344:0.08333 345:0.08333 346:0.08333 347:0.08333 348:0.08333 349:0.08333 350:0.08333 351:0.08333 352:0.08333 353:0.08333 354:0.08333 355:0.08333 356:0.08333 357:0.08333 358:0.08333 359:0.08333 360:0.08333
-2 1:0.4833 2:0.4833 3:0.4833 4:0.4833 5:0.4833 6:0.5 7:0.5 8:0.5 9:0.5 10:0.55 11:1 12:1 13:1 14:1 15:1 16:1 17:1 18:1 19:1 20:1 21:1 22:0.8167 23:0.6833 24:0.6667 25:0.6667 26:0.6667 27:0.6667 28:0.6667 29:0.6667 30:0.6667 31:0.6667 32:0.6667 33:1 34:1 35:1 36:1 37:1 38:0.9833 39:0.8 40:0.55 41:0.5333 42:0.5333 43:0.2667 44:0.2667 45:0.25 46:0.25 47:0.25 48:0.2667 49:0.25 50:0.25 51:0.25 52:0.25 53:0.25 54:0.25 55:0.25 56:0.25 57:0.25 58:0.2333 59:0.2333 60:0.2333 61:0.2333 62:0.2333 63:0.2333 64:0.2333 65:0.2333 66:0.2333 67:0.2333 68:0.2333 69:0.2333 70:0.2333 71:0.2333 72:0.2333 73:0.2333 74:0.2333 75:0.2333 76:0.2333 77:0.2333 78:0.2333 79:0.2333 80:0.2333 81:0.2333 82:0.35 83:0.35 84:0.35 85:0.35 86:0.35 87:0.35 88:0.35 89:0.35 90:0.35 91:0.35 92:0.35 93:0.2833 94:0.2833 95:0.2833 96:0.2833 97:0.2833 98:0.2833 99:0.2833 100:0.2833 101:0.2833 102:0.2833 103:0.2833 104:0.2833 105:0.2833 106:0.2833 107:0.2833 108:0.2833 109:0.3 110:0.3 111:0.3333 112:0.4667 113:0.4667 114:0.4833 115:0.4833 116:0.6167 117:0.6167 118:0.6167 119:0.7333 120:0.9167 121:1 122:1 123:1 124:1 125:1 126:1 127:1 128:1 129:0.8833 130:0.7667 131:0.7667 132:0.7667 133:0.6 134:0.6 135:0.55 136:0.5167 137:0.3833 138:0.3667 139:0.3667 140:0.2833 141:0.2833 142:0.24557895 143:0.22810526 144:0.22810526 145:0.24557895 146:0.24557895 147:0.22810526 148:0.24557895 149:0.24557895 150:0.22810526 151:0.22810526 152:0.24557895 153:0.22810526 154:0.22810526 155:0.24557895 156:0.22810526 157:0.21431862 158:0.2321044 159:0.2321044 160:0.26789024 161:0.2321044 162:0.2321044 163:0.21431862 164:0.21431862 165:0.21431862 166:0.21431862 167:0.21431862 168:0.21431862 169:0.21431862 170:0.21431862 171:0.21431862 172:0.21431862 173:0.21431862 174:0.21431862 175:0.21431862 176:0.21431862 177:0.21431862 178:0.21431862 179:0.12496116 180:0.12496116 181:0.12496116 182:0.12496116 183:0.12496116 184:0.12496116 185:0.12496116 186:0.12496116 187:0.12496116 188:0.12496116 189:0.12496116 190:0.12496116 191:0.12496116 192:0.12496116 193:0.12496116 194:0.12496116 195:0.12496116 196:0.12496116 197:0.12496116 198:0.12496116 199:0.12496116 200:0.12496116 201:0.12496116 202:0.12496116 203:0.12496116 204:0.12496116 205:0.12496116 206:0.12496116 207:0.12496116 208:0.21431862 209:0.21431862 210:0.2321044 211:0.21431862 212:0.21431862 213:0.2321044 214:0.2321044 215:0.21431862 216:0.2321044 217:0.2321044 218:0.21431862 219:0.21431862 220:0.2321044 221:0.2833 222:0.2833 223:0.2833 224:0.2833 225:0.3 226:0.3 227:0.3 228:0.25 229:0.25 230:0.2333 231:0.2333 232:0.2333 233:0.2333 234:0.2333 235:0.2333 236:0.2333 237:0.2333 238:0.2333 239:0.2333 240:0.2333 241:0.2333 242:0.2333 243:0.2333 244:0.2333 245:0.2333 246:0.2333 247:0.2333 248:0.2333 249:0.35 250:0.35 251:0.35 252:0.35 253:0.35 254:0.3667 255:0.35 256:0.35 257:0.6 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:0.9833 282:0.9833 283:0.85 284:0.85 285:0.3667 286:0.35 287:0.35 288:0.3667 289:0.35 290:0.3667 291:0.35 292:0.35 293:0.3667 294:0.35 295:0.35 296:0.3333 297:0.3333 298:0.3333 299:0.3333 300:0.3333 301:0.3333 302:0.3333 303:0.3333 304:0.3167 305:0.25 306:0.25 307:0.25 308:0.2333 309:0.2333 310:0.25 311:0.25 312:0.2333 313:0.25 314:0.25 315:0.25 316:0.2333 317:0.25 318:0.25 319:0.25 320:0.2333 321:0.25 322:0.1833 323:0.1833 324:0.1833 325:0.1833 326:0.1833 327:0.1833 328:0.1833 329:0.1833 330:0.1833 331:0.1667 332:0.1667 333:0.1833 334:0.1833 335:0.1833 336:0.1833 337:0.1833 338:0.1833 339:0.1833 340:0.1833 341:0.1833 342:0.1833 343:0.1833 344:0.1833 345:0.1833 346:0.1833 347:0.1833 348:0.1833 349:0.1833 350:0.1833 351:0.1833 352:0.1667 353:0.1667 354:0.2 355:0.4833 356:0.4833 357:0.4833 358:0.4833 359:0.4833 360:0.4833
-0.6980622909351277 1:0.2833 2:0.2833 3:0.2833 4:0.2833 5:0.2833 6:0.2833 7:0.2833 8:0.2833 9:0.2833 10:0.2833 11:0.2833 12:0.2833 13:0.2833 14:0.2833 15:0.2833 16:0.15 17:0.15 18:0.1333 19:0.1333 20:0.1333 21:0.1333 22:0.1333 23:0.1333 24:0.1333 25:0.1333 26:0.1333 27:0.1333 28:0.1333 29:0.1333 30:0.1333 31:0.1333 32:0.1333 33:0.1333 34:0.1333 35:0.1333 36:0.1333 37:0.1333 38:0.1333 39:0.1333 40:0.1333 41:0.1333 42:0.1333 43:0.1333 44:0.1333 45:0.1333 46:0.1333 47:0.1333 48:0.1333 49:0.1333 50:0.1333 51:0.1333 52:0.1333 53:0.1333 54:0.1333 55:0.1333 56:0.1333 57:0.1333 58:0.1333 59:0.2333 60:0.2333 61:0.2333 62:0.2333 63:0.2333 64:0.2333 65:0.25 66:0.25 67:0.25 68:0.25 69:0.2333 70:0.25 71:0.25 72:0.2333 73:0.2333 74:0.25 75:0.3333 76:0.3333 77:0.3333 78:0.3333 79:0.3333 80:0.3333 81:0.3333 82:0.3833 83:0.3833 84:0.3833 85:0.3833 86:0.3833 87:0.3833 88:0.4 89:0.4 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:0.7667 100:0.7667 101:0.7667 102:0.75 103:0.6 104:0.5833 105:0.5833 106:0.5833 107:0.5833 108:0.4167 109:0.4 110:0.4 111:0.4 112:0.4 113:0.4 114:0.4 115:0.4 116:0.4 117:0.4 118:0.2333 119:0.2333 120:0.2333 121:0.2333 122:0.2333 123:0.2333 124:0.2333 125:0.2333 126:0.2333 127:0.2333 128:0.2333 129:0.2333 130:0.2333 131:0.2333 132:0.2333 133:0.2333 134:0.2333 135:0.2333 136:0.2333 137:0.2333 138:0.2333 139:0.2333 140:0.2667 141:0.3333 142:0.29821053 143:0.29821053 144:0.15789474 145:0.15789474 146:0.15789474 147:0.15789474 148:0.15789474 149:0.15789474 150:0.15789474 151:0.15789474 152:0.15789474 153:0.15789474 154:0.15789474 155:0.15789474 156:0.10526316 157:0.089282462 158:0.089282462 159:0.089282462 160:0.071389541 161:0.071389541 162:0.071389541 163:0.071389541 164:0.071389541 165:0.071389541 166:0.071389541 167:0.071389541 168:0.071389541 169:0.035710842 170:0.035710842 171:0.035710842 172:0.035710842 173:0.035710842 174:0.035710842 175:0.035710842 176:0.035710842 177:0.035710842 178:0.035710842 179:0.035710842 180:0.035710842 181:0.035710842 182:0.035710842 183:0.035710842 184:0.035710842 185:0.035710842 186:0.035710842 187:0.035710842 188:0.035710842 189:0.035710842 190:0.035710842 191:0.035710842 192:0.035710842 193:0.035710842 194:0.035710842 195:0.035710842 196:0.035710842 197:0.035710842 198:0.035710842 199:0.035710842 200:0.035710842 201:0.035710842 202:0.035710842 203:0.035710842 204:0.035710842 205:0.035710842 206:0.035710842 207:0.035710842 208:0.035710842 209:0.035710842 210:0.035710842 211:0.035710842 212:0.035710842 213:0.035710842 214:0.035710842 215:0.035710842 216:0.035710842 217:0.035710842 218:0.12496116 219:0.12496116 220:0.12496116 221:0.1833 222:0.1833 223:0.1833 224:0.1833 225:0.1833 226:0.1833 227:0.1833 228:0.1833 229:0.2 230:0.2 231:0.2 232:0.2167 233:0.2 234:0.2 235:0.2 236:0.2 237:0.2 238:0.2 239:0.2 240:0.2 241:0.2167 242:0.2167 243:0.2 244:0.2 245:0.2833 246:0.2833 247:0.3 248:0.2833 249:0.2833 250:0.3 251:0.2833 252:0.2833 253:0.2833 254:0.2833 255:0.2833 256:0.2833 257:0.3 258:0.55 259:0.55 260:0.55 261:0.55 262:0.55 263:0.55 264:0.75 265:0.7333 266:0.9 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:0.8167 280:0.7333 281:0.7333 282:0.5667 283:0.4333 284:0.4167 285:0.4167 286:0.4167 287:0.3833 288:0.3667 289:0.3667 290:0.2833 291:0.2667 292:0.2667 293:0.2667 294:0.2667 295:0.2667 296:0.2667 297:0.2667 298:0.2667 299:0.2667 300:0.2667 301:0.2667 302:0.2667 303:0.2667 304:0.2667 305:0.2667 306:0.2667 307:0.2667 308:0.2667 309:0.1167 310:0.1167 311:0.1167 312:0.1167 313:0.1167 314:0.1167 315:0.1167 316:0.1167 317:0.1167 318:0.1167 319:0.1167 320:0.1167 321:0.1167 322:0.1167 323:0.1167 324:0.1167 325:0.1167 326:0.1167 327:0.1167 328:0.1167 329:0.1167 330:0.1167 331:0.1167 332:0.1167 333:0.1167 334:0.1167 335:0.1167 336:0.1167 337:0.1167 338:0.1167 339:0.1167 340:0.1167 341:0.1167 342:0.1167 343:0.1167 344:0.1167 345:0.1167 346:0.1167 347:0.1167 348:0.1167 349:0.1167 350:0.3 351:0.2833 352:0.2833 353:0.2833 354:0.2833 355:0.2833 356:0.2833 357:0.2833 358:0.2833 359:0.2833 360:0.2833
-2 1:0.15 2:0.15 3:0.15 4:0.15 5:0.15 6:0.15 7:0.15 8:0.15 9:0.15 10:0.15 11:0.15 12:0.15 13:0.15 14:0.15 15:0.15 16:0.2167 17:0.2 18:0.2 19:0.2 20:0.2 21:0.2 22:0.2 23:0.2 24:0.2 25:0.2167 26:0.2167 27:0.2 28:0.2 29:0.2 30:0.1833 31:0.1833 32:0.1833 33:0.1833 34:0.1833 35:0.1833 36:0.1833 37:0.1833 38:0.1833 39:0.1833 40:0.1833 41:0.1833 42:0.1833 43:0.1833 44:0.1833 45:0.1833 46:0.1833 47:0.1833 48:0.1833 49:0.1833 50:0.1833 51:0.1833 52:0.1833 53:0.1833 54:0.1833 55:0.1833 56:0.1833 57:0.25 58:0.25 59:0.25 60:0.25 61:0.25 62:0.25 63:0.2667 64:0.2667 65:0.25 66:0.25 67:0.3167 68:0.3167 69:0.3167 70:0.3167 71:0.3167 72:0.3167 73:0.3167 74:0.3167 75:0.3167 76:0.3167 77:0.3167 78:0.3167 79:0.3167 80:0.3167 81:0.3333 82:0.3333 83:0.3167 84:0.9667 85:0.9667 86:0.9667 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:0.7 97:0.7 98:0.65 99:0.65 100:0.4833 101:0.4833 102:0.4833 103:0.4833 104:0.4833 105:0.4833 106:0.2833 107:0.2833 108:0.2833 109:0.2833 110:0.2833 111:0.2833 112:0.3 113:0.2833 114:0.2833 115:0.3 116:0.2833 117:0.2833 118:0.3 119:0.2833 120:0.2833 121:0.2833 122:0.3 123:0.3 124:0.1333 125:0.1333 126:0.1333 127:0.1333 128:0.1333 129:0.1333 130:0.1333 131:0.1333 132:0.1333 133:0.1333 134:0.1333 135:0.1333 136:0.1333 137:0.1333 138:0.1333 139:0.1333 140:0.1333 141:0.1333 142:0.087684211 143:0.087684211 144:0.087684211 145:0.087684211 146:0.087684211 147:0.087684211 148:0.087684211 149:0.087684211 150:0.087684211 151:0.087684211 152:0.087684211 153:0.087684211 154:0.087684211 155:0.087684211 156:0.087684211 157:0.089282462 158:0.089282462 159:0.089282462 160:0.089282462 161:0.089282462 162:0.089282462 163:0.089282462 164:0.089282462 165:0.089282462 166:0.089282462 167:0.089282462 168:0.089282462 169:0.089282462 170:0.089282462 171:0.089282462 172:0.089282462 173:0.089282462 174:0.089282462 175:0.089282462 176:0.089282462 177:0.089282462 178:0.089282462 179:0.089282462 180:0.089282462 181:0.089282462 182:0.089282462 183:0.089282462 184:0.51785542 185:0.51785542 186:0.51785542 187:0.51785542 188:0.51785542 189:0.51785542 190:0.51785542 191:0.51785542 192:0.160747 193:0.14285408 194:0.14285408 195:0.14285408 196:0.14285408 197:0.14285408 198:0.14285408 199:0.14285408 200:0.14285408 201:0.053603763 202:0.053603763 203:0.053603763 204:0.053603763 205:0.071389541 206:0.071389541 207:0.071389541 208:0.053603763 209:0.053603763 210:0.053603763 211:0.071389541 212:0.071389541 213:0.071389541 214:0.071389541 215:0.071389541 216:0.053603763 217:0.071389541 218:0.071389541 219:0.071389541 220:0.071389541 221:0.1333 222:0.1333 223:0.1167 224:0.1167 225:0.1333 226:0.1333 227:0.1333 228:0.1333 229:0.1167 230:0.1167 231:0.1167 232:0.1167 233:0.1167 234:0.1333 235:0.1333 236:0.1333 237:0.1333 238:0.1333 239:0.1333 240:0.1333 241:0.1333 242:0.25 243:0.25 244:0.1333 245:0.1333 246:0.1333 247:0.1333 248:0.1333 249:0.1333 250:0.1333 251:0.1333 252:0.1333 253:0.1333 254:0.1333 255:0.2667 256:0.2833 257:0.2833 258:0.2833 259:0.2833 260:0.3833 261:0.3833 262:0.3667 263:0.3833 264:0.3667 265:0.4 266:0.6333 267:0.6333 268:0.6333 269:0.6333 270:0.6333 271:0.6333 272:0.6333 273:0.6333 274:0.6667 275:0.7333 276:1 277:1 278:1 279:1 280:0.9167 281:0.85 282:0.8333 283:0.6833 284:0.6333 285:0.6333 286:0.55 287:0.5333 288:0.5333 289:0.5333 290:0.3833 291:0.3833 292:0.3833 293:0.3833 294:0.3833 295:0.3833 296:0.3833 297:0.3833 298:0.3833 299:0.3833 300:0.2167 301:0.2167 302:0.2167 303:0.2167 304:0.2167 305:0.2167 306:0.2167 307:0.2167 308:0.2167 309:0.2167 310:0.2167 311:0.2167 312:0.2167 313:0.2167 314:0.2167 315:0.2167 316:0.2167 317:0.2167 318:0.2167 319:0.2167 320:0.2167 321:0.2167 322:0.2333 323:0.2333 324:0.2333 325:0.3667 326:0.3667 327:0.3667 328:0.3667 329:0.3667 330:0.3667 331:0.3667 332:0.3667 333:0.3667 334:0.3667 335:0.3333 336:0.3333 337:0.3333 338:0.3333 339:0.3333 340:0.3333 341:0.3333 342:0.15 343:0.15 344:0.15 345:0.15 346:0.15 347:0.15 348:0.15 349:0.15 350:0.15 351:0.15 352:0.15 353:0.15 354:0.15 355:0.15 356:0.15 357:0.15 358:0.15 359:0.15 360:0.15
-2 1:0.15 2:0.15 3:0.15 4:0.3167 5:0.3167 6:0.3167 7:0.3167 8:0.2 9:0.2 10:0.2 11:0.2167 12:0.2167 13:0.2 14:0.2167 15:0.2167 16:0.2167 17:0.2167 18:0.2167 19:0.1833 20:0.1833 21:0.1667 22:0.1667 23:0.1833 24:0.1833 25:0.1833 26:0.1667 27:0.1667 28:0.1667 29:0.1667 30:0.1667 31:0.1667 32:0.1667 33:0.1667 34:0.1667 35:0.1667 36:0.1833 37:0.1833 38:0.1667 39:0.1667 40:0.1667 41:0.1667 42:0.1667 43:0.1667 44:0.1667 45:0.1667 46:0.1833 47:0.1667 48:0.1667 49:0.1667 50:0.1667 51:0.1667 52:0.2333 53:0.2333 54:0.2333 55:0.2333 56:0.2333 57:0.2333 58:0.2333 59:0.2333 60:0.2333 61:0.2333 62:0.2333 63:0.2333 64:0.2333 65:0.3 66:0.3 67:0.3 68:0.3 69:0.3 70:0.3 71:0.3 72:0.3 73:0.3 74:0.3 75:0.3 76:0.3 77:0.3 78:0.3 79:0.3 80:0.3 81:0.3167 82:0.3167 83:0.3 84:0.95 85:0.95 86:0.95 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:0.6667 97:0.6667 98:0.6167 99:0.6167 100:0.4667 101:0.4667 102:0.4667 103:0.45 104:0.45 105:0.45 106:0.45 107:0.2667 108:0.25 109:0.25 110:0.2667 111:0.2667 112:0.25 113:0.2667 114:0.2667 115:0.25 116:0.25 117:0.2667 118:0.2667 119:0.25 120:0.2667 121:0.2667 122:0.25 123:0.25 124:0.25 125:0.2667 126:0.2667 127:0.2667 128:0.65 129:0.1167 130:0.1167 131:0.1167 132:0.1167 133:0.1167 134:0.1167 135:0.1167 136:0.1167 137:0.1167 138:0.1167 139:0.1167 140:0.1167 141:0.1167 142:0.070210526 143:0.070210526 144:0.070210526 145:0.070210526 146:0.070210526 147:0.070210526 148:0.070210526 149:0.070210526 150:0.070210526 151:0.070210526 152:0.070210526 153:0.070210526 154:0.070210526 155:0.070210526 156:0.070210526 157:0.053603763 158:0.053603763 159:0.053603763 160:0.053603763 161:0.053603763 162:0.053603763 163:0.053603763 164:0.053603763 165:0.053603763 166:0.053603763 167:0.053603763 168:0.053603763 169:0.053603763 170:0.071389541 171:0.089282462 172:0.089282462 173:0.089282462 174:0.089282462 175:0.089282462 176:0.089282462 177:0.089282462 178:0.089282462 179:0.089282462 180:0.089282462 181:0.089282462 182:0.089282462 183:0.089282462 184:0.089282462 185:0.089282462 186:0.089282462 187:0.089282462 188:0.089282462 189:0.089282462 190:0.51785542 191:0.51785542 192:0.51785542 193:0.51785542 194:0.51785542 195:0.53574834 196:0.53574834 197:0.53574834 198:0.53574834 199:0.53574834 200:0.53574834 201:0.160747 202:0.160747 203:0.160747 204:0.160747 205:0.160747 206:0.071389541 207:0.071389541 208:0.071389541 209:0.071389541 210:0.071389541 211:0.071389541 212:0.071389541 213:0.071389541 214:0.071389541 215:0.071389541 216:0.071389541 217:0.071389541 218:0.071389541 219:0.071389541 220:0.071389541 221:0.1333 222:0.1333 223:0.1333 224:0.1333 225:0.1333 226:0.1333 227:0.1333 228:0.1333 229:0.1333 230:0.1333 231:0.1333 232:0.1333 233:0.1333 234:0.1333 235:0.1333 236:0.1333 237:0.1333 238:0.1333 239:0.1333 240:0.1333 241:0.1333 242:0.1333 243:0.1333 244:0.1333 245:0.1333 246:0.1333 247:0.15 248:0.15 249:0.15 250:0.15 251:0.15 252:0.15 253:0.15 254:0.15 255:0.15 256:0.15 257:0.1667 258:0.3 259:0.3 260:0.3 261:0.4 262:0.4 263:0.4 264:0.4 265:0.4 266:0.4 267:0.4 268:0.65 269:0.65 270:0.65 271:0.65 272:0.6667 273:0.6667 274:0.7167 275:0.7167 276:1 277:1 278:1 279:1 280:0.95 281:0.8833 282:0.8667 283:0.6833 284:0.6333 285:0.5833 286:0.5667 287:0.5667 288:0.4167 289:0.4 290:0.4 291:0.4 292:0.4 293:0.4 294:0.4 295:0.4 296:0.4 297:0.4 298:0.4 299:0.2667 300:0.25 301:0.25 302:0.25 303:0.2333 304:0.25 305:0.25 306:0.25 307:0.2333 308:0.25 309:0.25 310:0.25 311:0.25 312:0.25 313:0.25 314:0.25 315:0.25 316:0.25 317:0.25 318:0.2333 319:0.2333 320:0.4 321:0.4 322:0.4 323:0.4 324:0.4 325:0.4 326:0.4 327:0.3667 328:0.35 329:0.35 330:0.15 331:0.15 332:0.15 333:0.15 334:0.15 335:0.15 336:0.15 337:0.15 338:0.15 339:0.15 340:0.15 341:0.15 342:0.15 343:0.15 344:0.15 345:0.15 346:0.15 347:0.15 348:0.15 349:0.15 350:0.15 351:0.15 352:0.15 353:0.15 354:0.15 355:0.15 356:0.15 357:0.15 358:0.15 359:0.15 360:0.15
-0.3333908625310683 1:0.3 2:0.3 3:0.3 4:0.1833 5:0.1833 6:0.1833 7:0.1833 8:0.1833 9:0.1833 10:0.1833 11:0.1833 12:0.1833 13:0.1833 14:0.1833 15:0.1667 16:0.15 17:0.15 18:0.1333 19:0.1333 20:0.1333 21:0.1333 22:0.1333 23:0.1333 24:0.1333 25:0.1333 26:0.1333 27:0.1333 28:0.1333 29:0.15 30:0.15 31:0.1333 32:0.1333 33:0.1333 34:0.1333 35:0.15 36:0.15 37:0.15 38:0.1333 39:0.1333 40:0.1333 41:0.1333 42:0.15 43:0.1333 44:0.1333 45:0.1333 46:0.1333 47:0.1333 48:0.1333 49:0.1333 50:0.15 51:0.15 52:0.2167 53:0.2 54:0.2 55:0.2 56:0.2 57:0.2 58:0.2 59:0.2 60:0.2 61:0.2167 62:0.2167 63:0.2 64:0.2 65:0.2667 66:0.2667 67:0.2667 68:0.2667 69:0.2667 70:0.2667 71:0.2667 72:0.2667 73:0.2833 74:0.2667 75:0.2667 76:0.2833 77:0.2833 78:0.2667 79:0.2667 80:0.2833 81:0.2667 82:0.2667 83:0.2667 84:0.2667 85:0.2667 86:0.9167 87:0.9167 88:0.9833 89:0.9833 90:1 91:1 92:1 93:0.9667 94:0.95 95:0.95 96:0.95 97:0.95 98:0.65 99:0.65 100:0.6 101:0.6 102:0.6 103:0.4333 104:0.4333 105:0.4333 106:0.4333 107:0.4333 108:0.4333 109:0.4333 110:0.4333 111:0.4333 112:0.25 113:0.25 114:0.25 115:0.25 116:0.25 117:0.25 118:0.25 119:0.25 120:0.25 121:0.25 122:0.25 123:0.25 124:0.25 125:0.25 126:0.25 127:0.25 128:0.25 129:0.25 130:0.25 131:0.25 132:0.6333 133:0.5333 134:0.5333 135:0.5167 136:0.5167 137:0.5167 138:0.5167 139:0.5167 140:0.5167 141:0.5167 142:0.49126316 143:0.070210526 144:0.070210526 145:0.070210526 146:0.070210526 147:0.070210526 148:0.070210526 149:0.070210526 150:0.070210526 151:0.070210526 152:0.070210526 153:0.070210526 154:0.070210526 155:0.070210526 156:0.070210526 157:0.053603763 158:0.053603763 159:0.053603763 160:0.053603763 161:0.053603763 162:0.053603763 163:0.053603763 164:0.053603763 165:0.053603763 166:0.053603763 167:0.053603763 168:0.053603763 169:0.053603763 170:0.053603763 171:0.053603763 172:0.053603763 173:0.053603763 174:0.053603763 175:0.053603763 176:0.053603763 177:0.053603763 178:0.053603763 179:0.053603763 180:0.053603763 181:0.053603763 182:0.053603763 183:0.053603763 184:0.053603763 185:0.10717538 186:0.10717538 187:0.10717538 188:0.10717538 189:0.10717538 190:0.10717538 191:0.10717538 192:0.10717538 193:0.10717538 194:0.10717538 195:0.10717538 196:0.10717538 197:0.10717538 198:0.10717538 199:0.10717538 200:0.53574834 201:0.51785542 202:0.51785542 203:0.51785542 204:0.51785542 205:0.51785542 206:0.51785542 207:0.51785542 208:0.1964257 209:0.1964257 210:0.1964257 211:0.1964257 212:0.1964257 213:0.10717538 214:0.10717538 215:0.10717538 216:0.10717538 217:0.10717538 218:0.10717538 219:0.10717538 220:0.10717538 221:0.1667 222:0.1667 223:0.1667 224:0.1667 225:0.1667 226:0.1667 227:0.1667 228:0.1667 229:0.1667 230:0.1667 231:0.1667 232:0.1667 233:0.1667 234:0.1667 235:0.1667 236:0.1667 237:0.1667 238:0.1667 239:0.1667 240:0.1667 241:0.1667 242:0.1667 243:0.1667 244:0.1667 245:0.1667 246:0.3167 247:0.3167 248:0.3167 249:0.3167 250:0.3167 251:0.3167 252:0.3167 253:0.3167 254:0.3333 255:0.3333 256:0.3333 257:0.3333 258:0.3333 259:0.4333 260:0.4333 261:0.4333 262:0.45 263:0.45 264:0.5 265:0.6833 266:0.6833 267:0.7333 268:0.7167 269:0.7167 270:0.7167 271:0.7167 272:0.7167 273:0.7167 274:0.7167 275:1 276:1 277:1 278:1 279:0.9 280:0.9 281:0.7167 282:0.65 283:0.6167 284:0.5667 285:0.5833 286:0.4167 287:0.4333 288:0.4167 289:0.4167 290:0.4167 291:0.4167 292:0.4167 293:0.4167 294:0.4167 295:0.2667 296:0.25 297:0.25 298:0.2667 299:0.2667 300:0.25 301:0.2667 302:0.2667 303:0.2667 304:0.2667 305:0.2667 306:0.2667 307:0.25 308:0.2667 309:0.2667 310:0.25 311:0.25 312:0.2667 313:0.2667 314:0.2667 315:0.2667 316:0.4333 317:0.3833 318:0.15 319:0.15 320:0.15 321:0.15 322:0.15 323:0.15 324:0.15 325:0.15 326:0.1333 327:0.1333 328:0.1333 329:0.1333 330:0.1333 331:0.1333 332:0.1333 333:0.15 334:0.15 335:0.1333 336:0.1333 337:0.1333 338:0.1333 339:0.15 340:0.15 341:0.15 342:0.1333 343:0.1333 344:0.1333 345:0.15 346:0.15 347:0.15 348:0.1333 349:0.1333 350:0.1333 351:0.1333 352:0.1333 353:0.1333 354:0.1333 355:0.1333 356:0.1333 357:0.1333 358:0.3 359:0.3 360:0.3
-1.281383192868089 1:0.1833 2:0.1833 3:0.1833 4:0.15 5:0.1333 6:0.1333 7:0.1333 8:0.1333 9:0.1333 10:0.1333 11:0.1333 12:0.1333 13:0.1333 14:0.1333 15:0.1333 16:0.1333 17:0.1333 18:0.1333 19:0.1333 20:0.1333 21:0.1333 22:0.1333 23:0.1333 24:0.1333 25:0.1333 26:0.1333 27:0.1333 28:0.1333 29:0.1333 30:0.1333 31:0.1333 32:0.1333 33:0.1333 34:0.1333 35:0.1333 36:0.1333 37:0.1333 38:0.1333 39:0.1333 40:0.1333 41:0.1333 42:0.1333 43:0.1833 44:0.1833 45:0.1833 46:0.1833 47:0.1833 48:0.1833 49:0.1833 50:0.1833 51:0.1833 52:0.1833 53:0.1833 54:0.1833 55:0.1833 56:0.1833 57:0.1833 58:0.1833 59:0.1833 60:0.1833 61:0.1833 62:0.25 63:0.25 64:0.25 65:0.25 66:0.25 67:0.25 68:0.25 69:0.25 70:0.25 71:0.25 72:0.25 73:0.25 74:0.25 75:0.25 76:0.25 77:0.25 78:0.25 79:0.25 80:0.25 81:0.25 82:0.2667 83:0.25 84:0.25 85:0.25 86:0.8833 87:0.9 88:0.95 89:0.9667 90:0.9667 91:1 92:1 93:1 94:0.9167 95:0.9167 96:0.9167 97:0.9167 98:0.6333 99:0.6333 100:0.6167 101:0.6167 102:0.5667 103:0.5667 104:0.4 105:0.4 106:0.4 107:0.4 108:0.4 109:0.4 110:0.4 111:0.4 112:0.4 113:0.4 114:0.4 115:0.2167 116:0.2167 117:0.2167 118:0.2167 119:0.2333 120:0.2167 121:0.2167 122:0.2333 123:0.2333 124:0.2167 125:0.2167 126:0.2333 127:0.2333 128:0.2167 129:0.2167 130:0.2167 131:0.2333 132:0.2167 133:0.2167 134:0.2167 135:0.2333 136:0.2333 137:0.2333 138:0.5167 139:0.5167 140:0.5167 141:0.5167 142:0.49126316 143:0.49126316 144:0.49126316 145:0.49126316 146:0.49126316 147:0.49126316 148:0.64915789 149:0.64915789 150:0.070210526 151:0.070210526 152:0.070210526 153:0.070210526 154:0.070210526 155:0.070210526 156:0.070210526 157:0.053603763 158:0.053603763 159:0.053603763 160:0.053603763 161:0.053603763 162:0.053603763 163:0.053603763 164:0.053603763 165:0.053603763 166:0.053603763 167:0.053603763 168:0.053603763 169:0.053603763 170:0.053603763 171:0.053603763 172:0.053603763 173:0.053603763 174:0.053603763 175:0.053603763 176:0.053603763 177:0.053603763 178:0.053603763 179:0.053603763 180:0.053603763 181:0.053603763 182:0.053603763 183:0.053603763 184:0.053603763 185:0.053603763 186:0.053603763 187:0.053603763 188:0.053603763 189:0.053603763 190:0.053603763 191:0.053603763 192:0.10717538 193:0.10717538 194:0.53574834 195:0.55353412 196:0.55353412 197:0.55353412 198:0.55353412 199:0.55353412 200:0.55353412 201:0.55353412 202:0.55353412 203:0.53574834 204:0.53574834 205:0.53574834 206:0.53574834 207:0.53574834 208:0.53574834 209:0.53574834 210:0.53574834 211:0.53574834 212:0.53574834 213:0.21431862 214:0.21431862 215:0.1964257 216:0.1964257 217:0.1964257 218:0.1964257 219:0.1964257 220:0.1964257 221:0.25 222:0.2 223:0.1833 224:0.1833 225:0.1833 226:0.1833 227:0.1833 228:0.1833 229:0.1833 230:0.1833 231:0.1833 232:0.1833 233:0.1833 234:0.1833 235:0.1833 236:0.1833 237:0.1833 238:0.1833 239:0.1833 240:0.1833 241:0.1833 242:0.1833 243:0.1833 244:0.1833 245:0.1833 246:0.1833 247:0.1833 248:0.1833 249:0.35 250:0.3333 251:0.35 252:0.3333 253:0.35 254:0.35 255:0.3333 256:0.35 257:0.35 258:0.35 259:0.35 260:0.4667 261:0.45 262:0.4667 263:0.45 264:0.45 265:0.45 266:0.4667 267:0.7167 268:0.7167 269:0.7167 270:0.7167 271:0.7167 272:0.7167 273:0.7333 274:0.7333 275:1 276:1 277:1 278:1 279:1 280:0.9167 281:0.75 282:0.65 283:0.6 284:0.5833 285:0.45 286:0.4333 287:0.45 288:0.4333 289:0.45 290:0.4333 291:0.45 292:0.3 293:0.2833 294:0.2833 295:0.2667 296:0.2667 297:0.2833 298:0.2667 299:0.2667 300:0.2833 301:0.2833 302:0.2667 303:0.2833 304:0.2833 305:0.2667 306:0.2833 307:0.2833 308:0.2667 309:0.2667 310:0.3 311:0.4333 312:0.4167 313:0.4167 314:0.4 315:0.4 316:0.1667 317:0.15 318:0.15 319:0.15 320:0.15 321:0.15 322:0.15 323:0.15 324:0.15 325:0.15 326:0.15 327:0.15 328:0.15 329:0.1667 330:0.15 331:0.15 332:0.15 333:0.15 334:0.15 335:0.15 336:0.15 337:0.15 338:0.15 339:0.15 340:0.15 341:0.15 342:0.15 343:0.15 344:0.15 345:0.15 346:0.15 347:0.1667 348:0.3 349:0.3 350:0.3 351:0.3 352:0.3 353:0.3 354:0.3 355:0.3 356:0.3 357:0.3 358:0.3 359:0.1833 360:0.1833
-0.008592076477101866 1:0.1167 2:0.1167 3:0.1167 4:0.1167 5:0.1167 6:0.1167 7:0.1167 8:0.1167 9:0.1167 10:0.1167 11:0.1167 12:0.1167 13:0.1167 14:0.1167 15:0.1167 16:0.1167 17:0.1167 18:0.1167 19:0.1167 20:0.1167 21:0.1167 22:0.1167 23:0.1167 24:0.1167 25:0.1167 26:0.1167 27:0.1167 28:0.1167 29:0.1167 30:0.1167 31:0.1167 32:0.1167 33:0.1167 34:0.1167 35:0.1167 36:0.1167 37:0.1167 38:0.1167 39:0.1167 40:0.1667 41:0.1667 42:0.1667 43:0.1667 44:0.1667 45:0.1667 46:0.1667 47:0.1667 48:0.1667 49:0.1667 50:0.1667 51:0.1667 52:0.1667 53:0.1667 54:0.1667 55:0.1667 56:0.1667 57:0.1667 58:0.1667 59:0.1667 60:0.2333 61:0.2167 62:0.2167 63:0.2333 64:0.2167 65:0.2167 66:0.2167 67:0.2167 68:0.2333 69:0.2333 70:0.2333 71:0.2333 72:0.2333 73:0.2333 74:0.2333 75:0.2333 76:0.2333 77:0.2333 78:0.2333 79:0.2333 80:0.2333 81:0.2333 82:0.2333 83:0.2333 84:0.2333 85:0.2333 86:0.8667 87:0.8667 88:0.9333 89:0.9333 90:1 91:1 92:1 93:0.8667 94:0.8667 95:0.8667 96:0.8667 97:0.8667 98:0.8667 99:0.6 100:0.5833 101:0.5833 102:0.5667 103:0.5667 104:0.5667 105:0.3833 106:0.3833 107:0.3833 108:0.3833 109:0.3833 110:0.3833 111:0.3833 112:0.3833 113:0.3833 114:0.3833 115:0.3833 116:0.3833 117:0.4 118:0.2 119:0.2 120:0.2167 121:0.2167 122:0.2 123:0.2167 124:0.2167 125:0.2167 126:0.2167 127:0.2 128:0.2167 129:0.2167 130:0.2167 131:0.2 132:0.2167 133:0.2167 134:0.2167 135:0.2 136:0.2 137:0.2167 138:0.2167 139:0.2167 140:0.2167 141:0.2167 142:0.45610526 143:0.45610526 144:0.45610526 145:0.45610526 146:0.45610526 147:0.45610526 148:0.45610526 149:0.45610526 150:0.50873684 151:0.63157895 152:0.63157895 153:0.63157895 154:0.614 155:0.614 156:0.614 157:0.14285408 158:0.14285408 159:0.14285408 160:0.14285408 161:0.14285408 162:0.14285408 163:0.14285408 164:0.053603763 165:0.053603763 166:0.053603763 167:0.053603763 168:0.053603763 169:0.053603763 170:0.053603763 171:0.053603763 172:0.053603763 173:0.053603763 174:0.053603763 175:0.053603763 176:0.053603763 177:0.053603763 178:0.053603763 179:0.053603763 180:0.053603763 181:0.053603763 182:0.053603763 183:0.053603763 184:0.053603763 185:0.053603763 186:0.053603763 187:0.053603763 188:0.053603763 189:0.053603763 190:0.053603763 191:0.053603763 192:0.053603763 193:0.053603763 194:0.053603763 195:0.053603763 196:0.053603763 197:0.053603763 198:0.053603763 199:0.053603763 200:0.053603763 201:0.053603763 202:0.053603763 203:0.053603763 204:0.053603763 205:0.053603763 206:0.53574834 207:0.53574834 208:0.53574834 209:0.55353412 210:0.53574834 211:0.53574834 212:0.53574834 213:0.53574834 214:0.55353412 215:0.53574834 216:0.24999732 217:0.21431862 218:0.21431862 219:0.21431862 220:0.21431862 221:0.2667 222:0.2667 223:0.2667 224:0.2667 225:0.2667 226:0.2 227:0.2 228:0.2167 229:0.2167 230:0.2167 231:0.2 232:0.2167 233:0.2167 234:0.2167 235:0.2 236:0.2167 237:0.2167 238:0.2167 239:0.2167 240:0.2 241:0.2167 242:0.2167 243:0.2 244:0.2 245:0.2167 246:0.2167 247:0.2167 248:0.2167 249:0.2167 250:0.2167 251:0.2167 252:0.3667 253:0.35 254:0.3667 255:0.35 256:0.35 257:0.3667 258:0.3833 259:0.3833 260:0.3833 261:0.4833 262:0.4833 263:0.4833 264:0.4833 265:0.4833 266:0.4833 267:0.95 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:0.95 281:0.7833 282:0.65 283:0.6167 284:0.6167 285:0.6167 286:0.4833 287:0.4667 288:0.4667 289:0.4667 290:0.4667 291:0.3167 292:0.3 293:0.3 294:0.3 295:0.3 296:0.3 297:0.3 298:0.3 299:0.3 300:0.3 301:0.3 302:0.3 303:0.3 304:0.3 305:0.3 306:0.3 307:0.4667 308:0.1833 309:0.1833 310:0.1833 311:0.1667 312:0.1667 313:0.1667 314:0.1667 315:0.1667 316:0.1667 317:0.15 318:0.1667 319:0.1667 320:0.1667 321:0.1667 322:0.1667 323:0.1667 324:0.1667 325:0.1667 326:0.1667 327:0.1667 328:0.1667 329:0.1667 330:0.1667 331:0.1667 332:0.1667 333:0.1667 334:0.1667 335:0.1667 336:0.1667 337:0.1667 338:0.1667 339:0.15 340:0.3167 341:0.3 342:0.3 343:0.3 344:0.3 345:0.3 346:0.3 347:0.3 348:0.3 349:0.3 350:0.3 351:0.3 352:0.3 353:0.3 354:0.1833 355:0.1833 356:0.1833 357:0.1833 358:0.1167 359:0.1167 360:0.1167
-0.5505324532054231 1:0.1167 2:0.1167 3:0.1167 4:0.1167 5:0.1167 6:0.1167 7:0.1167 8:0.1167 9:0.1167 10:0.1167 11:0.1167 12:0.1167 13:0.1167 14:0.1167 15:0.1167 16:0.1167 17:0.1167 18:0.1167 19:0.1167 20:0.1167 21:0.1167 22:0.1167 23:0.1167 24:0.1167 25:0.1167 26:0.15 27:0.15 28:0.15 29:0.15 30:0.15 31:0.15 32:0.15 33:0.15 34:0.15 35:0.15 36:0.15 37:0.15 38:0.15 39:0.15 40:0.15 41:0.15 42:0.15 43:0.15 44:0.15 45:0.15 46:0.15 47:0.15 48:0.15 49:0.15 50:0.15 51:0.15 52:0.2167 53:0.2 54:0.2 55:0.2 56:0.2 57:0.2 58:0.2 59:0.2 60:0.2 61:0.2167 62:0.2167 63:0.2 64:0.2 65:0.2 66:0.2 67:0.2167 68:0.2167 69:0.2167 70:0.2167 71:0.2 72:0.2167 73:0.2167 74:0.2167 75:0.2167 76:0.2167 77:0.2167 78:0.2167 79:0.2 80:0.2167 81:0.2167 82:0.2 83:0.2 84:0.2 85:0.8333 86:0.8333 87:0.8333 88:0.9 89:0.9167 90:1 91:1 92:1 93:0.8167 94:0.8167 95:0.8167 96:0.8167 97:0.8167 98:0.8167 99:0.5667 100:0.5667 101:0.55 102:0.55 103:0.5333 104:0.5333 105:0.5333 106:0.35 107:0.35 108:0.3667 109:0.35 110:0.3667 111:0.35 112:0.35 113:0.3667 114:0.35 115:0.35 116:0.3667 117:0.35 118:0.35 119:0.3667 120:0.3667 121:0.1833 122:0.1833 123:0.1833 124:0.1833 125:0.1833 126:0.1833 127:0.1833 128:0.1833 129:0.1833 130:0.1833 131:0.1833 132:0.1833 133:0.1833 134:0.1833 135:0.1833 136:0.1833 137:0.1833 138:0.1833 139:0.1833 140:0.1833 141:0.1833 142:0.14031579 143:0.14031579 144:0.14031579 145:0.14031579 146:0.14031579 147:0.45610526 148:0.43863158 149:0.43863158 150:0.43863158 151:0.45610526 152:0.47368421 153:0.63157895 154:0.63157895 155:0.614 156:0.59652632 157:0.58931996 158:0.58931996 159:0.58931996 160:0.58931996 161:0.58931996 162:0.58931996 163:0.58931996 164:0.58931996 165:0.58931996 166:0.14285408 167:0.14285408 168:0.14285408 169:0.14285408 170:0.14285408 171:0.14285408 172:0.14285408 173:0.14285408 174:0.14285408 175:0.14285408 176:0.14285408 177:0.14285408 178:0.053603763 179:0.053603763 180:0.053603763 181:0.053603763 182:0.053603763 183:0.053603763 184:0.053603763 185:0.053603763 186:0.053603763 187:0.053603763 188:0.053603763 189:0.053603763 190:0.053603763 191:0.053603763 192:0.053603763 193:0.053603763 194:0.053603763 195:0.053603763 196:0.053603763 197:0.053603763 198:0.053603763 199:0.053603763 200:0.053603763 201:0.053603763 202:0.053603763 203:0.053603763 204:0.053603763 205:0.053603763 206:0.053603763 207:0.053603763 208:0.053603763 209:0.053603763 210:0.053603763 211:0.053603763 212:0.053603763 213:0.55353412 214:0.55353412 215:0.55353412 216:0.55353412 217:0.57142704 218:1 219:1 220:0.53574834 221:0.3 222:0.3 223:0.2833 224:0.2833 225:0.2833 226:0.3 227:0.2833 228:0.2833 229:0.3 230:0.2333 231:0.2333 232:0.2333 233:0.2333 234:0.2333 235:0.2167 236:0.2333 237:0.2333 238:0.2333 239:0.2333 240:0.2333 241:0.2333 242:0.2333 243:0.2333 244:0.2333 245:0.2333 246:0.2333 247:0.2333 248:0.2333 249:0.2333 250:0.2333 251:0.2333 252:0.4 253:0.4 254:0.4 255:0.3833 256:0.4 257:0.4 258:0.4 259:0.4 260:0.4 261:0.5 262:0.5 263:0.5 264:0.5 265:0.5 266:0.5 267:0.9833 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:0.8 281:0.7667 282:0.65 283:0.6333 284:0.6333 285:0.5167 286:0.5167 287:0.5 288:0.5167 289:0.35 290:0.3333 291:0.3333 292:0.3333 293:0.3333 294:0.3333 295:0.3333 296:0.3333 297:0.3333 298:0.3333 299:0.3333 300:0.3333 301:0.3333 302:0.3333 303:0.3333 304:0.3333 305:0.3333 306:0.1833 307:0.1833 308:0.1833 309:0.1833 310:0.1833 311:0.1833 312:0.1833 313:0.1833 314:0.1833 315:0.1833 316:0.1833 317:0.1833 318:0.1833 319:0.1833 320:0.1833 321:0.1833 322:0.1833 323:0.1833 324:0.1833 325:0.1833 326:0.1833 327:0.1833 328:0.1833 329:0.1833 330:0.1833 331:0.1833 332:0.1833 333:0.3167 334:0.3167 335:0.3167 336:0.3167 337:0.3167 338:0.3167 339:0.3167 340:0.3167 341:0.3 342:0.3 343:0.3 344:0.3 345:0.3 346:0.1333 347:0.1333 348:0.1333 349:0.1333 350:0.1333 351:0.1167 352:0.1167 353:0.1167 354:0.1167 355:0.1167 356:0.1167 357:0.1167 358:0.1167 359:0.1167 360:0.1167
-1.337034051918933 1:0.2333 2:0.2333 3:0.2333 4:0.2333 5:0.2333 6:0.2333 7:0.2333 8:0.2333 9:0.2333 10:0.2333 11:0.2333 12:0.2333 13:0.2333 14:0.2333 15:0.2333 16:0.2333 17:0.2333 18:0.2333 19:0.2333 20:0.2333 21:0.1667 22:0.1667 23:0.1833 24:0.1833 25:0.1833 26:0.1667 27:0.1667 28:0.1667 29:0.1667 30:0.1667 31:0.1667 32:0.1667 33:0.1667 34:0.1667 35:0.1667 36:0.1833 37:0.1833 38:0.1667 39:0.1667 40:0.1667 41:0.1667 42:0.1667 43:0.1667 44:0.1667 45:0.1667 46:0.1833 47:0.1667 48:0.1667 49:0.1667 50:0.1667 51:0.1667 52:0.4667 53:0.3333 54:0.3333 55:0.3333 56:0.3333 57:0.3333 58:0.3333 59:0.3333 60:0.3333 61:0.3333 62:0.3333 63:0.3333 64:0.3333 65:0.3333 66:0.3333 67:0.35 68:0.3333 69:0.3333 70:0.5 71:0.5 72:0.5 73:0.5 74:0.5 75:0.5 76:0.5167 77:0.5833 78:0.5667 79:0.7 80:0.7 81:0.9 82:0.9 83:0.9 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:0.9167 95:0.9167 96:0.9167 97:0.9167 98:0.85 99:0.4167 100:0.4167 101:0.4167 102:0.4167 103:0.4167 104:0.4167 105:0.4167 106:0.2833 107:0.2667 108:0.2667 109:0.2667 110:0.2833 111:0.2667 112:0.2667 113:0.2833 114:0.2667 115:0.2667 116:0.2833 117:0.2667 118:0.2667 119:0.1167 120:0.1167 121:0.1167 122:0.1167 123:0.1167 124:0.1167 125:0.1 126:0.1 127:0.1167 128:0.1167 129:0.1167 130:0.1167 131:0.1167 132:0.1167 133:0.1167 134:0.1167 135:0.1167 136:0.1167 137:0.1167 138:0.1167 139:0.1167 140:0.1167 141:0.1167 142:0.070210526 143:0.070210526 144:0.070210526 145:0.070210526 146:0.070210526 147:0.070210526 148:0.070210526 149:0.070210526 150:0.070210526 151:0.070210526 152:0.070210526 153:0.070210526 154:0.070210526 155:0.070210526 156:0.070210526 157:0.035710842 158:0.035710842 159:0.053603763 160:0.053603763 161:0.053603763 162:0.071389541 163:0.071389541 164:0.071389541 165:0.160747 166:0.160747 167:0.17853278 168:0.1964257 169:0.66067736 170:0.66067736 171:0.33924764 172:0.33924764 173:0.1964257 174:0.1964257 175:0.1964257 176:0.17853278 177:0.17853278 178:0.17853278 179:0.17853278 180:0.17853278 181:0.17853278 182:0.17853278 183:0.17853278 184:0.17853278 185:0.053603763 186:0.035710842 187:0.035710842 188:0.035710842 189:0.035710842 190:0.035710842 191:0.035710842 192:0.053603763 193:0.053603763 194:0.035710842 195:0.035710842 196:0.035710842 197:0.053603763 198:0.053603763 199:0.053603763 200:0.053603763 201:0.053603763 202:0.035710842 203:0.053603763 204:0.053603763 205:0.053603763 206:0.053603763 207:0.053603763 208:0.053603763 209:0.053603763 210:0.035710842 211:0.035710842 212:0.035710842 213:0.053603763 214:0.053603763 215:0.053603763 216:0.053603763 217:0.053603763 218:0.035710842 219:0.035710842 220:0.035710842 221:0.1 222:0.1 223:0.1 224:0.1167 225:0.1167 226:0.1167 227:0.1167 228:0.1167 229:0.4167 230:0.2333 231:0.2333 232:0.2333 233:0.2333 234:0.2333 235:0.2167 236:0.2333 237:0.2333 238:0.2333 239:0.2333 240:0.2333 241:0.2333 242:0.2333 243:0.2333 244:0.2333 245:0.2333 246:0.2333 247:0.2333 248:0.2333 249:0.2333 250:0.2333 251:0.2333 252:0.35 253:0.35 254:0.35 255:0.35 256:0.35 257:0.35 258:0.35 259:0.35 260:0.3667 261:0.3667 262:0.3667 263:0.9167 264:0.9167 265:0.95 266:0.95 267:0.95 268:0.95 269:0.95 270:1 271:1 272:1 273:0.9 274:0.8833 275:0.8833 276:0.8833 277:0.8833 278:0.6333 279:0.4333 280:0.4333 281:0.4333 282:0.4333 283:0.4333 284:0.4333 285:0.4333 286:0.35 287:0.35 288:0.3667 289:0.35 290:0.3667 291:0.35 292:0.35 293:0.2833 294:0.2833 295:0.2667 296:0.2667 297:0.2833 298:0.2667 299:0.2667 300:0.2167 301:0.2167 302:0.2167 303:0.2 304:0.2 305:0.2 306:0.1833 307:0.1833 308:0.2 309:0.2 310:0.2 311:0.2 312:0.2 313:0.2 314:0.2 315:0.2 316:0.2 317:0.2 318:0.15 319:0.15 320:0.15 321:0.15 322:0.15 323:0.15 324:0.15 325:0.15 326:0.1333 327:0.15 328:0.15 329:0.15 330:0.15 331:0.15 332:0.15 333:0.15 334:0.15 335:0.15 336:0.15 337:0.15 338:0.15 339:0.15 340:0.15 341:0.15 342:0.15 343:0.15 344:0.15 345:0.15 346:0.15 347:0.15 348:0.15 349:0.15 350:0.15 351:0.1333 352:0.2667 353:0.2667 354:0.2667 355:0.2667 356:0.25 357:0.25 358:0.25 359:0.25 360:0.2333
-1.791166510934416 1:0.2333 2:0.2333 3:0.2333 4:0.2333 5:0.2333 6:0.2333 7:0.2333 8:0.2333 9:0.2333 10:0.2333 11:0.2333 12:0.2333 13:0.2333 14:0.2333 15:0.2333 16:0.25 17:0.25 18:0.25 19:0.2333 20:0.2333 21:0.25 22:0.2333 23:0.2333 24:0.2333 25:0.2333 26:0.25 27:0.25 28:0.25 29:0.25 30:0.25 31:0.25 32:0.25 33:0.25 34:0.25 35:0.2667 36:0.3167 37:0.3167 38:0.2667 39:0.2667 40:0.3167 41:0.3167 42:0.3167 43:0.3167 44:0.3167 45:0.3167 46:0.3167 47:0.3167 48:0.3167 49:0.35 50:0.35 51:0.35 52:0.35 53:0.35 54:0.35 55:0.4 56:0.4 57:0.4 58:0.4 59:0.4 60:0.4 61:0.4667 62:0.4667 63:0.4667 64:0.4667 65:0.4667 66:0.5167 67:0.5167 68:0.5667 69:0.5667 70:0.5667 71:0.5667 72:0.6333 73:0.65 74:0.6667 75:0.8833 76:0.8833 77:0.8833 78:0.9 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:0.9333 105:0.85 106:0.75 107:0.75 108:0.65 109:0.6167 110:0.5833 111:0.55 112:0.5333 113:0.5167 114:0.4833 115:0.4667 116:0.45 117:0.4333 118:0.4167 119:0.4 120:0.4 121:0.3833 122:0.3667 123:0.3667 124:0.3167 125:0.3333 126:0.3333 127:0.3167 128:0.3167 129:0.3167 130:0.3 131:0.3 132:0.3 133:0.2833 134:0.2833 135:0.25 136:0.25 137:0.25 138:0.25 139:0.25 140:0.25 141:0.25 142:0.21052632 143:0.21052632 144:0.21052632 145:0.21052632 146:0.21052632 147:0.19294737 148:0.19294737 149:0.19294737 150:0.19294737 151:0.19294737 152:0.19294737 153:0.19294737 154:0.19294737 155:0.19294737 156:0.17547368 157:0.160747 158:0.160747 159:0.160747 160:0.160747 161:0.160747 162:0.160747 163:0.160747 164:0.160747 165:0.160747 166:0.160747 167:0.160747 168:0.160747 169:0.160747 170:0.160747 171:0.160747 172:0.160747 173:0.160747 174:0.160747 175:0.160747 176:0.160747 177:0.160747 178:0.160747 179:0.160747 180:0.160747 181:0.160747 182:0.160747 183:0.160747 184:0.7321419 185:0.7321419 186:0.7321419 187:0.7321419 188:0.7321419 189:0.7321419 190:0.75003482 191:0.75003482 192:0.7321419 193:0.7321419 194:0.7321419 195:0.7321419 196:0.7321419 197:0.7321419 198:0.7321419 199:0.75003482 200:0.75003482 201:0.17853278 202:0.17853278 203:0.17853278 204:0.17853278 205:0.17853278 206:0.17853278 207:0.17853278 208:0.17853278 209:0.17853278 210:0.17853278 211:0.17853278 212:0.17853278 213:0.17853278 214:0.17853278 215:0.17853278 216:0.17853278 217:0.160747 218:0.17853278 219:0.17853278 220:0.17853278 221:0.2333 222:0.2333 223:0.2667 224:0.2667 225:0.2667 226:0.2833 227:0.3167 228:0.3167 229:0.3167 230:0.3167 231:0.3167 232:0.3167 233:0.3167 234:0.3167 235:0.3167 236:0.3167 237:0.3167 238:0.3167 239:0.3333 240:0.3333 241:0.3333 242:0.3333 243:0.3667 244:0.3833 245:0.4 246:0.4 247:0.4 248:0.4 249:0.4167 250:0.5333 251:0.55 252:0.5333 253:0.5667 254:0.6 255:0.6167 256:0.6167 257:0.65 258:0.7333 259:0.75 260:0.8167 261:0.9 262:0.9 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:0.9333 287:0.8667 288:0.7667 289:0.7333 290:0.6833 291:0.65 292:0.6333 293:0.6 294:0.5667 295:0.55 296:0.5333 297:0.5167 298:0.5 299:0.4833 300:0.4667 301:0.4667 302:0.4333 303:0.4333 304:0.4167 305:0.4 306:0.4 307:0.3833 308:0.3833 309:0.3667 310:0.3667 311:0.3667 312:0.35 313:0.3333 314:0.3333 315:0.3333 316:0.3167 317:0.3167 318:0.3167 319:0.3167 320:0.3167 321:0.3167 322:0.3 323:0.3 324:0.2833 325:0.2833 326:0.2833 327:0.2833 328:0.2833 329:0.2833 330:0.2667 331:0.2667 332:0.2833 333:0.2833 334:0.2667 335:0.2667 336:0.2667 337:0.2333 338:0.2333 339:0.2333 340:0.2333 341:0.2333 342:0.2333 343:0.2333 344:0.2333 345:0.2333 346:0.2333 347:0.2333 348:0.2333 349:0.2333 350:0.2333 351:0.2333 352:0.2333 353:0.2333 354:0.2333 355:0.2333 356:0.2333 357:0.2333 358:0.2333 359:0.2333 360:0.2333
-1.695589249122103 1:1 2:1 3:1 4:0.8 5:0.8 6:0.8 7:0.7833 8:0.7833 9:0.1833 10:0.1833 11:0.2 12:0.2 13:0.8167 14:0.2 15:0.2 16:0.2 17:0.2 18:0.2 19:0.2 20:0.2 21:0.2 22:0.2 23:0.1833 24:0.2 25:0.2 26:0.8667 27:0.2 28:0.1833 29:0.1833 30:0.8333 31:0.2 32:0.2 33:0.2 34:0.8333 35:0.2 36:0.2 37:0.2 38:0.2 39:0.9667 40:0.9167 41:0.9167 42:0.9167 43:0.2833 44:0.2833 45:0.2833 46:0.3 47:0.2833 48:0.2833 49:0.3 50:0.2833 51:0.2833 52:0.3 53:0.2833 54:0.2833 55:0.3 56:0.2833 57:0.2833 58:0.3 59:0.3 60:0.3 61:0.4333 62:0.4333 63:0.4333 64:0.4333 65:0.4333 66:0.4333 67:0.4333 68:0.4333 69:0.4333 70:0.4333 71:0.4667 72:0.5 73:0.5833 74:0.5833 75:0.5833 76:0.6 77:0.65 78:0.9333 79:0.9333 80:0.9333 81:0.95 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:0.8167 103:0.8667 104:0.7 105:0.65 106:0.6 107:0.6 108:0.6 109:0.5667 110:0.5 111:0.5 112:0.4833 113:0.4667 114:0.45 115:0.4333 116:0.4333 117:0.4333 118:0.3833 119:0.3667 120:0.3667 121:0.3667 122:0.3667 123:0.3667 124:0.3167 125:0.3333 126:0.3 127:0.2667 128:0.2667 129:0.2667 130:0.25 131:0.25 132:0.25 133:0.2333 134:0.2333 135:0.25 136:0.25 137:0.25 138:0.25 139:0.25 140:0.2333 141:0.2167 142:0.17547368 143:0.17547368 144:0.15789474 145:0.15789474 146:0.15789474 147:0.15789474 148:0.15789474 149:0.15789474 150:0.15789474 151:0.15789474 152:0.15789474 153:0.14031579 154:0.14031579 155:0.14031579 156:0.14031579 157:0.12496116 158:0.12496116 159:0.12496116 160:0.12496116 161:0.12496116 162:0.12496116 163:0.12496116 164:0.12496116 165:0.12496116 166:0.12496116 167:0.12496116 168:0.12496116 169:0.12496116 170:0.12496116 171:0.12496116 172:0.12496116 173:0.12496116 174:0.12496116 175:0.12496116 176:0.12496116 177:0.12496116 178:0.12496116 179:0.12496116 180:0.12496116 181:0.12496116 182:0.12496116 183:0.12496116 184:0.12496116 185:0.12496116 186:0.12496116 187:0.12496116 188:0.12496116 189:0.12496116 190:0.12496116 191:0.12496116 192:0.12496116 193:0.12496116 194:0.12496116 195:0.12496116 196:0.12496116 197:0.12496116 198:0.12496116 199:0.12496116 200:0.12496116 201:0.12496116 202:0.12496116 203:0.12496116 204:0.12496116 205:0.12496116 206:0.12496116 207:0.12496116 208:0.12496116 209:0.12496116 210:0.14285408 211:0.14285408 212:0.14285408 213:0.14285408 214:0.14285408 215:0.14285408 216:0.14285408 217:0.14285408 218:0.14285408 219:0.160747 220:0.160747 221:0.2167 222:0.2167 223:0.2167 224:0.2167 225:0.2333 226:0.2333 227:0.2333 228:0.2333 229:0.2333 230:0.25 231:0.25 232:0.25 233:0.2667 234:0.2667 235:0.2667 236:0.2833 237:0.2833 238:0.3 239:0.3 240:0.3 241:0.3167 242:0.3333 243:0.3333 244:0.35 245:0.3667 246:0.3667 247:0.3833 248:0.4 249:0.4333 250:0.4333 251:0.4667 252:0.4667 253:0.4667 254:0.4833 255:0.5167 256:0.6 257:0.6 258:0.6333 259:0.6833 260:0.8167 261:0.9 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:0.95 282:0.8167 283:0.75 284:0.7 285:0.65 286:0.65 287:0.65 288:0.5333 289:0.5167 290:0.4833 291:0.4833 292:0.4833 293:0.4667 294:0.45 295:0.3833 296:0.3667 297:0.3667 298:0.35 299:0.3333 300:0.3333 301:0.3333 302:0.3333 303:0.3333 304:0.3333 305:0.2833 306:0.2833 307:0.3333 308:0.2667 309:0.2667 310:0.25 311:0.25 312:0.25 313:0.2333 314:0.2333 315:0.2333 316:0.2333 317:0.2333 318:0.2167 319:0.2167 320:0.2167 321:0.2167 322:0.2167 323:0.2167 324:0.2 325:0.2 326:0.2 327:0.2 328:0.2167 329:0.2 330:0.2 331:0.2 332:0.2167 333:0.2167 334:0.2 335:0.1833 336:0.1833 337:0.1833 338:0.1833 339:0.1833 340:0.1833 341:0.1833 342:0.1833 343:0.1833 344:0.1833 345:0.1833 346:0.1833 347:0.1833 348:0.1833 349:0.1833 350:0.1833 351:0.1833 352:0.1833 353:0.1833 354:0.1833 355:0.1833 356:0.1833 357:0.1833 358:0.1833 359:0.8833 360:0.9
-0.9989272910754306 1:0.2167 2:0.2167 3:0.2167 4:0.2167 5:0.2167 6:0.2167 7:0.2167 8:0.2167 9:0.2167 10:0.2167 11:0.2167 12:0.2167 13:0.2167 14:0.2167 15:0.2167 16:0.2167 17:0.2167 18:0.2167 19:0.2167 20:0.2167 21:0.2167 22:0.2167 23:0.2167 24:0.2167 25:0.2167 26:0.2167 27:0.2333 28:0.2333 29:0.2333 30:0.2333 31:0.2333 32:0.2333 33:0.2333 34:0.2333 35:0.2333 36:0.2333 37:0.2167 38:0.2333 39:0.2333 40:0.2333 41:0.2333 42:0.2333 43:0.25 44:0.25 45:0.25 46:0.25 47:0.25 48:0.2667 49:0.2667 50:0.2667 51:0.2833 52:0.2833 53:0.2833 54:0.3 55:0.3 56:0.3 57:0.3167 58:0.3167 59:0.3333 60:0.3333 61:0.35 62:0.3667 63:0.3667 64:0.3833 65:0.4 66:0.4167 67:0.4333 68:0.45 69:0.4667 70:0.4833 71:0.5167 72:0.5333 73:0.5667 74:0.6333 75:0.6333 76:0.6333 77:0.65 78:0.85 79:0.9 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:0.85 102:0.85 103:0.7 104:0.7 105:0.6167 106:0.6167 107:0.5167 108:0.5167 109:0.5167 110:0.5167 111:0.4167 112:0.4167 113:0.3833 114:0.3667 115:0.3667 116:0.3667 117:0.3167 118:0.3167 119:0.3 120:0.3 121:0.2833 122:0.2833 123:0.2667 124:0.2667 125:0.25 126:0.25 127:0.25 128:0.2333 129:0.2333 130:0.2333 131:0.2167 132:0.2167 133:0.2167 134:0.2167 135:0.2167 136:0.2 137:0.2 138:0.2 139:0.2 140:0.2 141:0.2 142:0.14031579 143:0.14031579 144:0.14031579 145:0.14031579 146:0.14031579 147:0.14031579 148:0.14031579 149:0.14031579 150:0.14031579 151:0.12284211 152:0.12284211 153:0.12284211 154:0.12284211 155:0.12284211 156:0.12284211 157:0.10717538 158:0.10717538 159:0.10717538 160:0.10717538 161:0.10717538 162:0.10717538 163:0.10717538 164:0.10717538 165:0.10717538 166:0.10717538 167:0.10717538 168:0.10717538 169:0.10717538 170:0.10717538 171:0.10717538 172:0.10717538 173:0.10717538 174:0.10717538 175:0.10717538 176:0.10717538 177:0.10717538 178:0.10717538 179:0.10717538 180:0.10717538 181:0.10717538 182:0.10717538 183:0.10717538 184:0.10717538 185:0.10717538 186:0.10717538 187:0.10717538 188:0.10717538 189:0.10717538 190:0.10717538 191:0.10717538 192:0.10717538 193:0.10717538 194:0.10717538 195:0.10717538 196:0.10717538 197:0.10717538 198:0.10717538 199:0.10717538 200:0.10717538 201:0.10717538 202:0.10717538 203:0.10717538 204:0.10717538 205:0.10717538 206:0.10717538 207:0.10717538 208:0.10717538 209:0.10717538 210:0.10717538 211:0.10717538 212:0.12496116 213:0.12496116 214:0.12496116 215:0.12496116 216:0.12496116 217:0.12496116 218:0.12496116 219:0.12496116 220:0.12496116 221:0.2 222:0.2 223:0.2 224:0.2 225:0.2 226:0.2 227:0.2167 228:0.2167 229:0.2167 230:0.2167 231:0.2167 232:0.2333 233:0.2333 234:0.2333 235:0.25 236:0.25 237:0.25 238:0.2667 239:0.2667 240:0.2833 241:0.2833 242:0.3 243:0.3 244:0.3167 245:0.3167 246:0.3333 247:0.35 248:0.3667 249:0.3833 250:0.4 251:0.4333 252:0.4333 253:0.6167 254:0.6167 255:0.6167 256:0.6167 257:0.2167 258:0.2167 259:0.2167 260:0.2167 261:0.2167 262:0.2167 263:0.2167 264:0.2167 265:0.2167 266:0.2167 267:0.2167 268:0.2167 269:0.2167 270:0.2167 271:0.2167 272:0.2167 273:0.2167 274:0.2167 275:0.2167 276:0.2167 277:0.2167 278:0.25 279:0.25 280:0.2833 281:0.2833 282:0.2833 283:0.2833 284:0.2833 285:0.2833 286:0.6667 287:0.6333 288:0.6 289:0.5667 290:0.5333 291:0.5167 292:0.4833 293:0.4667 294:0.45 295:0.4333 296:0.4167 297:0.4 298:0.3833 299:0.3667 300:0.3667 301:0.35 302:0.3333 303:0.3333 304:0.3167 305:0.3167 306:0.3 307:0.3 308:0.3 309:0.2833 310:0.2833 311:0.2833 312:0.2667 313:0.2667 314:0.2667 315:0.25 316:0.25 317:0.25 318:0.25 319:0.25 320:0.2333 321:0.2333 322:0.2333 323:0.2333 324:0.2333 325:0.2167 326:0.2167 327:0.2167 328:0.2167 329:0.2167 330:0.2167 331:0.2167 332:0.2167 333:0.2167 334:0.2167 335:0.2 336:0.2 337:0.2167 338:0.2167 339:0.2167 340:0.2167 341:0.2 342:0.2167 343:0.2167 344:0.2167 345:0.2167 346:0.2167 347:0.2167 348:0.2167 349:0.2 350:0.2167 351:0.2167 352:0.2 353:0.2 354:0.2 355:0.2167 356:0.2167 357:0.2167 358:0.2167 359:0.2167 360:0.2167
-1.013490659548135 1:0.2 2:0.2 3:0.2 4:0.2 5:0.2 6:0.2 7:0.2 8:0.2 9:0.1833 10:0.1833 11:0.2 12:0.2 13:0.2 14:0.2 15:0.2 16:0.2 17:0.2 18:0.2 19:0.1833 20:0.1833 21:0.1667 22:0.1667 23:0.1833 24:0.1833 25:0.1833 26:0.1667 27:0.1833 28:0.1833 29:0.1833 30:0.1833 31:0.1833 32:0.1833 33:0.1833 34:0.1833 35:0.1833 36:0.1833 37:0.1833 38:0.1833 39:0.1833 40:0.1833 41:0.1667 42:0.1667 43:0.1667 44:0.1833 45:0.1833 46:0.1833 47:0.1833 48:0.1833 49:0.1833 50:0.1833 51:0.1833 52:0.1833 53:0.1833 54:0.1833 55:0.2 56:0.2 57:0.2 58:0.2 59:0.2 60:0.2 61:0.2 62:0.1833 63:0.2 64:0.2 65:0.2 66:0.2 67:0.2 68:0.2 69:0.2 70:0.2 71:0.2 72:0.2 73:0.2 74:0.2 75:0.2 76:0.2167 77:0.2333 78:0.2333 79:0.2333 80:0.2333 81:0.2333 82:0.2667 83:0.25 84:0.25 85:0.25 86:0.2833 87:0.2833 88:0.2833 89:0.2833 90:0.3 91:0.3 92:0.3 93:0.3333 94:0.3333 95:0.3333 96:0.3667 97:0.3667 98:0.4167 99:0.4333 100:0.4333 101:0.4833 102:0.5 103:0.5 104:0.5333 105:0.6333 106:0.7 107:0.7667 108:0.9333 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:1 118:1 119:1 120:1 121:1 122:1 123:1 124:1 125:1 126:1 127:1 128:1 129:1 130:1 131:1 132:0.8833 133:0.7833 134:0.75 135:0.7167 136:0.65 137:0.6167 138:0.5667 139:0.55 140:0.5333 141:0.45 142:0.42105263 143:0.386 144:0.386 145:0.35084211 146:0.35084211 147:0.33336842 148:0.31578947 149:0.29821053 150:0.29821053 151:0.29821053 152:0.26315789 153:0.26315789 154:0.26315789 155:0.26315789 156:0.26315789 157:0.2321044 158:0.2321044 159:0.21431862 160:0.21431862 161:0.21431862 162:0.1964257 163:0.1964257 164:0.17853278 165:0.17853278 166:0.17853278 167:0.17853278 168:0.17853278 169:0.17853278 170:0.17853278 171:0.160747 172:0.160747 173:0.160747 174:0.160747 175:0.14285408 176:0.14285408 177:0.14285408 178:0.14285408 179:0.14285408 180:0.14285408 181:0.14285408 182:0.14285408 183:0.14285408 184:0.14285408 185:0.14285408 186:0.14285408 187:0.14285408 188:0.14285408 189:0.12496116 190:0.12496116 191:0.14285408 192:0.14285408 193:0.14285408 194:0.12496116 195:0.12496116 196:0.12496116 197:0.12496116 198:0.12496116 199:0.12496116 200:0.12496116 201:0.12496116 202:0.12496116 203:0.12496116 204:0.12496116 205:0.12496116 206:0.12496116 207:0.12496116 208:0.12496116 209:0.12496116 210:0.12496116 211:0.12496116 212:0.12496116 213:0.12496116 214:0.12496116 215:0.12496116 216:0.12496116 217:0.12496116 218:0.14285408 219:0.14285408 220:0.14285408 221:0.2 222:0.2 223:0.1833 224:0.2 225:0.2 226:0.2 227:0.2 228:0.2 229:0.1833 230:0.2 231:0.2 232:0.2 233:0.2 234:0.2 235:0.2 236:0.2 237:0.2 238:0.2 239:0.2 240:0.2 241:0.2 242:0.1833 243:0.2 244:0.2 245:0.2167 246:0.2167 247:0.2167 248:0.2167 249:0.2167 250:0.2167 251:0.2167 252:0.2333 253:0.2333 254:0.2667 255:0.2667 256:0.2667 257:0.2667 258:0.2667 259:0.2667 260:0.2667 261:0.2667 262:0.2667 263:0.2667 264:0.2667 265:0.2667 266:0.2667 267:0.2667 268:0.2667 269:0.2667 270:0.3 271:0.3 272:0.3 273:0.3167 274:0.3167 275:0.3167 276:0.35 277:0.35 278:0.3667 279:0.3667 280:1 281:1 282:1 283:1 284:1 285:0.85 286:0.8333 287:0.8333 288:0.8333 289:0.8333 290:0.8333 291:0.9167 292:1 293:1 294:1 295:1 296:1 297:1 298:1 299:1 300:1 301:1 302:1 303:1 304:1 305:1 306:1 307:1 308:1 309:1 310:1 311:1 312:1 313:0.5167 314:0.5167 315:0.5167 316:0.5167 317:0.5167 318:0.5167 319:0.4833 320:0.4333 321:0.4333 322:0.4 323:0.4 324:0.4 325:0.3833 326:0.3833 327:0.3667 328:0.35 329:0.35 330:0.35 331:0.35 332:0.35 333:0.35 334:0.3333 335:0.3333 336:0.3333 337:0.3333 338:0.25 339:0.25 340:0.25 341:0.25 342:0.2667 343:0.2167 344:0.2167 345:0.2167 346:0.2167 347:0.2167 348:0.2167 349:0.2167 350:0.2167 351:0.2167 352:0.2167 353:0.2167 354:0.2167 355:0.2167 356:0.2167 357:0.2167 358:0.2167 359:0.2 360:0.2
-0.03591734355888352 1:0.1833 2:0.1833 3:0.1833 4:0.1833 5:0.1833 6:0.1833 7:0.1833 8:0.1833 9:0.1667 10:0.1667 11:0.1833 12:0.1833 13:0.1833 14:0.1833 15:0.1833 16:0.1833 17:0.1833 18:0.1833 19:0.1833 20:0.1833 21:0.1667 22:0.1667 23:0.1833 24:0.1833 25:0.1833 26:0.1667 27:0.1667 28:0.1667 29:0.1667 30:0.1667 31:0.1667 32:0.1667 33:0.1667 34:0.1667 35:0.1667 36:0.1833 37:0.1833 38:0.1667 39:0.1667 40:0.1667 41:0.1667 42:0.1667 43:0.1667 44:0.1667 45:0.1667 46:0.1833 47:0.1667 48:0.1667 49:0.1667 50:0.1667 51:0.1667 52:0.1833 53:0.1833 54:0.1833 55:0.1833 56:0.1833 57:0.1833 58:0.1833 59:0.1833 60:0.1833 61:0.1833 62:0.1833 63:0.2 64:0.2 65:0.2 66:0.2 67:0.2 68:0.2 69:0.2 70:0.2 71:0.2 72:0.2 73:0.2 74:0.2 75:0.2 76:0.2167 77:0.2333 78:0.25 79:0.25 80:0.25 81:0.25 82:0.2667 83:0.2667 84:0.2667 85:0.2667 86:0.2833 87:0.2833 88:0.2833 89:0.2833 90:0.3333 91:0.3333 92:0.3333 93:0.3667 94:0.3667 95:0.4167 96:0.4167 97:0.4667 98:0.5 99:0.5 100:0.5333 101:0.5833 102:0.6167 103:0.7333 104:0.8167 105:0.9667 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:1 118:1 119:1 120:1 121:1 122:1 123:1 124:1 125:1 126:1 127:1 128:0.9333 129:0.8833 130:0.75 131:0.75 132:0.7 133:0.6667 134:0.6333 135:0.5667 136:0.5333 137:0.5 138:0.5 139:0.45 140:0.4333 141:0.4333 142:0.40347368 143:0.386 144:0.33336842 145:0.31578947 146:0.31578947 147:0.29821053 148:0.29821053 149:0.29821053 150:0.29821053 151:0.28073684 152:0.26315789 153:0.26315789 154:0.24557895 155:0.24557895 156:0.24557895 157:0.2321044 158:0.1964257 159:0.1964257 160:0.1964257 161:0.1964257 162:0.1964257 163:0.1964257 164:0.17853278 165:0.17853278 166:0.17853278 167:0.160747 168:0.160747 169:0.160747 170:0.160747 171:0.160747 172:0.160747 173:0.160747 174:0.160747 175:0.160747 176:0.160747 177:0.160747 178:0.160747 179:0.160747 180:0.160747 181:0.160747 182:0.160747 183:0.160747 184:0.12496116 185:0.12496116 186:0.12496116 187:0.12496116 188:0.12496116 189:0.12496116 190:0.12496116 191:0.12496116 192:0.12496116 193:0.12496116 194:0.12496116 195:0.12496116 196:0.12496116 197:0.12496116 198:0.12496116 199:0.12496116 200:0.12496116 201:0.12496116 202:0.12496116 203:0.12496116 204:0.12496116 205:0.12496116 206:0.12496116 207:0.12496116 208:0.12496116 209:0.12496116 210:0.160747 211:0.14285408 212:0.14285408 213:0.14285408 214:0.160747 215:0.14285408 216:0.14285408 217:0.14285408 218:0.14285408 219:0.14285408 220:0.14285408 221:0.2 222:0.2167 223:0.2167 224:0.2 225:0.2 226:0.2 227:0.2 228:0.2 229:0.2 230:0.2 231:0.2 232:0.2167 233:0.2 234:0.2 235:0.2 236:0.2 237:0.2 238:0.2 239:0.2 240:0.2 241:0.2167 242:0.2167 243:0.2 244:0.2 245:0.2167 246:0.2167 247:0.2167 248:0.2333 249:0.2667 250:0.25 251:0.2667 252:0.2667 253:0.25 254:0.25 255:0.2833 256:0.2833 257:0.2833 258:0.2833 259:0.2833 260:0.2833 261:0.2833 262:0.2833 263:0.2833 264:0.2833 265:0.2833 266:0.2833 267:0.3167 268:0.3167 269:0.3167 270:0.35 271:0.35 272:0.35 273:0.3833 274:0.3833 275:0.7667 276:0.7667 277:0.7667 278:0.7667 279:0.7667 280:0.7667 281:0.7667 282:0.7667 283:0.7833 284:0.8 285:0.8167 286:0.8333 287:0.9667 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:1 296:1 297:1 298:1 299:1 300:1 301:1 302:1 303:1 304:1 305:1 306:1 307:0.8167 308:0.7333 309:0.7 310:0.6333 311:0.5833 312:0.5167 313:0.5167 314:0.45 315:0.45 316:0.4167 317:0.4167 318:0.4 319:0.4 320:0.3667 321:0.3833 322:0.3667 323:0.3833 324:0.3667 325:0.3667 326:0.3667 327:0.3333 328:0.3333 329:0.3 330:0.3 331:0.2833 332:0.2667 333:0.2667 334:0.2667 335:0.2667 336:0.2667 337:0.2333 338:0.2333 339:0.2333 340:0.2333 341:0.2667 342:0.2333 343:0.2167 344:0.2167 345:0.2167 346:0.2 347:0.2 348:0.2 349:0.2 350:0.1833 351:0.1833 352:0.1833 353:0.1833 354:0.1833 355:0.1833 356:0.1833 357:0.1833 358:0.1833 359:0.1833 360:0.1833
-0.4449203349903729 1:0.6667 2:0.6667 3:0.6667 4:0.6667 5:0.6667 6:0.6667 7:0.6667 8:0.6667 9:0.6667 10:0.6667 11:0.6667 12:0.6667 13:0.7 14:0.7 15:0.7 16:0.7 17:0.7 18:0.7 19:0.7 20:0.7 21:0.7 22:0.9167 23:0.9 24:0.9 25:0.75 26:0.75 27:0.75 28:0.75 29:0.75 30:0.75 31:0.75 32:0.7667 33:0.8 34:0.8 35:1 36:1 37:1 38:1 39:1 40:1 41:1 42:0.95 43:0.95 44:0.95 45:0.95 46:0.95 47:0.95 48:1 49:1 50:1 51:1 52:1 53:1 54:1 55:1 56:1 57:1 58:1 59:1 60:1 61:1 62:1 63:1 64:1 65:1 66:1 67:1 68:1 69:1 70:1 71:1 72:1 73:1 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:0.75 99:0.6833 100:0.5833 101:0.5667 102:0.5667 103:0.5667 104:0.4833 105:0.4667 106:0.4167 107:0.3833 108:0.3667 109:0.35 110:0.3333 111:0.3167 112:0.3 113:0.3 114:0.3 115:0.3 116:0.25 117:0.25 118:0.2333 119:0.2333 120:0.2167 121:0.2167 122:0.2167 123:0.2 124:0.2 125:0.2 126:0.1833 127:0.1833 128:0.1833 129:0.1833 130:0.1833 131:0.1667 132:0.1667 133:0.1667 134:0.1667 135:0.1667 136:0.1833 137:0.1667 138:0.15 139:0.15 140:0.15 141:0.15 142:0.10526316 143:0.10526316 144:0.10526316 145:0.10526316 146:0.10526316 147:0.087684211 148:0.087684211 149:0.087684211 150:0.087684211 151:0.087684211 152:0.087684211 153:0.087684211 154:0.087684211 155:0.087684211 156:0.087684211 157:0.071389541 158:0.071389541 159:0.071389541 160:0.071389541 161:0.071389541 162:0.071389541 163:0.071389541 164:0.071389541 165:0.071389541 166:0.071389541 167:0.071389541 168:0.071389541 169:0.071389541 170:0.071389541 171:0.071389541 172:0.071389541 173:0.071389541 174:0.071389541 175:0.071389541 176:0.071389541 177:0.071389541 178:0.071389541 179:0.071389541 180:0.071389541 181:0.071389541 182:0.071389541 183:0.071389541 184:0.071389541 185:0.071389541 186:0.071389541 187:0.071389541 188:0.071389541 189:0.071389541 190:0.071389541 191:0.071389541 192:0.071389541 193:0.071389541 194:0.071389541 195:0.071389541 196:0.071389541 197:0.071389541 198:0.071389541 199:0.071389541 200:0.071389541 201:0.071389541 202:0.071389541 203:0.089282462 204:0.089282462 205:0.089282462 206:0.089282462 207:0.089282462 208:0.089282462 209:0.089282462 210:0.089282462 211:0.089282462 212:0.089282462 213:0.089282462 214:0.089282462 215:0.089282462 216:0.071389541 217:0.089282462 218:0.089282462 219:0.10717538 220:0.10717538 221:0.1667 222:0.1667 223:0.1667 224:0.1667 225:0.1667 226:0.1833 227:0.1667 228:0.1667 229:0.1667 230:0.1667 231:0.1667 232:0.1833 233:0.1833 234:0.1833 235:0.1833 236:0.1833 237:0.2 238:0.2 239:0.2 240:0.2167 241:0.2167 242:0.2167 243:0.2333 244:0.2333 245:0.2833 246:0.2833 247:0.2833 248:0.2833 249:0.2833 250:0.35 251:0.3667 252:0.3833 253:0.4333 254:0.4167 255:0.4333 256:0.4167 257:0.5167 258:0.6 259:0.6 260:0.65 261:0.7167 262:0.8 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:1 296:1 297:1 298:1 299:1 300:1 301:1 302:1 303:1 304:1 305:1 306:1 307:1 308:1 309:1 310:1 311:1 312:0.95 313:0.9333 314:0.9167 315:0.9 316:0.9 317:0.9 318:0.9 319:0.9 320:0.8333 321:0.8167 322:0.8167 323:0.8 324:0.7833 325:0.7833 326:0.7667 327:0.7667 328:0.75 329:0.75 330:0.7333 331:0.7333 332:0.7333 333:0.7167 334:0.7167 335:0.7 336:0.7 337:0.7 338:0.7 339:0.6833 340:0.6833 341:0.7 342:0.6833 343:0.6667 344:0.6667 345:0.6667 346:0.6667 347:0.6667 348:0.6667 349:0.6667 350:0.6667 351:0.6667 352:0.6667 353:0.6667 354:0.6667 355:0.6667 356:0.6667 357:0.6667 358:0.6667 359:0.6667 360:0.6667
-0.5441108218943412 1:0.65 2:0.65 3:0.65 4:0.65 5:0.65 6:0.65 7:0.65 8:0.8333 9:0.6667 10:0.6667 11:0.6667 12:0.6667 13:0.6667 14:0.6667 15:0.6667 16:0.6667 17:0.6667 18:0.6667 19:0.6833 20:0.6833 21:0.7 22:0.6833 23:0.6833 24:0.7 25:0.7 26:0.7167 27:0.7 28:0.7167 29:1 30:1 31:1 32:1 33:0.8167 34:0.8 35:0.8167 36:0.8167 37:0.8167 38:0.8167 39:0.8167 40:1 41:1 42:1 43:1 44:1 45:1 46:1 47:0.9833 48:0.9833 49:0.9833 50:0.9833 51:0.9833 52:1 53:1 54:1 55:1 56:1 57:1 58:1 59:1 60:1 61:1 62:1 63:1 64:1 65:1 66:1 67:1 68:1 69:1 70:1 71:1 72:1 73:1 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:0.8 101:0.75 102:0.65 103:0.6 104:0.55 105:0.5167 106:0.5 107:0.45 108:0.4167 109:0.4 110:0.3833 111:0.3667 112:0.35 113:0.3333 114:0.3167 115:0.3 116:0.3 117:0.2833 118:0.2833 119:0.2667 120:0.25 121:0.25 122:0.25 123:0.2333 124:0.2333 125:0.2333 126:0.2167 127:0.2167 128:0.2167 129:0.2 130:0.2 131:0.2 132:0.2 133:0.1833 134:0.1833 135:0.1833 136:0.1833 137:0.1833 138:0.1833 139:0.1667 140:0.1667 141:0.1667 142:0.12284211 143:0.12284211 144:0.12284211 145:0.12284211 146:0.12284211 147:0.087684211 148:0.087684211 149:0.087684211 150:0.087684211 151:0.087684211 152:0.087684211 153:0.10526316 154:0.10526316 155:0.087684211 156:0.087684211 157:0.071389541 158:0.071389541 159:0.089282462 160:0.089282462 161:0.089282462 162:0.071389541 163:0.071389541 164:0.071389541 165:0.089282462 166:0.089282462 167:0.089282462 168:0.071389541 169:0.071389541 170:0.071389541 171:0.071389541 172:0.071389541 173:0.071389541 174:0.071389541 175:0.071389541 176:0.071389541 177:0.071389541 178:0.089282462 179:0.089282462 180:0.089282462 181:0.089282462 182:0.089282462 183:0.089282462 184:0.089282462 185:0.089282462 186:0.089282462 187:0.089282462 188:0.089282462 189:0.089282462 190:0.089282462 191:0.089282462 192:0.089282462 193:0.089282462 194:0.089282462 195:0.089282462 196:0.089282462 197:0.089282462 198:0.089282462 199:0.089282462 200:0.089282462 201:0.089282462 202:0.089282462 203:0.089282462 204:0.089282462 205:0.089282462 206:0.089282462 207:0.089282462 208:0.089282462 209:0.089282462 210:0.089282462 211:0.089282462 212:0.089282462 213:0.089282462 214:0.10717538 215:0.10717538 216:0.10717538 217:0.10717538 218:0.10717538 219:0.10717538 220:0.10717538 221:0.1667 222:0.1667 223:0.1667 224:0.1667 225:0.15 226:0.1667 227:0.1667 228:0.1667 229:0.1667 230:0.1667 231:0.1667 232:0.1833 233:0.1833 234:0.1833 235:0.1833 236:0.1833 237:0.2 238:0.2 239:0.2 240:0.2167 241:0.2167 242:0.2167 243:0.2333 244:0.2333 245:0.2833 246:0.2667 247:0.2667 248:0.2833 249:0.2833 250:0.3 251:0.3167 252:0.35 253:0.35 254:0.4167 255:0.4167 256:0.4167 257:0.55 258:0.55 259:0.55 260:0.5667 261:0.6333 262:0.6833 263:0.7667 264:0.8833 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:0.7333 285:0.7167 286:0.7167 287:0.7 288:0.7 289:0.7 290:0.6833 291:0.6833 292:0.6833 293:0.6833 294:0.6833 295:0.6833 296:0.6833 297:1 298:1 299:1 300:1 301:1 302:1 303:1 304:1 305:1 306:1 307:1 308:1 309:1 310:1 311:1 312:0.95 313:0.9333 314:0.9333 315:0.9 316:0.8833 317:0.8833 318:0.9 319:0.85 320:0.8333 321:0.8333 322:0.8333 323:0.8333 324:0.8333 325:0.8333 326:0.8333 327:0.7833 328:0.7667 329:0.7667 330:0.7667 331:0.75 332:0.75 333:0.7333 334:0.7333 335:0.7333 336:0.7167 337:0.7167 338:0.7167 339:0.6833 340:0.6833 341:0.6833 342:0.6833 343:0.6667 344:0.6667 345:0.6667 346:0.6667 347:0.6667 348:0.6667 349:0.65 350:0.65 351:0.65 352:0.65 353:0.65 354:0.65 355:0.65 356:0.65 357:0.65 358:0.65 359:0.65 360:0.65
-0.2431753598127436 1:0.3 2:0.3 3:0.3 4:0.3 5:0.3 6:0.3 7:0.3 8:0.3 9:0.3 10:0.3 11:0.3 12:0.3 13:0.3 14:0.3 15:0.3 16:0.3 17:0.3 18:0.4167 19:0.4167 20:0.3333 21:0.3333 22:0.3333 23:0.3333 24:0.3333 25:0.3333 26:0.3333 27:0.3333 28:0.3333 29:0.3333 30:0.3333 31:0.3333 32:0.3333 33:0.3333 34:0.35 35:0.35 36:0.35 37:0.35 38:0.35 39:0.35 40:0.3667 41:0.3667 42:0.3667 43:0.3833 44:0.3833 45:0.3833 46:0.4 47:0.45 48:0.4667 49:0.45 50:0.4667 51:0.45 52:0.45 53:0.45 54:0.4667 55:0.4667 56:0.4833 57:0.5 58:0.5 59:0.5833 60:0.6 61:0.6167 62:0.75 63:0.6167 64:0.7167 65:0.7167 66:0.7167 67:0.7167 68:0.7167 69:0.7333 70:0.7667 71:0.8667 72:0.8833 73:0.8833 74:0.9333 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:0.95 97:0.55 98:0.4667 99:0.4167 100:0.2833 101:0.2333 102:0.2333 103:0.2333 104:0.2333 105:0.2333 106:0.15 107:0.15 108:0.1333 109:0.1333 110:0.1333 111:0.1333 112:0.1333 113:0.1333 114:0.1333 115:0.1333 116:0.1 117:0.1 118:0.08333 119:0.08333 120:0.08333 121:0.08333 122:0.08333 123:0.08333 124:0.08333 125:0.08333 126:0.06667 127:0.06667 128:0.06667 129:0.06667 130:0.06667 131:0.06667 132:0.08333 133:0.08333 134:0.08333 135:0.08333 136:0.08333 137:0.08333 138:0.08333 139:0.08333 140:0.08333 141:0.08333 142:0.035084211 143:0.035084211 144:0.035084211 145:0.035084211 146:0.035084211 147:0.035084211 148:0.035084211 149:0.035084211 150:0.035084211 151:0.035084211 152:0.035084211 153:0.035084211 154:0.035084211 155:0.035084211 156:0.035084211 157:0.017850064 158:0.017850064 159:0.017850064 160:0.017850064 161:0.017850064 162:0.017850064 163:0.017850064 164:0.017850064 165:0.017850064 166:0.017850064 167:0.017850064 168:0.017850064 169:0.017850064 176:0.017850064 177:0.017850064 178:0.017850064 179:0.017850064 180:0.017850064 181:0.017850064 182:0.017850064 183:0.017850064 184:0.017850064 185:0.017850064 186:0.017850064 187:0.017850064 188:0.017850064 189:0.017850064 190:0.017850064 191:0.017850064 192:0.017850064 193:0.017850064 194:0.017850064 195:0.017850064 196:0.017850064 197:0.017850064 198:0.017850064 199:0.017850064 200:0.017850064 201:0.017850064 202:0.017850064 203:0.017850064 204:0.017850064 205:0.017850064 206:0.017850064 207:0.017850064 208:0.017850064 209:0.017850064 210:0.017850064 211:0.017850064 212:0.017850064 213:0.017850064 214:0.017850064 215:0.017850064 216:0.017850064 217:0.017850064 218:0.017850064 219:0.017850064 220:0.017850064 221:0.08333 222:0.08333 223:0.08333 224:0.08333 225:0.08333 226:0.08333 227:0.08333 228:0.08333 229:0.08333 230:0.08333 231:0.08333 232:0.08333 233:0.1 234:0.08333 235:0.08333 236:0.08333 237:0.08333 238:0.08333 239:0.08333 240:0.08333 241:0.08333 242:0.08333 243:0.08333 244:0.08333 245:0.1 246:0.1 247:0.1 248:0.1 249:0.1167 250:0.1167 251:0.1167 252:0.1333 253:0.1333 254:0.1333 255:0.15 256:0.15 257:0.1667 258:0.1833 259:0.2 260:0.2167 261:0.2333 262:0.2667 263:0.3 264:0.3333 265:0.5833 266:0.6 267:0.6 268:0.7833 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:0.9333 289:0.8833 290:0.85 291:0.8333 292:0.7667 293:0.6833 294:0.6833 295:0.6667 296:0.65 297:0.65 298:0.6167 299:0.6167 300:0.6167 301:0.55 302:0.5333 303:0.5167 304:0.5 305:0.5 306:0.5 307:0.5 308:0.4333 309:0.4333 310:0.4333 311:0.4333 312:0.4167 313:0.4167 314:0.4 315:0.4 316:0.4 317:0.3833 318:0.3833 319:0.3833 320:0.3833 321:0.3833 322:0.3833 323:0.3833 324:0.3833 325:0.3833 326:0.3833 327:0.3833 328:0.3833 329:0.4333 330:0.4333 331:0.4333 332:0.4333 333:0.4333 334:0.3167 335:0.3167 336:0.3167 337:0.3167 338:0.3167 339:0.3167 340:0.3167 341:0.3 342:0.3 343:0.3 344:0.3 345:0.3 346:0.3 347:0.3 348:0.3 349:0.3 350:0.3 351:0.3 352:0.3 353:0.3 354:0.3 355:0.3 356:0.3 357:0.3 358:0.3 359:0.3 360:0.3
-1.162418084943818 1:0.25 2:0.25 3:0.25 4:0.25 5:0.25 6:0.25 7:0.25 8:0.25 9:0.25 10:0.25 11:0.25 12:0.25 13:0.25 14:0.25 15:0.25 16:0.25 17:0.25 18:0.25 19:0.25 20:0.25 21:0.25 22:0.25 23:0.25 24:0.25 25:0.25 26:0.25 27:0.25 28:0.25 29:0.25 30:0.25 31:0.25 32:0.2667 33:0.2833 34:0.2833 35:0.2833 36:0.3 37:0.3 38:0.3 39:0.3 40:0.3 41:0.3 42:0.3 43:0.3167 44:0.3167 45:0.3167 46:0.3167 47:0.3333 48:0.3333 49:0.3333 50:0.35 51:0.35 52:0.35 53:0.35 54:0.35 55:0.3833 56:0.3833 57:0.3833 58:0.3833 59:0.4 60:0.4 61:0.4167 62:0.4333 63:0.45 64:0.4667 65:0.4667 66:0.5167 67:0.5167 68:0.55 69:0.55 70:0.6 71:0.6 72:0.6333 73:0.65 74:0.7667 75:0.7667 76:0.7667 77:0.9 78:0.9167 79:0.9167 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:0.85 109:0.8333 110:0.7833 111:0.7 112:0.6667 113:0.65 114:0.6167 115:0.6 116:0.5667 117:0.55 118:0.5333 119:0.5167 120:0.5 121:0.4833 122:0.4333 123:0.4333 124:0.4167 125:0.4333 126:0.4167 127:0.4167 128:0.4 129:0.4 130:0.3833 131:0.3833 132:0.3667 133:0.3667 134:0.3667 135:0.3667 136:0.3667 137:0.35 138:0.3667 139:0.3667 140:0.3667 141:0.3667 142:0.33336842 143:0.33336842 144:0.33336842 145:0.31578947 146:0.33336842 147:0.33336842 148:0.35084211 149:0.35084211 150:0.35084211 151:0.35084211 152:0.36842105 153:0.36842105 154:0.43863158 155:0.43863158 156:0.63157895 157:0.6964632 158:1 159:1 160:1 161:1 162:1 163:1 164:0.83928514 165:0.82139222 166:0.82139222 167:0.71424898 168:0.71424898 169:0.71424898 170:0.71424898 171:0.71424898 172:0.71424898 173:0.80360644 174:0.87496384 175:0.89285676 176:0.67857028 177:0.24999732 178:0.24999732 179:0.24999732 180:0.21431862 181:0.21431862 182:0.21431862 183:0.1964257 184:0.1964257 185:0.1964257 186:0.1964257 187:0.1964257 188:0.1964257 189:0.1964257 190:0.1964257 191:0.1964257 192:0.1964257 193:0.1964257 194:0.1964257 195:0.1964257 196:0.1964257 197:0.1964257 198:0.1964257 199:0.1964257 200:0.1964257 201:0.1964257 202:0.1964257 203:0.1964257 204:0.1964257 205:0.1964257 206:0.1964257 207:0.21431862 208:0.21431862 209:0.1964257 210:0.21431862 211:0.21431862 212:0.1964257 213:0.1964257 214:0.1964257 215:0.21431862 216:0.21431862 217:0.21431862 218:0.21431862 219:0.21431862 220:0.2321044 221:0.2833 222:0.2833 223:0.2833 224:0.2833 225:0.3 226:0.3 227:0.3 228:0.3167 229:0.3167 230:0.3167 231:0.3333 232:0.3333 233:0.3333 234:0.35 235:0.35 236:0.3667 237:0.3667 238:0.3833 239:0.4 240:0.4 241:0.4167 242:0.4167 243:0.4167 244:0.4167 245:0.4667 246:0.4833 247:0.4667 248:0.4833 249:0.5167 250:0.5333 251:0.55 252:0.5833 253:0.6167 254:0.65 255:0.7 256:0.7333 257:0.7833 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:0.8167 289:0.8167 290:0.7333 291:0.7 292:0.6667 293:0.6667 294:0.6667 295:0.6333 296:0.6167 297:0.5833 298:0.5667 299:0.5167 300:0.5 301:0.4833 302:0.4667 303:0.45 304:0.4167 305:0.4 306:0.4 307:0.4 308:0.4 309:0.4 310:0.3833 311:0.3833 312:0.35 313:0.3333 314:0.3333 315:0.3333 316:0.3167 317:0.3167 318:0.3167 319:0.3167 320:0.3 321:0.3 322:0.3 323:0.3 324:0.2833 325:0.2833 326:0.2833 327:0.2833 328:0.2833 329:0.2833 330:0.2667 331:0.2667 332:0.2667 333:0.2667 334:0.2667 335:0.2667 336:0.2667 337:0.2667 338:0.25 339:0.25 340:0.25 341:0.25 342:0.25 343:0.25 344:0.25 345:0.25 346:0.25 347:0.25 348:0.25 349:0.25 350:0.25 351:0.25 352:0.25 353:0.25 354:0.25 355:0.25 356:0.25 357:0.25 358:0.25 359:0.25 360:0.25
-0.17667374294657 1:0.45 2:0.45 3:0.45 4:0.45 5:0.45 6:0.45 7:0.45 8:0.45 9:0.45 10:0.45 11:0.45 12:0.45 13:0.45 14:0.45 15:0.45 16:0.45 17:0.45 18:0.4667 19:0.45 20:0.4667 21:0.45 22:0.4667 23:0.45 24:0.45 25:0.4667 26:0.4667 27:0.4667 28:0.4667 29:0.4667 30:0.4833 31:0.4833 32:0.4833 33:0.4833 34:0.5 35:0.5 36:0.5 37:0.5167 38:0.5167 39:0.5333 40:0.5333 41:0.5333 42:0.55 43:0.55 44:0.55 45:0.55 46:0.55 47:0.55 48:0.5833 49:0.5833 50:0.6 51:0.6167 52:0.6333 53:0.6333 54:0.65 55:0.6667 56:0.6833 57:0.7 58:0.7167 59:0.7333 60:0.7333 61:0.75 62:0.7667 63:0.7667 64:0.7833 65:0.85 66:0.5667 67:0.5667 68:0.5667 69:0.5667 70:0.5667 71:0.55 72:0.55 73:0.55 74:0.55 75:0.55 76:0.55 77:0.55 78:0.55 79:0.55 80:0.5667 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:1 118:0.9667 119:0.9333 120:0.9167 121:0.8833 122:0.8667 123:0.8333 124:0.8167 125:0.7333 126:0.7167 127:0.7 128:0.7 129:0.7 130:0.65 131:0.6333 132:0.6333 133:0.6167 134:0.6 135:0.6 136:0.5833 137:0.5667 138:0.5667 139:0.55 140:0.55 141:0.5333 142:0.50873684 143:0.50873684 144:0.49126316 145:0.49126316 146:0.47368421 147:0.47368421 148:0.47368421 149:0.45610526 150:0.45610526 151:0.47368421 152:0.45610526 153:0.47368421 154:0.45610526 155:0.45610526 156:0.45610526 157:0.44639088 158:0.44639088 159:0.44639088 160:0.41071218 161:0.41071218 162:0.41071218 163:0.41071218 164:0.41071218 165:0.41071218 166:0.39281926 167:0.39281926 168:0.39281926 169:0.39281926 170:0.39281926 171:0.39281926 172:0.39281926 173:0.39281926 174:0.39281926 175:0.39281926 176:0.39281926 177:0.39281926 178:0.39281926 179:0.39281926 180:0.39281926 181:0.39281926 182:0.39281926 183:0.39281926 184:0.39281926 185:0.39281926 186:0.39281926 187:0.39281926 188:0.39281926 189:0.39281926 190:0.39281926 191:0.39281926 192:0.39281926 193:0.39281926 194:0.39281926 195:0.39281926 196:0.39281926 197:0.39281926 198:0.39281926 199:0.39281926 200:0.39281926 201:0.39281926 202:0.39281926 203:0.39281926 204:0.39281926 205:0.41071218 206:0.41071218 207:0.41071218 208:0.41071218 209:0.41071218 210:0.41071218 211:0.41071218 212:0.41071218 213:0.41071218 214:0.41071218 215:0.44639088 216:0.44639088 217:0.4642838 218:0.4642838 219:0.4642838 220:0.4642838 221:0.5167 222:0.5 223:0.5167 224:0.5167 225:0.5333 226:0.5333 227:0.55 228:0.4667 229:0.45 230:0.45 231:0.45 232:0.45 233:0.45 234:0.45 235:0.45 236:0.45 237:0.45 238:0.45 239:0.45 240:0.4667 241:0.4833 242:0.5 243:1 244:1 245:1 246:1 247:1 248:1 249:1 250:1 251:1 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:1 296:1 297:1 298:1 299:0.9 300:0.8833 301:0.75 302:0.7333 303:0.7333 304:0.7333 305:0.75 306:0.75 307:0.6667 308:0.65 309:0.6667 310:0.6667 311:0.65 312:0.65 313:0.6333 314:0.6333 315:0.6167 316:0.6 317:0.6 318:0.5833 319:0.5833 320:0.5667 321:0.5667 322:0.55 323:0.55 324:0.5333 325:0.5333 326:0.5333 327:0.5167 328:0.5167 329:0.5167 330:0.5 331:0.5 332:0.5 333:0.5 334:0.4833 335:0.4833 336:0.4833 337:0.4833 338:0.4833 339:0.4833 340:0.4833 341:0.4667 342:0.4667 343:0.4667 344:0.4667 345:0.4667 346:0.4667 347:0.4667 348:0.45 349:0.45 350:0.45 351:0.45 352:0.45 353:0.45 354:0.45 355:0.45 356:0.45 357:0.45 358:0.45 359:0.45 360:0.45
-0.07818660114870858 1:0.4333 2:0.4333 3:0.4333 4:0.4333 5:0.4333 6:0.4333 7:0.4333 8:0.4333 9:0.4333 10:0.4333 11:0.4333 12:0.4333 13:0.4333 14:0.4333 15:0.4333 16:0.4333 17:0.4333 18:0.45 19:0.45 20:0.45 21:0.45 22:0.45 23:0.45 24:0.45 25:0.45 26:0.45 27:0.45 28:0.45 29:0.45 30:0.4833 31:0.4833 32:0.4833 33:0.4833 34:0.4833 35:0.5 36:0.4833 37:0.5 38:0.5 39:0.5 40:0.5167 41:0.5167 42:0.5333 43:0.5333 44:0.55 45:0.55 46:0.5667 47:0.5833 48:0.5833 49:0.5833 50:0.6 51:0.6333 52:0.65 53:0.6667 54:0.65 55:0.6667 56:0.6667 57:0.6667 58:0.6833 59:0.6833 60:0.7 61:0.7167 62:0.7333 63:0.8 64:0.8 65:0.8167 66:0.8333 67:0.5833 68:0.5833 69:0.5833 70:0.5833 71:0.5667 72:0.5667 73:0.5667 74:0.5667 75:0.5667 76:0.5667 77:0.5667 78:0.5667 79:0.5667 80:0.5667 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:0.9667 116:0.9667 117:0.9333 118:0.9167 119:0.9167 120:0.9167 121:0.9167 122:0.8667 123:0.8 124:0.7833 125:0.7667 126:0.75 127:0.75 128:0.7333 129:0.7167 130:0.7 131:0.6333 132:0.6333 133:0.6167 134:0.6 135:0.6 136:0.5833 137:0.5667 138:0.5667 139:0.55 140:0.55 141:0.5333 142:0.50873684 143:0.50873684 144:0.49126316 145:0.49126316 146:0.47368421 147:0.47368421 148:0.47368421 149:0.45610526 150:0.45610526 151:0.45610526 152:0.45610526 153:0.43863158 154:0.43863158 155:0.43863158 156:0.43863158 157:0.4286051 158:0.41071218 159:0.41071218 160:0.41071218 161:0.41071218 162:0.41071218 163:0.41071218 164:0.41071218 165:0.39281926 166:0.39281926 167:0.39281926 168:0.39281926 169:0.39281926 170:0.39281926 171:0.39281926 172:0.39281926 173:0.39281926 174:0.39281926 175:0.39281926 176:0.39281926 177:0.39281926 178:0.39281926 179:0.39281926 180:0.39281926 181:0.39281926 182:0.39281926 183:0.39281926 184:0.39281926 185:0.39281926 186:0.39281926 187:0.39281926 188:0.39281926 189:0.39281926 190:0.39281926 191:0.39281926 192:0.39281926 193:0.39281926 194:0.39281926 195:0.39281926 196:0.39281926 197:0.39281926 198:0.41071218 199:0.41071218 200:0.41071218 201:0.41071218 202:0.41071218 203:0.41071218 204:0.41071218 205:0.41071218 206:0.41071218 207:0.41071218 208:0.41071218 209:0.41071218 210:0.4286051 211:0.4286051 212:0.4286051 213:0.4286051 214:0.44639088 215:0.44639088 216:0.44639088 217:0.4642838 218:0.4642838 219:0.4642838 220:0.48217672 221:0.5167 222:0.5167 223:0.5167 224:0.5167 225:0.5333 226:0.5667 227:0.5667 228:0.5833 229:0.5833 230:0.5833 231:0.5833 232:0.6 233:0.6167 234:0.6333 235:0.6333 236:0.65 237:0.6667 238:0.6833 239:0.7 240:0.6 241:0.6 242:0.6 243:0.6 244:0.6 245:0.6 246:0.6 247:0.6 248:0.6167 249:0.6 250:0.6333 251:0.65 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:1 296:1 297:0.85 298:0.8333 299:0.8333 300:0.8333 301:0.8333 302:0.7667 303:0.75 304:0.75 305:0.75 306:0.75 307:0.7333 308:0.7167 309:0.7 310:0.6833 311:0.6667 312:0.65 313:0.6333 314:0.6333 315:0.6167 316:0.6167 317:0.6 318:0.5833 319:0.5833 320:0.5667 321:0.5667 322:0.55 323:0.55 324:0.5333 325:0.5333 326:0.5333 327:0.5167 328:0.5167 329:0.5167 330:0.5 331:0.5 332:0.5 333:0.5 334:0.4833 335:0.4833 336:0.4833 337:0.4833 338:0.4833 339:0.4833 340:0.4833 341:0.4667 342:0.4667 343:0.4667 344:0.4667 345:0.4667 346:0.45 347:0.45 348:0.45 349:0.45 350:0.45 351:0.45 352:0.45 353:0.45 354:0.45 355:0.45 356:0.45 357:0.45 358:0.45 359:0.45 360:0.4333
-1.40280426951943 142:0.84210526 143:0.84210526 144:0.84210526 145:0.84210526 146:0.78947368 147:0.77189474 148:0.73684211 149:0.73684211 150:0.73684211 151:0.73684211 152:0.73684211 153:0.73684211 154:0.73684211 155:0.73684211 156:0.73684211 157:0.71424898 158:0.71424898 159:0.71424898 160:0.71424898 161:0.6964632 162:0.6964632 163:0.6964632 164:0.6964632 165:0.6964632 166:0.6964632 167:0.6964632 168:0.6964632 169:0.67857028 170:0.66067736 171:0.66067736 172:0.66067736 173:0.66067736 174:0.66067736 175:0.66067736 176:0.66067736 177:0.66067736 178:0.66067736 179:0.66067736 180:0.66067736 181:0.66067736 182:0.66067736 183:0.66067736 184:0.67857028 185:0.67857028 186:0.6964632 187:0.6964632 188:0.6964632 189:0.6964632 190:0.6964632 191:0.6964632 192:0.6964632 193:0.6964632 194:0.6964632 195:0.6964632 196:0.6964632 197:0.6964632 198:0.6964632 199:0.71424898 200:0.71424898 201:0.71424898 202:0.71424898 203:0.7321419 204:0.7321419 205:0.7321419 206:0.7321419 207:0.80360644 208:0.7321419 209:0.7321419 210:0.7321419 211:0.7321419 212:0.7321419 213:0.7321419 214:0.7321419 215:0.75003482 216:0.75003482 217:0.83928514 218:0.83928514 219:0.85717806 220:0.89285676
-0.8882500798720596 1:0.35 2:0.35 3:0.35 4:0.35 5:0.35 6:0.35 7:0.35 8:0.35 9:0.35 10:0.35 11:0.35 12:0.35 13:0.35 14:0.35 15:0.35 16:0.35 17:0.35 18:0.35 19:0.35 20:0.3667 21:0.3667 22:0.3667 23:0.3667 24:0.3667 25:0.3667 26:0.3667 27:0.3667 28:0.3833 29:0.3833 30:0.3833 31:0.3833 32:0.3833 33:0.4 34:0.4 35:0.4 36:0.4 37:0.4167 38:0.4167 39:0.4167 40:0.4333 41:0.4333 42:0.4333 43:0.4667 44:0.4667 45:0.4833 46:0.4833 47:0.4833 48:0.4833 49:0.4833 50:0.5 51:0.5167 52:0.5167 53:0.5333 54:0.55 55:0.55 56:0.5667 57:0.5833 58:0.5833 59:0.5833 60:0.6667 61:0.65 62:0.6667 63:0.7167 64:0.7167 65:0.7 66:0.7667 67:1 68:1 69:1 70:1 71:1 72:0.75 73:0.75 74:0.7333 75:0.7333 76:0.5667 77:0.5667 78:0.5667 79:0.5667 80:0.5667 81:0.5667 82:0.5667 83:0.5667 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:0.7167 109:0.6667 110:0.6333 111:0.6 112:0.5833 113:0.55 114:0.5333 115:0.5167 116:0.5 117:0.4667 118:0.4667 119:0.45 120:0.4333 121:0.4167 122:0.4167 123:0.4167 124:0.4167 125:0.4167 126:0.4167 127:0.4167 128:0.4167 129:0.4167 130:0.4167 131:0.4167 132:0.4167 133:0.4167 134:0.4333 135:0.4333 136:0.4333 137:0.4333 138:0.4333 139:0.4333 140:0.4333 141:0.4333 142:0.40347368 143:0.386 144:0.386 145:0.386 146:0.36842105 147:0.386 148:0.36842105 149:0.386 150:0.386 151:0.36842105 152:0.386 153:0.36842105 154:0.386 155:0.36842105 156:0.64915789 157:0.64289158 158:0.64289158 159:0.64289158 160:0.64289158 161:0.64289158 162:0.71424898 163:0.71424898 164:0.71424898 165:0.71424898 166:0.71424898 167:0.67857028 168:0.67857028 169:0.67857028 170:0.66067736 171:0.66067736 172:0.66067736 173:0.66067736 174:0.66067736 175:0.58931996 176:0.58931996 177:0.58931996 178:0.35714056 179:0.35714056 180:0.35714056 181:0.35714056 182:0.35714056 183:0.35714056 184:0.35714056 185:0.30356894 186:0.30356894 187:0.30356894 188:0.28567602 189:0.28567602 190:0.30356894 191:0.28567602 192:0.30356894 193:0.30356894 194:0.30356894 195:0.30356894 196:0.30356894 197:0.30356894 198:0.30356894 199:0.28567602 200:0.28567602 201:0.30356894 202:0.30356894 203:0.30356894 204:0.30356894 205:0.30356894 206:0.30356894 207:0.30356894 208:0.30356894 209:0.33924764 210:0.33924764 211:0.33924764 212:0.33924764 213:0.33924764 214:0.33924764 215:0.35714056 216:0.4999625 217:0.4999625 218:0.4999625 219:0.4999625 220:0.4999625 221:0.5167 222:0.4667 223:0.4833 224:0.4667 225:0.4833 226:0.4667 227:0.4833 228:0.4667 229:0.4833 230:0.4667 231:0.4833 232:0.5 233:0.5 234:0.5167 235:0.5333 236:0.5333 237:0.55 238:0.5667 239:0.5833 240:0.7 241:0.7 242:0.7 243:0.7 244:0.7167 245:0.7167 246:0.7333 247:0.75 248:0.7833 249:1 250:1 251:1 252:0.6667 253:0.65 254:0.65 255:0.65 256:0.65 257:0.65 258:0.65 259:0.65 260:0.65 261:0.65 262:0.65 263:0.65 264:0.65 265:0.65 266:0.65 267:0.65 268:0.65 269:0.65 270:0.65 271:0.65 272:0.65 273:0.65 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:0.95 292:0.9 293:0.8667 294:0.8333 295:0.8 296:0.7667 297:0.7333 298:0.7167 299:0.7 300:0.6667 301:0.65 302:0.6333 303:0.6167 304:0.6 305:0.5833 306:0.5667 307:0.5833 308:0.5667 309:0.5667 310:0.5667 311:0.5833 312:0.5833 313:0.5667 314:0.5833 315:0.5667 316:0.5833 317:0.5833 318:0.5833 319:0.5833 320:0.5833 321:0.5833 322:0.6 323:0.6 324:0.6167 325:0.6167 326:0.95 327:0.95 328:0.9 329:0.45 330:0.4333 331:0.4167 332:0.4 333:0.4 334:0.3833 335:0.3667 336:0.3667 337:0.3667 338:0.3667 339:0.3667 340:0.3667 341:0.3667 342:0.3667 343:0.3667 344:0.3667 345:0.3667 346:0.3667 347:0.35 348:0.35 349:0.35 350:0.35 351:0.35 352:0.35 353:0.35 354:0.35 355:0.35 356:0.35 357:0.35 358:0.35 359:0.35 360:0.35
-0.1454729085346107 1:0.2 2:0.2 3:0.2 4:0.2 5:0.2 6:0.2 7:0.2 8:0.25 9:0.1833 10:0.1833 11:0.2 12:0.2 13:0.2 14:0.2 15:0.2 16:0.2 17:0.2 18:0.2 19:0.2 20:0.2 21:0.2 22:0.2 23:0.1833 24:0.2 25:0.2 26:0.2 27:0.2 28:0.1833 29:0.1833 30:0.2 31:0.2 32:0.2 33:0.2 34:0.2 35:0.2 36:0.2 37:0.2 38:0.2 39:0.2167 40:0.2167 41:0.2167 42:0.2167 43:0.2167 44:0.2167 45:0.2667 46:0.2667 47:0.2667 48:0.2667 49:0.2667 50:0.2667 51:0.2667 52:0.2667 53:0.2667 54:0.2667 55:0.3 56:0.3 57:0.3 58:0.3 59:0.3 60:0.3 61:0.3167 62:0.35 63:0.3667 64:0.35 65:0.3833 66:0.3833 67:0.3833 68:0.4167 69:0.4167 70:0.5333 71:0.5333 72:0.5833 73:0.5667 74:0.5833 75:0.5833 76:0.6667 77:0.6667 78:0.8333 79:0.8167 80:0.8167 81:0.8 82:0.8 83:0.8 84:0.8 85:0.8 86:0.8 87:0.8 88:0.8 89:0.8 90:0.8 91:0.8167 92:1 93:1 94:0.5667 95:0.5667 96:0.55 97:0.55 98:0.5333 99:0.5333 100:0.55 101:0.55 102:0.55 103:0.55 104:0.55 105:0.5333 106:0.6167 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:1 118:1 119:1 120:1 121:1 122:1 123:1 124:0.9333 125:0.9333 126:0.9333 127:0.9333 128:0.9333 129:0.9333 130:0.9333 131:0.9333 132:0.75 133:0.7333 134:0.7333 135:0.7167 136:0.7167 137:0.7167 138:0.7167 139:0.6667 140:0.65 141:0.65 142:0.614 143:0.614 144:0.59652632 145:0.59652632 146:0.59652632 147:0.59652632 148:0.59652632 149:0.59652632 150:0.59652632 151:0.59652632 152:0.57894737 153:0.56136842 154:0.56136842 155:0.56136842 156:0.54389474 157:0.53574834 158:0.51785542 159:0.51785542 160:0.51785542 161:0.51785542 162:0.51785542 163:0.51785542 164:0.51785542 165:0.51785542 166:0.51785542 167:0.51785542 168:0.51785542 169:0.51785542 170:0.48217672 171:0.48217672 172:0.48217672 173:0.48217672 174:0.48217672 175:0.48217672 176:0.48217672 177:0.48217672 178:0.48217672 179:0.48217672 180:0.48217672 181:0.48217672 182:0.48217672 183:0.48217672 184:0.48217672 185:0.48217672 186:0.48217672 187:0.48217672 188:0.48217672 189:0.48217672 190:0.48217672 191:0.48217672 192:0.48217672 193:0.48217672 194:0.48217672 195:0.48217672 196:0.4999625 197:0.4999625 198:0.4999625 199:0.4999625 200:0.51785542 201:0.51785542 202:0.51785542 203:0.51785542 204:0.51785542 205:0.51785542 206:0.51785542 207:0.53574834 208:0.53574834 209:0.53574834 210:0.53574834 211:0.55353412 212:0.55353412 213:0.55353412 214:0.57142704 215:0.57142704 216:0.58931996 217:0.58931996 218:0.58931996 219:0.60710574 220:0.60710574 221:0.6667 222:0.6833 223:0.6833 224:0.7 225:0.7167 226:0.7167 227:0.75 228:0.75 229:0.75 230:0.75 231:0.7667 232:0.7833 233:0.8 234:0.8167 235:0.8333 236:0.8667 237:0.8833 238:0.9 239:0.9333 240:0.95 241:0.9833 242:1 243:1 244:1 245:1 246:1 247:1 248:1 249:1 250:1 251:1 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:0.4167 292:0.4 293:0.4167 294:0.4 295:0.4167 296:0.4 297:0.4167 298:0.4167 299:0.4 300:0.4167 301:0.4 302:0.4333 303:0.4167 304:0.4167 305:0.4 306:0.4 307:0.3833 308:0.3833 309:0.3667 310:0.3667 311:0.35 312:0.3667 313:0.3667 314:0.3667 315:0.3 316:0.3 317:0.3 318:0.2833 319:0.2833 320:0.3 321:0.3 322:0.2833 323:0.3 324:0.3 325:0.2833 326:0.3 327:0.3 328:0.2833 329:0.3 330:0.2167 331:0.2167 332:0.2167 333:0.1833 334:0.1833 335:0.2 336:0.2 337:0.2 338:0.2 339:0.1833 340:0.2 341:0.2 342:0.2 343:0.2 344:0.2 345:0.2 346:0.2 347:0.2 348:0.2 349:0.2 350:0.2 351:0.2 352:0.1833 353:0.1833 354:0.2 355:0.2 356:0.2 357:0.2 358:0.2 359:0.2 360:0.2
-0.07017368170936793 1:0.4167 2:0.4167 3:0.4167 4:0.4167 5:0.4167 6:0.4167 7:0.4 8:0.4 9:0.4167 10:0.4 11:0.4167 12:0.4 13:0.4167 14:0.4 15:0.4167 16:0.4 17:0.4 18:0.4333 19:0.4333 20:0.4333 21:0.4333 22:0.4333 23:0.4333 24:0.4333 25:0.4333 26:0.4333 27:0.4333 28:0.4333 29:0.4333 30:0.4333 31:0.4333 32:0.4333 33:0.4333 34:0.4333 35:0.4333 36:0.45 37:0.5 38:0.5 39:0.5 40:0.5 41:0.5 42:0.5 43:0.2833 44:0.2833 45:0.2833 46:0.2833 47:0.2667 48:0.2667 49:0.2667 50:0.2667 51:0.2667 52:0.2667 53:0.2667 54:0.2667 55:0.2667 56:0.2667 57:0.2667 58:0.2667 59:0.2667 60:0.2667 61:0.2667 62:0.2667 63:0.2667 64:0.2833 65:0.2833 66:0.3 67:0.7333 68:0.7333 69:0.7333 70:0.7333 71:0.4333 72:0.4333 73:0.4333 74:0.4333 75:0.4333 76:0.4333 77:0.4333 78:0.4333 79:0.4333 80:0.4333 81:0.4333 82:0.4333 83:0.4333 84:0.4833 85:0.65 86:0.65 87:0.65 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:0.9 112:0.8833 113:0.8667 114:0.8667 115:0.75 116:0.7333 117:0.7167 118:0.7167 119:0.7167 120:0.7 121:0.7167 122:0.7 123:0.7 124:0.7 125:0.5167 126:0.5167 127:0.5 128:0.4833 129:0.5 130:0.4833 131:0.45 132:0.45 133:0.4333 134:0.4333 135:0.4333 136:0.4167 137:0.4167 138:0.4 139:0.4 140:0.4 141:0.3833 142:0.35084211 143:0.35084211 144:0.35084211 145:0.35084211 146:0.35084211 147:0.35084211 148:0.35084211 149:0.35084211 150:0.35084211 151:0.35084211 152:0.33336842 153:0.33336842 154:0.31578947 155:0.31578947 156:0.31578947 157:0.30356894 158:0.28567602 159:0.28567602 160:0.28567602 161:0.28567602 162:0.26789024 163:0.26789024 164:0.26789024 165:0.26789024 166:0.26789024 167:0.26789024 168:0.26789024 169:0.26789024 170:0.26789024 171:0.26789024 172:0.26789024 173:0.26789024 174:0.26789024 175:0.26789024 176:0.26789024 177:0.26789024 178:0.26789024 179:0.26789024 180:0.26789024 181:0.26789024 182:0.26789024 183:0.26789024 184:0.26789024 185:0.26789024 186:0.26789024 187:0.26789024 188:0.26789024 189:0.26789024 190:0.26789024 191:0.26789024 192:0.26789024 193:0.26789024 194:0.26789024 195:0.26789024 196:0.26789024 197:0.26789024 198:0.26789024 199:0.26789024 200:0.26789024 201:0.28567602 202:0.30356894 203:0.30356894 204:0.30356894 205:0.30356894 206:0.30356894 207:0.30356894 208:0.30356894 209:0.32146186 210:0.30356894 211:0.30356894 212:0.30356894 213:0.30356894 214:0.30356894 215:0.32146186 216:0.32146186 217:0.32146186 218:0.32146186 219:0.33924764 220:0.33924764 221:0.3833 222:0.4 223:0.4 224:0.4 225:0.4167 226:0.4167 227:0.4333 228:0.4333 229:0.4333 230:0.45 231:0.45 232:0.4667 233:0.4833 234:0.4833 235:0.5 236:0.5333 237:0.5833 238:0.6 239:0.6167 240:0.6167 241:0.6167 242:0.6167 243:0.6167 244:0.65 245:0.6667 246:0.6833 247:0.7167 248:0.75 249:0.7833 250:0.8167 251:0.85 252:0.9 253:0.9333 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:1 296:1 297:1 298:1 299:1 300:1 301:1 302:1 303:1 304:0.6333 305:0.6167 306:0.6 307:0.6 308:0.6 309:0.5833 310:0.55 311:0.5333 312:0.5333 313:0.5167 314:0.5167 315:0.5167 316:0.4833 317:0.4833 318:0.4667 319:0.4667 320:0.4667 321:0.4667 322:0.4667 323:0.4667 324:0.45 325:0.45 326:0.45 327:0.45 328:0.4667 329:0.45 330:0.4667 331:0.45 332:0.45 333:0.45 334:0.4667 335:0.45 336:0.45 337:0.45 338:0.4333 339:0.4333 340:0.4333 341:0.4333 342:0.4333 343:0.4333 344:0.4333 345:0.4333 346:0.4333 347:0.4333 348:0.4333 349:0.4333 350:0.4333 351:0.4333 352:0.4333 353:0.4333 354:0.4333 355:0.4333 356:0.4167 357:0.4167 358:0.4167 359:0.4167 360:0.4167
-2 1:0.1833 2:0.1833 3:0.1833 4:0.1833 5:0.1833 6:0.1833 7:0.1833 8:0.1833 9:0.1833 10:0.1833 11:0.1833 12:0.1833 13:0.1833 14:0.1833 15:0.1833 16:0.1833 17:0.1833 18:0.1833 19:0.1833 20:0.1833 21:0.1833 22:0.1833 23:0.1833 24:0.1833 25:0.1833 26:0.1833 27:0.1833 28:0.1833 29:0.1833 30:0.2 31:0.2 32:0.2 33:0.2 34:0.2 35:0.2 36:0.2 37:0.2 38:0.2 39:0.2333 40:0.2333 41:0.2333 42:0.2333 43:0.25 44:0.25 45:0.25 46:0.25 47:0.25 48:0.2667 49:0.2667 50:0.2667 51:0.2833 52:0.2833 53:0.2833 54:0.3167 55:0.3333 56:0.3333 57:0.35 58:0.35 59:0.35 60:0.35 61:0.35 62:0.3667 63:0.3667 64:0.3833 65:0.4 66:0.4167 67:0.4333 68:0.45 69:0.65 70:0.6667 71:0.7 72:0.7333 73:0.8833 74:0.8833 75:0.8833 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:0.8667 98:0.75 99:0.7167 100:0.6833 101:0.6167 102:0.5667 103:0.5167 104:0.4833 105:0.45 106:0.4167 107:0.3833 108:0.3667 109:0.35 110:0.3333 111:0.3167 112:0.3 113:0.2833 114:0.2833 115:0.2667 116:0.25 117:0.25 118:0.2333 119:0.2333 120:0.2167 121:0.2167 122:0.2167 123:0.2 124:0.2 125:0.2 126:0.1833 127:0.1833 128:0.1833 129:0.1833 130:0.1833 131:0.1833 132:0.1833 133:0.1833 134:0.1833 135:0.1833 136:0.1833 137:0.1833 138:0.1833 139:0.1833 140:0.1833 141:0.1833 142:0.14031579 143:0.14031579 144:0.14031579 145:0.14031579 146:0.14031579 147:0.14031579 148:0.14031579 149:0.14031579 150:0.14031579 151:0.14031579 152:0.14031579 153:0.14031579 154:0.14031579 155:0.14031579 156:0.14031579 157:0.12496116 158:0.12496116 159:0.51785542 160:0.48217672 161:0.48217672 162:0.48217672 163:0.48217672 164:0.48217672 165:0.48217672 166:0.48217672 167:0.48217672 168:0.48217672 169:0.48217672 170:0.48217672 171:0.4642838 172:0.4642838 173:0.4642838 174:0.4642838 175:0.4642838 176:0.4642838 177:0.4642838 178:0.4642838 179:0.4642838 180:0.4642838 181:0.4642838 182:0.4642838 183:0.4642838 184:0.089282462 185:0.089282462 186:0.089282462 187:0.089282462 188:0.089282462 189:0.089282462 190:0.089282462 191:0.071389541 192:0.089282462 193:0.089282462 194:0.089282462 195:0.089282462 196:0.089282462 197:0.089282462 198:0.089282462 199:0.089282462 200:0.089282462 201:0.089282462 202:0.089282462 203:0.089282462 204:0.089282462 205:0.089282462 206:0.089282462 207:0.089282462 208:0.089282462 209:0.089282462 210:0.089282462 211:0.089282462 212:0.089282462 213:0.089282462 214:0.089282462 215:0.089282462 216:0.071389541 217:0.089282462 218:0.089282462 219:0.089282462 220:0.089282462 221:0.15 222:0.15 223:0.15 224:0.15 225:0.15 226:0.1667 227:0.1667 228:0.1667 229:0.1667 230:0.1667 231:0.1667 232:0.1833 233:0.1833 234:0.1833 235:0.1833 236:0.1833 237:0.2 238:0.2 239:0.2 240:0.2167 241:0.2167 242:0.2167 243:0.2333 244:0.2333 245:0.25 246:0.25 247:0.2667 248:0.2833 249:0.2833 250:0.3 251:0.3167 252:0.3333 253:0.35 254:0.3667 255:0.3833 256:0.4167 257:0.45 258:0.4833 259:0.4833 260:0.4833 261:0.5333 262:0.5833 263:0.65 264:0.75 265:0.8667 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:0.85 285:0.7833 286:0.6 287:0.5667 288:0.5333 289:0.5167 290:0.4833 291:0.4667 292:0.4333 293:0.4167 294:0.4 295:0.3833 296:0.3667 297:0.3667 298:0.35 299:0.3333 300:0.3333 301:0.3167 302:0.3 303:0.3 304:0.3 305:0.2833 306:0.2833 307:0.2667 308:0.2667 309:0.2667 310:0.25 311:0.25 312:0.25 313:0.2333 314:0.1833 315:0.1833 316:0.1833 317:0.1833 318:0.1833 319:0.1833 320:0.1833 321:0.1833 322:0.1833 323:0.1833 324:0.1833 325:0.1833 326:0.1833 327:0.1833 328:0.1833 329:0.1833 330:0.1833 331:0.1833 332:0.1833 333:0.1833 334:0.1833 335:0.1833 336:0.1833 337:0.1833 338:0.1833 339:0.1833 340:0.1833 341:0.1833 342:0.1833 343:0.1833 344:0.1833 345:0.1833 346:0.1833 347:0.1833 348:0.1833 349:0.1833 350:0.1833 351:0.1833 352:0.1833 353:0.1833 354:0.1833 355:0.1833 356:0.1833 357:0.1833 358:0.1833 359:0.1833 360:0.1833
-0.1033417771238669 1:0.1333 2:0.1333 3:0.1333 4:0.1333 5:0.1333 6:0.1333 7:0.1333 8:0.1333 9:0.1333 10:0.1333 11:0.1333 12:0.1333 13:0.1333 14:0.1333 15:0.1333 16:0.1333 17:0.1333 18:0.1333 19:0.1333 20:0.1333 21:0.1333 22:0.1333 23:0.1333 24:0.1333 25:0.1333 26:0.1333 27:0.1333 28:0.1333 29:0.1333 30:0.1333 31:0.1333 32:0.1333 33:0.1333 34:0.1333 35:0.1333 36:0.1333 37:0.15 38:0.15 39:0.15 40:0.15 41:0.15 42:0.15 43:0.15 44:0.15 45:0.15 46:0.1667 47:0.1667 48:0.1667 49:0.1667 50:0.1667 51:0.1667 52:0.1833 53:0.1833 54:0.1833 55:0.1833 56:0.1833 57:0.2 58:0.2 59:0.2 60:0.2 61:0.2 62:0.2 63:0.1833 64:0.1833 65:0.1833 66:0.1833 67:0.1833 68:0.1833 69:0.1833 70:0.1833 71:0.1833 72:0.1833 73:0.1833 74:0.1833 75:0.1833 76:0.1833 77:0.1833 78:0.1833 79:0.1833 80:0.1833 81:0.1833 82:0.1833 83:0.1833 84:0.1833 85:0.1833 86:0.1833 87:0.1833 88:0.1833 89:0.1833 90:0.1833 91:0.1833 92:0.1833 93:0.1833 94:0.1833 95:0.1833 96:0.1833 97:0.1833 98:0.1833 99:0.1833 100:0.1833 101:0.1833 102:0.1833 103:1 104:0.8667 105:0.8167 106:0.7333 107:0.7 108:0.65 109:0.6167 110:0.5833 111:0.5167 112:0.4833 113:0.4667 114:0.45 115:0.4333 116:0.4167 117:0.4 118:0.3833 119:0.3667 120:0.3667 121:0.35 122:0.3333 123:0.3333 124:0.3167 125:0.3167 126:0.3 127:0.3 128:0.3 129:0.2833 130:0.2833 131:0.2833 132:0.2667 133:0.2667 134:0.2667 135:0.25 136:0.25 137:0.25 138:0.25 139:0.25 140:0.2333 141:0.2333 142:0.19294737 143:0.19294737 144:0.19294737 145:0.17547368 146:0.17547368 147:0.17547368 148:0.17547368 149:0.17547368 150:0.17547368 151:0.17547368 152:0.17547368 153:0.17547368 154:0.17547368 155:0.15789474 156:0.15789474 157:0.14285408 158:0.14285408 159:0.14285408 160:0.12496116 161:0.12496116 162:0.12496116 163:0.12496116 164:0.12496116 165:0.12496116 166:0.12496116 167:0.12496116 168:0.12496116 169:0.12496116 170:0.12496116 171:0.12496116 172:0.12496116 173:0.12496116 174:0.12496116 175:0.12496116 176:0.12496116 177:0.12496116 178:0.12496116 179:0.12496116 180:0.12496116 181:0.12496116 182:0.12496116 183:0.12496116 184:0.12496116 185:0.12496116 186:0.12496116 187:0.12496116 188:0.12496116 189:0.12496116 190:0.12496116 191:0.12496116 192:0.12496116 193:0.12496116 194:0.12496116 195:0.12496116 196:0.12496116 197:0.12496116 198:0.12496116 199:0.12496116 200:0.12496116 201:0.12496116 202:0.12496116 203:0.12496116 204:0.12496116 205:0.12496116 206:0.12496116 207:0.12496116 208:0.12496116 209:0.12496116 210:0.14285408 211:0.14285408 212:0.14285408 213:0.14285408 214:0.14285408 215:0.14285408 216:0.14285408 217:0.14285408 218:0.14285408 219:0.160747 220:0.160747 221:0.2167 222:0.2167 223:0.2167 224:0.2167 225:0.2333 226:0.2333 227:0.2333 228:0.2333 229:0.2333 230:0.25 231:0.25 232:0.25 233:0.2667 234:0.2667 235:0.2667 236:0.2833 237:0.2833 238:0.3 239:0.3 240:0.3 241:0.3167 242:0.3333 243:0.3333 244:0.35 245:0.35 246:0.35 247:0.35 248:0.3667 249:0.3833 250:0.4 251:0.4167 252:0.4333 253:0.45 254:0.4833 255:0.5167 256:0.55 257:0.5833 258:0.5667 259:0.6 260:0.65 261:0.7167 262:0.8 263:0.9 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:0.9 281:0.7167 282:0.65 283:0.6 284:0.5833 285:0.5167 286:0.4833 287:0.45 288:0.3833 289:0.3833 290:0.3333 291:0.3333 292:0.3333 293:0.2833 294:0.2833 295:0.2667 296:0.25 297:0.25 298:0.2333 299:0.2333 300:0.2167 301:0.2167 302:0.2167 303:0.2 304:0.2 305:0.2 306:0.1833 307:0.1833 308:0.1833 309:0.1833 310:0.1833 311:0.1667 312:0.1667 313:0.1667 314:0.1667 315:0.1667 316:0.1667 317:0.15 318:0.15 319:0.15 320:0.15 321:0.15 322:0.15 323:0.15 324:0.15 325:0.15 326:0.1333 327:0.1333 328:0.1333 329:0.1333 330:0.1333 331:0.1333 332:0.1333 333:0.1333 334:0.1333 335:0.1333 336:0.1333 337:0.1333 338:0.1333 339:0.1333 340:0.1333 341:0.1333 342:0.1333 343:0.1333 344:0.1333 345:0.1333 346:0.1333 347:0.1333 348:0.1333 349:0.1333 350:0.1333 351:0.1333 352:0.1333 353:0.1333 354:0.1333 355:0.1333 356:0.1333 357:0.1333 358:0.1333 359:0.1333 360:0.1333
-0.9972275900320716 1:0.45 2:0.45 3:0.45 4:0.45 5:0.45 6:0.45 7:0.45 8:0.45 9:0.45 10:0.45 11:0.45 12:0.45 13:0.45 14:0.45 15:0.45 16:0.45 17:0.4667 18:0.4667 19:0.4667 20:0.4667 21:0.4667 22:0.4667 23:0.4667 24:0.4833 25:0.4833 26:0.4833 27:0.4833 28:0.4833 29:0.5 30:0.5 31:0.5 32:0.5 33:0.5333 34:0.5333 35:0.5333 36:0.5333 37:0.5333 38:0.5333 39:0.55 40:0.55 41:0.5667 42:0.5667 43:0.6167 44:0.6 45:0.6167 46:0.6 47:0.6167 48:0.6833 49:0.6833 50:0.6833 51:0.6833 52:0.7 53:0.7 54:0.7167 55:0.7167 56:0.7167 57:0.7333 58:0.7833 59:1 60:1 61:1 62:1 63:1 64:1 65:1 66:1 67:1 68:1 69:1 70:1 71:1 72:1 73:1 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:1 118:1 119:1 120:1 121:1 122:1 123:0.8 124:0.7833 125:0.7667 126:0.7667 127:0.75 128:0.7333 129:0.7167 130:0.6833 131:0.6833 132:0.6833 133:0.6667 134:0.6667 135:0.6667 136:0.6667 137:0.6 138:0.5833 139:0.5833 140:0.5667 141:0.5667 142:0.52631579 143:0.52631579 144:0.50873684 145:0.50873684 146:0.50873684 147:0.49126316 148:0.49126316 149:0.49126316 150:0.49126316 151:0.45610526 152:0.45610526 153:0.45610526 154:0.45610526 155:0.45610526 156:0.45610526 157:0.44639088 158:0.44639088 159:0.4286051 160:0.4286051 161:0.4286051 162:0.4286051 163:0.4286051 164:0.4286051 165:0.4286051 166:0.39281926 167:0.39281926 168:0.39281926 169:0.39281926 170:0.39281926 171:0.39281926 172:0.39281926 173:0.39281926 174:0.39281926 175:0.39281926 176:0.39281926 177:0.39281926 178:0.39281926 179:0.39281926 180:0.39281926 181:0.39281926 182:0.39281926 183:0.39281926 184:0.39281926 185:0.39281926 186:0.39281926 187:0.39281926 188:0.39281926 189:0.39281926 190:0.39281926 191:0.39281926 192:0.39281926 193:0.39281926 194:0.39281926 195:0.39281926 196:0.39281926 197:0.41071218 198:0.41071218 199:0.41071218 200:0.41071218 201:0.41071218 202:0.41071218 203:0.41071218 204:0.41071218 205:0.4286051 206:0.4286051 207:0.4286051 208:0.4286051 209:0.4286051 210:0.44639088 211:0.44639088 212:0.44639088 213:0.44639088 214:0.4642838 215:0.4642838 216:0.4642838 217:0.48217672 218:0.48217672 219:0.4999625 220:0.4999625 221:0.5333 222:0.55 223:0.55 224:0.5667 225:0.5667 226:0.5833 227:0.6 228:0.6 229:0.6 230:0.6 231:0.6333 232:0.65 233:0.6667 234:0.6833 235:0.7 236:0.7167 237:0.7333 238:0.75 239:0.7667 240:0.8 241:0.8167 242:0.8167 243:0.8333 244:0.8667 245:0.9333 246:0.9667 247:1 248:1 249:1 250:1 251:1 252:1 253:1 254:1 255:1 256:1 257:0.15 258:0.15 259:0.15 260:0.15 261:0.15 262:0.15 263:0.15 264:0.15 265:0.15 266:0.15 267:0.15 268:0.15 269:0.15 270:0.15 271:0.15 272:0.15 273:0.15 274:0.15 275:0.15 276:0.15 277:0.15 278:0.15 279:0.15 280:0.15 281:0.15 282:0.15 283:0.15 284:0.15 285:0.15 286:0.15 287:0.15 288:0.15 289:0.15 290:0.15 291:1 292:1 293:1 294:1 295:1 296:1 297:1 298:1 299:1 300:0.8833 301:0.85 302:0.8333 303:0.8 304:0.7833 305:0.7667 306:0.75 307:0.7333 308:0.7167 309:0.7 310:0.6833 311:0.6667 312:0.65 313:0.6333 314:0.6333 315:0.6167 316:0.6 317:0.6 318:0.5833 319:0.5833 320:0.5667 321:0.5667 322:0.55 323:0.55 324:0.5333 325:0.5333 326:0.5333 327:0.5167 328:0.5167 329:0.5167 330:0.5 331:0.5 332:0.5 333:0.5 334:0.4833 335:0.4833 336:0.4833 337:0.4833 338:0.4833 339:0.4667 340:0.4667 341:0.4667 342:0.4667 343:0.4667 344:0.4667 345:0.4667 346:0.45 347:0.45 348:0.45 349:0.45 350:0.45 351:0.45 352:0.45 353:0.45 354:0.45 355:0.45 356:0.45 357:0.45 358:0.45 359:0.45 360:0.45
-0.7343290063912017 1:0.3333 2:0.3333 3:0.3333 4:0.3333 5:0.3333 6:0.3333 7:0.3333 8:0.3333 9:0.3333 10:0.3333 11:0.3333 12:0.3333 13:0.3333 14:0.3333 15:0.3333 16:0.3333 17:0.3333 18:0.3333 19:0.3333 20:0.3333 21:0.35 22:0.35 23:0.35 24:0.35 25:0.35 26:0.35 27:0.35 28:0.35 29:0.3667 30:0.3667 31:0.3667 32:0.3667 33:0.3667 34:0.3833 35:0.3833 36:0.3833 37:0.3833 38:0.4 39:0.4 40:0.4 41:0.4167 42:0.4167 43:0.4167 44:0.4333 45:0.4333 46:0.4333 47:0.45 48:0.45 49:0.4667 50:0.45 51:0.45 52:0.4667 53:0.5167 54:0.5167 55:0.55 56:0.55 57:0.55 58:0.5667 59:0.5833 60:0.6 61:0.6167 62:0.6333 63:0.45 64:0.45 65:0.45 66:0.45 67:0.45 68:0.4333 69:0.45 70:0.4333 71:0.45 72:0.4333 73:0.45 74:0.4333 75:0.45 76:0.4333 77:0.45 78:0.45 79:0.45 80:0.4833 81:0.55 82:1 83:1 84:1 85:1 86:1 87:1 88:0.7333 89:0.7333 90:0.7333 91:0.4833 92:0.4833 93:0.4833 94:0.4833 95:0.4833 96:0.4833 97:0.4833 98:0.4833 99:0.4833 100:0.4667 101:0.4667 102:0.3833 103:0.35 104:0.3333 105:0.3 106:0.3 107:0.2667 108:0.25 109:0.2333 110:0.2333 111:0.2167 112:0.2 113:0.2 114:0.1833 115:0.1833 116:0.1833 117:0.1667 118:0.1667 119:0.1667 120:0.15 121:0.15 122:0.15 123:0.15 124:0.1333 125:0.1333 126:0.1333 127:0.1333 128:0.1333 129:0.1167 130:0.1167 131:0.1167 132:0.1167 133:0.1167 134:0.1167 135:0.1167 136:0.1167 137:0.1167 138:0.1167 139:0.1 140:0.1 141:0.1 142:0.052631579 143:0.052631579 144:0.052631579 145:0.052631579 146:0.052631579 147:0.052631579 148:0.052631579 149:0.052631579 150:0.052631579 151:0.052631579 152:0.052631579 153:0.052631579 154:0.052631579 155:0.052631579 156:0.052631579 157:0.035710842 158:0.035710842 159:0.035710842 160:0.035710842 161:0.035710842 162:0.035710842 163:0.035710842 164:0.035710842 165:0.035710842 166:0.035710842 167:0.035710842 168:0.035710842 169:0.035710842 170:0.035710842 171:0.035710842 172:0.035710842 173:0.035710842 174:0.035710842 175:0.035710842 176:0.035710842 177:0.035710842 178:0.035710842 179:0.035710842 180:0.035710842 181:0.035710842 182:0.035710842 183:0.035710842 184:0.035710842 185:0.035710842 186:0.035710842 187:0.035710842 188:0.035710842 189:0.035710842 190:0.035710842 191:0.035710842 192:0.035710842 193:0.035710842 194:0.035710842 195:0.035710842 196:0.035710842 197:0.035710842 198:0.035710842 199:0.035710842 200:0.035710842 201:0.035710842 202:0.035710842 203:0.035710842 204:0.035710842 205:0.035710842 206:0.035710842 207:0.035710842 208:0.035710842 209:0.035710842 210:0.035710842 211:0.035710842 212:0.035710842 213:0.035710842 214:0.035710842 215:0.035710842 216:0.035710842 217:0.035710842 218:0.035710842 219:0.035710842 220:0.035710842 221:0.1 222:0.1 223:0.1 224:0.1167 225:0.1167 226:0.1167 227:0.1167 228:0.1167 229:0.1167 230:0.1167 231:0.1167 232:0.1167 233:0.1167 234:0.1333 235:0.1333 236:0.1333 237:0.1333 238:0.1333 239:0.15 240:0.15 241:0.15 242:0.15 243:0.1667 244:0.1667 245:0.1667 246:0.1833 247:0.1833 248:0.1833 249:0.2 250:0.2 251:0.2167 252:0.2333 253:0.2333 254:0.25 255:0.2667 256:0.2833 257:0.3 258:0.3333 259:0.35 260:0.35 261:0.35 262:0.3667 263:0.6833 264:0.6833 265:0.7167 266:0.7167 267:0.8333 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:0.4833 283:0.4833 284:0.4833 285:0.4833 286:0.4833 287:0.4833 288:0.4833 289:0.4833 290:0.4833 291:0.4833 292:0.85 293:0.8167 294:0.7833 295:0.75 296:0.7333 297:0.7 298:0.6833 299:0.65 300:0.6333 301:0.6167 302:0.6 303:0.5833 304:0.5667 305:0.55 306:0.5333 307:0.5333 308:0.5167 309:0.5 310:0.5 311:0.4833 312:0.4667 313:0.4667 314:0.45 315:0.45 316:0.4333 317:0.4333 318:0.4333 319:0.4167 320:0.4167 321:0.4167 322:0.4 323:0.4 324:0.4 325:0.3833 326:0.3833 327:0.3833 328:0.3833 329:0.3667 330:0.3667 331:0.3667 332:0.3667 333:0.3667 334:0.35 335:0.35 336:0.35 337:0.35 338:0.35 339:0.35 340:0.35 341:0.35 342:0.3333 343:0.3333 344:0.3333 345:0.3333 346:0.3333 347:0.3333 348:0.3333 349:0.3333 350:0.3333 351:0.3333 352:0.3333 353:0.3333 354:0.3333 355:0.3333 356:0.3333 357:0.3333 358:0.3333 359:0.3333 360:0.3333
-0.02674690764760544 1:0.45 2:0.45 3:0.45 4:0.45 5:0.45 6:0.45 7:0.45 8:0.45 9:0.45 10:0.45 11:0.45 12:0.45 13:0.45 14:0.45 15:0.45 16:0.45 17:0.4667 18:0.4667 19:0.4667 20:0.4667 21:0.4667 22:0.4667 23:0.4667 24:0.4833 25:0.4833 26:0.4833 27:0.4833 28:0.4833 29:0.5 30:0.5 31:0.5 32:0.5 33:0.5167 34:0.5167 35:0.5167 36:0.55 37:0.55 38:0.55 39:0.5667 40:0.55 41:0.5667 42:0.5667 43:0.5833 44:0.5833 45:0.6 46:0.6 47:0.6167 48:0.6667 49:0.6667 50:0.6667 51:0.6667 52:0.6833 53:0.7 54:0.7167 55:0.75 56:0.75 57:0.75 58:0.7667 59:1 60:1 61:1 62:1 63:1 64:1 65:1 66:1 67:1 68:1 69:1 70:1 71:1 72:1 73:1 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:0.95 115:0.95 116:0.8833 117:0.8833 118:0.8833 119:0.8833 120:0.4667 121:0.45 122:0.45 123:0.45 124:0.45 125:0.45 126:0.45 127:0.45 128:0.45 129:0.45 130:0.45 131:0.45 132:0.4667 133:0.4667 134:0.4667 135:0.4833 136:0.5167 137:0.5 138:0.5 139:0.4833 140:0.5 141:0.4833 142:0.47368421 143:0.47368421 144:0.47368421 145:0.47368421 146:0.47368421 147:0.73684211 148:0.70178947 149:0.68421053 150:0.68421053 151:0.68421053 152:0.68421053 153:0.386 154:0.386 155:0.386 156:0.36842105 157:0.35714056 158:0.35714056 159:0.35714056 160:0.35714056 161:0.35714056 162:0.35714056 163:0.35714056 164:0.35714056 165:0.35714056 166:0.35714056 167:0.35714056 168:0.35714056 169:0.35714056 170:0.35714056 171:0.35714056 172:0.35714056 173:0.33924764 174:0.33924764 175:0.33924764 176:0.33924764 177:0.33924764 178:0.33924764 179:0.33924764 180:0.33924764 181:0.33924764 182:0.33924764 183:0.33924764 184:0.33924764 185:0.33924764 186:0.33924764 187:0.33924764 188:0.33924764 189:0.33924764 190:0.33924764 191:0.33924764 192:0.33924764 193:0.33924764 194:0.33924764 195:0.33924764 196:0.33924764 197:0.33924764 198:0.33924764 199:0.35714056 200:0.35714056 201:0.37503348 202:0.37503348 203:0.37503348 204:0.37503348 205:0.39281926 206:0.39281926 207:0.39281926 208:0.39281926 209:0.39281926 210:0.39281926 211:0.39281926 212:0.39281926 213:0.39281926 214:0.39281926 215:0.39281926 216:0.4286051 217:0.4286051 218:0.44639088 219:0.48217672 220:0.48217672 221:0.5167 222:0.5333 223:0.5333 224:0.5833 225:0.5833 226:0.5833 227:0.5833 228:0.5833 229:0.5833 230:0.5833 231:0.5833 232:0.5833 233:0.5833 234:0.7167 235:0.7167 236:0.7167 237:0.7167 238:0.7167 239:0.7167 240:0.7667 241:0.8333 242:0.8333 243:0.8333 244:0.8333 245:0.8667 246:0.8667 247:1 248:1 249:1 250:1 251:1 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:1 296:1 297:1 298:1 299:1 300:1 301:1 302:1 303:0.9333 304:0.8833 305:0.8833 306:0.7667 307:0.7667 308:0.7667 309:0.7667 310:0.7667 311:0.7667 312:0.7667 313:1 314:1 315:1 316:1 317:0.4333 318:0.4 319:0.4167 320:0.4 321:0.4167 322:0.4167 323:0.4167 324:0.4167 325:0.4 326:0.4167 327:0.4 328:0.4167 329:0.4167 330:0.4167 331:0.4833 332:0.4833 333:0.4833 334:0.4833 335:0.4833 336:0.4833 337:0.4833 338:0.4833 339:0.4833 340:0.4833 341:0.4667 342:0.4667 343:0.4667 344:0.4667 345:0.4667 346:0.4667 347:0.4667 348:0.4667 349:0.4667 350:0.45 351:0.45 352:0.45 353:0.45 354:0.45 355:0.45 356:0.45 357:0.45 358:0.45 359:0.45 360:0.45
-0.7704745852510203 1:0.6 2:0.6 3:0.6 4:0.6 5:0.6 6:0.6 7:0.55 8:0.5167 9:0.5333 10:0.5333 11:0.5167 12:0.5333 13:0.5167 14:0.5333 15:0.5167 16:0.5333 17:0.5333 18:0.5667 19:0.5833 20:0.5833 21:0.5833 22:0.6 23:0.6 24:0.6 25:0.6 26:0.6167 27:0.6167 28:0.6167 29:0.6333 30:0.6167 31:0.6167 32:0.6 33:0.6167 34:0.6167 35:0.6 36:0.6167 37:0.6 38:0.6 39:0.8167 40:0.8333 41:0.85 42:0.85 43:0.8167 44:0.8167 45:0.8167 46:0.8167 47:0.8167 48:0.8167 49:0.9167 50:0.9667 51:0.9667 52:0.9667 53:1 54:1 55:1 56:1 57:1 58:1 59:1 60:1 61:1 62:1 63:1 64:1 65:1 66:1 67:1 68:1 69:1 70:1 71:1 72:1 73:1 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:0.9833 104:0.9833 105:0.9333 106:0.9333 107:0.3833 108:0.3833 109:0.3833 110:0.3833 111:0.3667 112:0.35 113:0.35 114:0.35 115:0.35 116:0.35 117:0.35 118:0.35 119:0.3667 120:0.35 121:0.35 122:0.35 123:0.35 124:0.35 125:0.3667 126:0.45 127:0.4667 128:0.45 129:0.3667 130:0.3 131:0.3 132:0.3 133:0.3 134:0.3 135:0.3 136:0.3 137:0.3 138:0.3 139:0.3 140:0.3 141:0.3 142:0.26315789 143:0.26315789 144:0.26315789 145:0.26315789 146:0.26315789 147:0.26315789 148:0.26315789 149:0.26315789 150:0.26315789 151:0.24557895 152:0.24557895 153:0.24557895 154:0.24557895 155:0.24557895 156:0.24557895 157:0.2321044 158:0.2321044 159:0.21431862 160:0.2321044 161:0.2321044 162:0.2321044 163:0.2321044 164:0.2321044 165:0.2321044 166:0.2321044 167:0.2321044 168:0.2321044 169:0.2321044 170:0.21431862 171:0.21431862 172:0.21431862 173:0.21431862 174:0.21431862 175:0.21431862 176:0.21431862 177:0.21431862 178:0.21431862 179:0.21431862 180:0.21431862 181:0.21431862 182:0.21431862 183:0.21431862 184:0.21431862 185:0.21431862 186:0.21431862 187:0.2321044 188:0.2321044 189:0.2321044 190:0.2321044 191:0.2321044 192:0.2321044 193:0.2321044 194:0.2321044 195:0.2321044 196:0.2321044 197:0.2321044 198:0.2321044 199:0.2321044 200:0.2321044 201:0.2321044 202:0.2321044 203:0.24999732 204:0.24999732 205:0.24999732 206:0.24999732 207:0.28567602 208:0.28567602 209:0.28567602 210:0.28567602 211:0.28567602 212:0.28567602 213:0.28567602 214:0.30356894 215:0.30356894 216:0.30356894 217:0.30356894 218:0.32146186 219:0.35714056 220:0.35714056 221:0.4167 222:0.5167 223:0.5167 224:0.5167 225:0.5167 226:0.5167 227:0.5167 228:0.5167 229:0.5167 230:0.5167 231:0.5167 232:0.5167 233:0.5333 234:0.5833 235:0.5833 236:0.5667 237:0.5833 238:0.5833 239:0.5833 240:0.5833 241:0.5833 242:0.6 243:0.6167 244:0.65 245:0.6667 246:0.7 247:0.7167 248:0.7833 249:0.7833 250:0.8667 251:0.9 252:0.95 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:1 296:1 297:1 298:1 299:1 300:1 301:1 302:1 303:1 304:1 305:1 306:1 307:1 308:1 309:1 310:1 311:0.85 312:0.8333 313:0.8333 314:0.8 315:0.7833 316:0.7667 317:0.7667 318:0.7833 319:0.7333 320:0.7333 321:0.7667 322:0.6833 323:0.6667 324:0.6667 325:0.6667 326:0.6667 327:0.6667 328:0.65 329:0.6333 330:0.6167 331:0.6333 332:0.6167 333:0.6167 334:0.6333 335:0.6167 336:0.6167 337:0.6333 338:0.6167 339:0.6167 340:0.6167 341:0.6167 342:0.6167 343:0.6167 344:0.5667 345:0.5667 346:0.5667 347:0.5667 348:0.55 349:0.5667 350:0.55 351:0.5667 352:0.5667 353:0.55 354:0.55 355:0.55 356:0.9167 357:0.9167 358:0.9167 359:0.9167 360:0.9167
-0.3110097732608271 1:0.3833 2:0.3833 3:0.4 4:0.4 5:0.4 6:0.4 7:0.4 8:0.4 9:0.4 10:0.4 11:0.4 12:0.4 13:0.4 14:0.4 15:0.4 16:0.4 17:0.4 18:0.4167 19:0.4167 20:0.4167 21:0.4167 22:0.4167 23:0.4167 24:0.4167 25:0.4167 26:0.4333 27:0.4333 28:0.4333 29:0.4333 30:0.4333 31:0.45 32:0.45 33:0.45 34:0.45 35:0.4667 36:0.4667 37:0.4667 38:0.4833 39:0.4833 40:0.4833 41:0.5 42:0.5 43:0.5333 44:0.55 45:0.55 46:0.5667 47:0.5667 48:0.6167 49:0.6167 50:0.6167 51:0.6167 52:0.6167 53:0.6167 54:0.7 55:0.7 56:0.7 57:0.7 58:0.7 59:0.7 60:0.7 61:0.7167 62:1 63:1 64:1 65:1 66:0.9 67:0.9 68:0.9 69:0.9 70:0.9 71:0.9 72:1 73:1 74:1 75:1 76:0.9333 77:0.9333 78:0.9333 79:0.9333 80:0.9333 81:0.9333 82:0.9333 83:0.9333 84:0.9333 85:0.9333 86:0.9333 87:1 88:1 89:1 90:1 91:1 92:1 93:0.9667 94:0.8 95:0.5833 96:0.4667 97:0.4 98:0.4 99:0.4167 100:0.3667 101:0.3333 102:0.3 103:0.2833 104:0.25 105:0.2333 106:0.2167 107:0.2 108:0.2 109:0.1833 110:0.1833 111:0.1667 112:0.1667 113:0.15 114:0.15 115:0.15 116:0.1333 117:0.1333 118:0.1333 119:0.1167 120:0.1167 121:0.1167 122:0.1167 123:0.1167 124:0.1167 125:0.1 126:0.1 127:0.1 128:0.1 129:0.1 130:0.1 131:0.1 132:0.1 133:0.08333 134:0.08333 135:0.08333 136:0.08333 137:0.08333 138:0.08333 139:0.08333 140:0.08333 141:0.08333 142:0.035084211 143:0.035084211 144:0.035084211 145:0.035084211 146:0.035084211 147:0.035084211 148:0.035084211 149:0.035084211 150:0.035084211 151:0.035084211 152:0.035084211 153:0.035084211 154:0.035084211 155:0.035084211 156:0.035084211 157:0.017850064 158:0.017850064 159:0.017850064 160:0.017850064 161:0.017850064 162:0.017850064 163:0.017850064 164:0.017850064 165:0.017850064 166:0.017850064 167:0.017850064 168:0.017850064 169:0.017850064 170:0.017850064 171:0.017850064 172:0.017850064 173:0.017850064 174:0.017850064 175:0.017850064 176:0.017850064 177:0.017850064 178:0.017850064 179:0.017850064 180:0.017850064 181:0.017850064 182:0.017850064 183:0.017850064 184:0.017850064 185:0.017850064 186:0.017850064 187:0.017850064 188:0.017850064 189:0.017850064 190:0.017850064 191:0.017850064 192:0.017850064 193:0.017850064 194:0.017850064 195:0.017850064 196:0.017850064 197:0.017850064 198:0.017850064 199:0.017850064 200:0.017850064 201:0.017850064 202:0.017850064 203:0.017850064 204:0.035710842 205:0.035710842 206:0.035710842 207:0.035710842 208:0.035710842 209:0.035710842 210:0.035710842 211:0.035710842 212:0.035710842 213:0.035710842 214:0.035710842 215:0.035710842 216:0.035710842 217:0.035710842 218:0.035710842 219:0.035710842 220:0.035710842 221:0.1 222:0.1 223:0.1 224:0.1167 225:0.1167 226:0.1167 227:0.1167 228:0.1167 229:0.1167 230:0.1167 231:0.1167 232:0.1167 233:0.1167 234:0.1333 235:0.1333 236:0.1333 237:0.1333 238:0.1333 239:0.15 240:0.15 241:0.15 242:0.15 243:0.1667 244:0.1667 245:0.1667 246:0.1833 247:0.1833 248:0.1833 249:0.2 250:0.2 251:0.2167 252:0.2333 253:0.2333 254:0.25 255:0.2667 256:0.2833 257:0.3 258:0.3333 259:0.35 260:0.3833 261:0.4333 262:0.4667 263:0.5333 264:0.75 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:0.9 281:0.9 282:0.8167 283:0.75 284:0.7 285:0.65 286:0.6 287:0.5833 288:0.5833 289:0.5833 290:0.5833 291:0.5833 292:0.5833 293:0.5833 294:0.5833 295:0.5833 296:0.6 297:0.6 298:0.6 299:0.6 300:0.7 301:0.3833 302:0.3667 303:0.3833 304:0.3833 305:0.3667 306:0.3833 307:0.3667 308:0.3833 309:0.1167 310:0.1167 311:0.1167 312:0.1167 313:0.1167 314:0.1167 315:0.1167 316:0.1167 317:0.1167 318:0.1167 319:0.1 320:0.1 321:0.1 322:0.1 323:0.1 324:0.1 325:0.1167 326:0.1167 327:0.1167 328:0.1167 329:0.1167 330:0.1 331:0.1 332:0.1 333:0.1167 334:0.1167 335:0.1167 336:0.1167 337:0.1167 338:0.1167 339:0.1167 340:0.1 341:0.1167 342:0.1167 343:0.1167 344:0.1167 345:0.1167 346:0.1 347:0.1 348:0.1 349:0.1167 350:0.1167 351:0.1 352:0.1 353:0.1 354:0.1 355:0.1 356:0.1 357:0.1167 358:0.3833 359:0.3833 360:0.3833
-0.1273458683593925 1:0.4333 2:0.4333 3:0.4333 4:0.4333 5:0.4333 6:0.4333 7:0.4333 8:0.4333 9:0.4333 10:0.4333 11:0.45 12:0.45 13:0.45 14:0.45 15:0.4667 16:0.4833 17:0.4667 18:0.4667 19:0.4667 20:0.4667 21:0.4667 22:0.4667 23:0.4667 24:0.4667 25:0.4667 26:0.4667 27:0.4833 28:0.5 29:0.5 30:0.5 31:0.5 32:0.5 33:0.6333 34:0.65 35:0.6667 36:0.6833 37:1 38:1 39:1 40:1 41:1 42:1 43:1 44:1 45:1 46:1 47:0.8667 48:0.8667 49:0.8667 50:0.8667 51:0.8667 52:0.8667 53:0.8667 54:0.9167 55:0.9167 56:0.9167 57:0.9167 58:1 59:1 60:1 61:1 62:1 63:1 64:1 65:1 66:1 67:1 68:1 69:1 70:1 71:1 72:1 73:1 74:1 75:1 76:0.9167 77:0.9167 78:0.9167 79:0.9167 80:0.9167 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:0.7167 113:0.6833 114:0.6833 115:0.6833 116:0.6833 117:0.4667 118:0.4667 119:0.4667 120:0.4667 121:0.4667 122:0.4667 123:0.4667 124:0.4667 125:0.4667 126:0.4667 127:0.4667 128:0.4833 129:0.5333 130:0.4667 131:0.45 132:0.45 133:0.4333 134:0.4333 135:0.4333 136:0.4333 137:0.4333 138:0.4333 139:0.4333 140:0.4333 141:0.4333 142:0.40347368 143:0.40347368 144:0.40347368 145:0.40347368 146:0.40347368 147:0.40347368 148:0.21052632 149:0.21052632 150:0.21052632 151:0.21052632 152:0.21052632 153:0.21052632 154:0.21052632 155:0.21052632 156:0.21052632 157:0.1964257 158:0.1964257 159:0.1964257 160:0.1964257 161:0.1964257 162:0.1964257 163:0.1964257 164:0.1964257 165:0.1964257 166:0.1964257 167:0.1964257 168:0.1964257 169:0.37503348 170:0.37503348 171:0.37503348 172:0.37503348 173:0.37503348 174:0.37503348 175:0.37503348 176:0.37503348 177:0.37503348 178:0.37503348 179:0.37503348 180:0.37503348 181:0.37503348 182:0.37503348 183:0.37503348 184:0.37503348 185:0.37503348 186:0.37503348 187:0.37503348 188:0.37503348 189:0.37503348 190:0.37503348 191:0.37503348 192:0.37503348 193:0.39281926 194:0.37503348 195:0.39281926 196:0.37503348 197:0.37503348 198:0.39281926 199:0.39281926 200:0.39281926 201:0.39281926 202:0.39281926 203:0.39281926 204:0.39281926 205:0.24999732 206:0.26789024 207:0.26789024 208:0.26789024 209:0.24999732 210:0.24999732 211:0.26789024 212:0.24999732 213:0.24999732 214:0.26789024 215:0.24999732 216:0.24999732 217:0.24999732 218:0.24999732 219:0.24999732 220:0.26789024 221:0.3 222:0.3 223:0.3167 224:0.3167 225:0.3167 226:0.35 227:0.35 228:0.3667 229:0.3667 230:0.3667 231:0.3667 232:0.3667 233:0.3667 234:0.3833 235:0.3833 236:0.4 237:0.4 238:0.4167 239:0.4333 240:0.4333 241:0.45 242:0.4667 243:0.4833 244:0.5 245:0.5167 246:0.5333 247:0.55 248:0.5667 249:0.6 250:0.6333 251:0.65 252:0.6833 253:0.7 254:0.7 255:0.7 256:0.7 257:0.7 258:0.6667 259:0.7 260:0.6333 261:0.6333 262:0.6333 263:0.6167 264:0.5667 265:0.5667 266:0.5667 267:0.5667 268:0.5667 269:0.5667 270:0.5667 271:0.5667 272:0.5667 273:0.5667 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:0.95 294:0.9167 295:0.8833 296:0.8833 297:0.8833 298:0.8833 299:0.8667 300:0.85 301:0.8167 302:0.8 303:0.7667 304:0.75 305:0.75 306:0.75 307:0.7333 308:0.6833 309:0.6667 310:0.6333 311:0.6167 312:0.6 313:0.6 314:0.6167 315:0.6 316:0.6167 317:0.6167 318:0.5667 319:0.55 320:0.55 321:0.55 322:0.55 323:0.55 324:0.55 325:0.35 326:0.35 327:0.3333 328:0.3333 329:0.3333 330:0.3333 331:0.3333 332:0.3333 333:0.3333 334:0.3333 335:0.3333 336:0.3333 337:0.3333 338:0.3333 339:0.3333 340:0.3333 341:0.3333 342:0.3333 343:0.35 344:0.35 345:0.3333 346:0.4333 347:0.4333 348:0.4333 349:0.4333 350:0.4333 351:0.4333 352:0.4333 353:0.4333 354:0.4333 355:0.4333 356:0.4333 357:0.4333 358:0.4333 359:0.4333 360:0.4333
-1.46790920289066 1:0.2167 2:0.2167 3:0.2167 4:0.2167 5:0.2167 6:0.2167 7:0.2167 8:0.2167 9:0.2167 10:0.2167 11:0.2167 12:0.2167 13:0.2167 14:0.2167 15:0.2167 16:0.2167 17:0.2167 18:0.2167 19:0.2167 20:0.2167 21:0.2167 22:0.2167 23:0.2167 24:0.2167 25:0.2167 26:0.1 27:0.1 28:0.08333 29:0.08333 30:0.08333 31:0.08333 32:0.08333 33:0.08333 34:0.08333 35:0.08333 36:0.08333 37:0.08333 38:0.08333 39:0.1 40:0.08333 41:0.08333 42:0.08333 43:0.08333 44:0.08333 45:0.08333 46:0.08333 47:0.1 48:0.1 49:0.1 50:0.08333 51:0.08333 52:0.08333 53:0.08333 54:0.08333 55:0.08333 56:0.1 57:0.1 58:0.1 59:0.08333 60:0.08333 61:0.08333 62:0.08333 63:0.08333 64:0.08333 65:0.08333 66:0.08333 67:0.08333 68:0.08333 69:0.08333 70:0.08333 71:0.08333 72:0.08333 73:0.08333 74:0.08333 75:0.08333 76:0.1 77:0.1 78:0.1 79:0.1167 80:0.1333 81:0.1333 82:0.4333 83:0.4333 84:0.6833 85:0.6 86:0.5667 87:0.5667 88:0.5667 89:0.5667 90:0.5667 91:0.5667 92:0.5667 93:0.5667 94:0.5833 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:0.8333 106:0.8 107:0.8 108:0.8 109:0.8 110:0.8 111:0.8 112:0.5333 113:0.5333 114:0.5333 115:0.5167 116:0.5 117:0.4667 118:0.4667 119:0.45 120:0.4333 121:0.4167 122:0.4 123:0.4 124:0.3833 125:0.3667 126:0.3667 127:0.35 128:0.35 129:0.3333 130:0.3 131:0.3167 132:0.3167 133:0.3167 134:0.3167 135:0.3 136:0.3 137:0.3 138:0.2833 139:0.2833 140:0.2833 141:0.2833 142:0.24557895 143:0.22810526 144:0.22810526 145:0.22810526 146:0.22810526 147:0.22810526 148:0.22810526 149:0.22810526 150:0.22810526 151:0.21052632 152:0.21052632 153:0.21052632 154:0.21052632 155:0.21052632 156:0.21052632 157:0.17853278 158:0.17853278 159:0.17853278 160:0.17853278 161:0.17853278 162:0.17853278 163:0.17853278 164:0.17853278 165:0.17853278 166:0.17853278 167:0.17853278 168:0.17853278 169:0.17853278 170:0.17853278 171:0.17853278 172:0.17853278 173:0.17853278 174:0.17853278 175:0.17853278 176:0.17853278 177:0.17853278 178:0.17853278 179:0.17853278 180:0.17853278 181:0.17853278 182:0.17853278 183:0.17853278 184:0.160747 185:0.160747 186:0.160747 187:0.160747 188:0.160747 189:0.160747 190:0.160747 191:0.160747 192:0.160747 193:0.160747 194:0.160747 195:0.160747 196:0.160747 197:0.160747 198:0.160747 199:0.160747 200:0.160747 201:0.160747 202:0.160747 203:0.160747 204:0.160747 205:0.160747 206:0.160747 207:0.17853278 208:0.17853278 209:0.17853278 210:0.17853278 211:0.17853278 212:0.17853278 213:0.17853278 214:0.17853278 215:0.21431862 216:0.21431862 217:0.21431862 218:0.21431862 219:0.21431862 220:0.2321044 221:0.2833 222:0.2833 223:0.2833 224:0.2833 225:0.3 226:0.3 227:0.3 228:0.3167 229:0.3167 230:0.3167 231:0.3333 232:0.3333 233:0.3333 234:0.35 235:0.35 236:0.35 237:0.35 238:0.35 239:0.3667 240:0.3667 241:0.45 242:0.5 243:0.4833 244:0.5 245:0.55 246:0.5667 247:0.55 248:0.55 249:0.55 250:0.5833 251:0.6 252:0.7 253:0.7 254:0.7167 255:0.75 256:0.7833 257:0.7833 258:0.7833 259:0.7833 260:0.7833 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:0.85 277:0.7167 278:0.6167 279:0.5333 280:0.4667 281:0.4333 282:0.3833 283:0.3833 284:0.3833 285:0.3667 286:0.3667 287:0.2667 288:0.2667 289:0.2667 290:0.2833 291:0.2667 292:0.2667 293:0.2833 294:0.2667 295:0.2667 296:0.2667 297:0.2667 298:0.2667 299:0.2667 300:0.2833 301:0.2667 302:0.2667 303:0.2833 304:0.2833 305:0.2667 306:0.2833 307:0.2833 308:0.2667 309:0.2667 310:0.2833 311:0.2833 312:0.2667 313:0.2667 314:0.2667 315:0.25 316:0.25 317:0.25 318:0.25 319:0.25 320:0.2333 321:0.2333 322:0.2333 323:0.2333 324:0.2 325:0.2 326:0.2 327:0.2 328:0.2 329:0.2 330:0.2 331:0.2 332:0.2 333:0.1833 334:0.1833 335:0.2 336:0.2 337:0.2 338:0.2 339:0.1833 340:0.2 341:0.2 342:0.2 343:0.2 344:0.2 345:0.2 346:0.2 347:0.2 348:0.2 349:0.2 350:0.2 351:0.2 352:0.1833 353:0.1833 354:0.2 355:0.2167 356:0.2167 357:0.2167 358:0.2167 359:0.2167 360:0.2167
-0.4885576313018514 1:0.35 2:0.35 3:0.35 4:0.35 5:0.35 6:0.35 7:0.35 8:0.35 9:0.35 10:0.35 11:0.35 12:0.35 13:0.35 14:0.35 15:0.35 16:0.35 17:0.35 18:0.35 19:0.35 20:0.3667 21:0.3667 22:0.3667 23:0.3667 24:0.3667 25:0.3667 26:0.3667 27:0.3667 28:0.3833 29:0.3833 30:0.3833 31:0.3833 32:0.3833 33:0.4 34:0.4 35:0.4 36:0.4 37:0.4167 38:0.4167 39:0.4167 40:0.4333 41:0.45 42:0.45 43:0.45 44:0.4667 45:0.4667 46:0.4667 47:0.4667 48:0.4833 49:0.4833 50:0.5 51:0.5333 52:0.5167 53:0.5333 54:0.55 55:0.55 56:0.6 57:0.6 58:0.6 59:0.6167 60:0.7 61:0.7 62:0.7 63:0.7 64:0.8 65:0.7 66:0.8 67:0.9 68:0.9 69:0.9667 70:0.9667 71:0.9667 72:1 73:1 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:0.5833 101:0.55 102:0.55 103:0.55 104:0.55 105:0.55 106:0.55 107:0.55 108:0.55 109:0.55 110:0.55 111:1 112:1 113:1 114:1 115:1 116:1 117:1 118:1 119:1 120:1 121:1 122:1 123:0.9667 124:0.9667 125:0.6833 126:0.6667 127:0.55 128:0.55 129:0.55 130:0.55 131:0.55 132:0.55 133:0.4833 134:0.4833 135:0.4667 136:0.4667 137:0.45 138:0.45 139:0.45 140:0.45 141:0.45 142:0.42105263 143:0.42105263 144:0.42105263 145:0.42105263 146:0.42105263 147:0.42105263 148:0.35084211 149:0.35084211 150:0.42105263 151:0.35084211 152:0.35084211 153:0.35084211 154:0.35084211 155:0.33336842 156:0.33336842 157:0.32146186 158:0.32146186 159:0.32146186 160:0.32146186 161:0.32146186 162:0.32146186 163:0.32146186 164:0.32146186 165:0.32146186 166:0.32146186 167:0.28567602 168:0.28567602 169:0.28567602 170:0.28567602 171:0.28567602 172:0.28567602 173:0.28567602 174:0.28567602 175:0.28567602 176:0.28567602 177:0.28567602 178:0.28567602 179:0.28567602 180:0.28567602 181:0.28567602 182:0.28567602 183:0.28567602 184:0.28567602 185:0.28567602 186:0.28567602 187:0.28567602 188:0.28567602 189:0.28567602 190:0.28567602 191:0.28567602 192:0.28567602 193:0.28567602 194:0.30356894 195:0.30356894 196:0.30356894 197:0.30356894 198:0.30356894 199:0.30356894 200:0.30356894 201:0.30356894 202:0.30356894 203:0.30356894 204:0.32146186 205:0.32146186 206:0.32146186 207:0.32146186 208:0.32146186 209:0.32146186 210:0.32146186 211:0.83928514 212:0.60710574 213:0.60710574 214:0.60710574 215:0.60710574 216:0.60710574 217:0.60710574 218:0.60710574 219:0.60710574 220:0.60710574 221:0.5833 222:0.5833 223:0.5667 224:0.55 225:0.5667 226:0.5667 227:0.5667 228:0.5667 229:0.5667 230:0.5667 231:0.5667 232:0.5667 233:0.3333 234:0.3333 235:0.3333 236:0.3167 237:0.3167 238:0.3167 239:0.3167 240:0.3167 241:0.3167 242:0.3 243:0.3 244:0.3 245:0.3 246:0.3 247:0.3 248:0.3 249:0.3 250:0.3 251:0.3 252:0.3 253:0.3 254:0.3 255:0.3 256:0.3 257:0.3 258:0.3333 259:0.35 260:0.3833 261:0.4333 262:0.4667 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:0.7833 280:0.7833 281:0.7833 282:0.7833 283:0.7833 284:0.7833 285:1 286:1 287:1 288:1 289:1 290:1 291:0.95 292:0.9 293:0.8667 294:0.8333 295:0.8333 296:0.8 297:0.8167 298:0.8 299:0.8 300:0.8 301:0.7833 302:0.7833 303:0.7833 304:0.7833 305:0.7833 306:0.7833 307:0.6333 308:0.5667 309:0.6 310:0.5667 311:0.6167 312:0.6 313:0.5667 314:0.55 315:0.4667 316:0.4667 317:0.45 318:0.45 319:0.45 320:0.4333 321:0.4333 322:0.4333 323:0.4167 324:0.4167 325:0.4167 326:0.4 327:0.4 328:0.4 329:0.4 330:0.3833 331:0.3833 332:0.3833 333:0.3833 334:0.3833 335:0.3667 336:0.3667 337:0.3667 338:0.3667 339:0.3667 340:0.3667 341:0.3667 342:0.3667 343:0.3667 344:0.3667 345:0.35 346:0.35 347:0.35 348:0.35 349:0.35 350:0.35 351:0.35 352:0.35 353:0.35 354:0.35 355:0.35 356:0.35 357:0.35 358:0.35 359:0.35 360:0.35
-1.130700285543645 1:0.4 2:0.4 3:0.4 4:0.4 5:0.4 6:0.4 7:0.4 8:0.4 9:0.4 10:0.4167 11:0.4167 12:0.4167 13:0.4167 14:0.4333 15:0.4333 16:0.4333 17:0.4333 18:0.4333 19:0.4333 20:0.4333 21:0.4333 22:0.4333 23:0.4333 24:0.4333 25:0.4667 26:0.4667 27:0.4667 28:0.4667 29:0.4667 30:0.4833 31:0.4833 32:0.4833 33:0.4833 34:0.5 35:0.5 36:0.5 37:0.5167 38:0.5333 39:0.5333 40:0.55 41:0.5333 42:0.5833 43:0.5833 44:0.5833 45:0.6 46:0.6 47:0.65 48:0.65 49:0.6333 50:0.65 51:0.6667 52:0.6833 53:0.7167 54:0.7333 55:0.75 56:0.7667 57:0.8333 58:0.8333 59:0.8333 60:0.8667 61:0.8833 62:0.8833 63:0.9833 64:0.9833 65:1 66:1 67:1 68:1 69:1 70:1 71:1 72:1 73:1 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:0.8833 116:0.8667 117:0.85 118:0.8333 119:0.8333 120:0.8333 121:0.7833 122:0.7833 123:0.6833 124:0.6667 125:0.65 126:0.6333 127:0.6167 128:0.6167 129:0.6333 130:0.5667 131:0.5667 132:0.55 133:0.55 134:0.55 135:0.55 136:0.5167 137:0.5 138:0.5 139:0.4833 140:0.4833 141:0.4667 142:0.43863158 143:0.43863158 144:0.42105263 145:0.42105263 146:0.42105263 147:0.42105263 148:0.386 149:0.386 150:0.386 151:0.36842105 152:0.386 153:0.36842105 154:0.386 155:0.386 156:0.36842105 157:0.37503348 158:0.35714056 159:0.33924764 160:0.33924764 161:0.33924764 162:0.33924764 163:0.33924764 164:0.33924764 165:0.33924764 166:0.33924764 167:0.33924764 168:0.33924764 169:0.33924764 170:0.33924764 171:0.33924764 172:0.33924764 173:0.33924764 174:0.33924764 175:0.33924764 176:0.33924764 177:0.33924764 178:0.35714056 179:0.35714056 180:0.83928514 181:0.83928514 182:0.83928514 183:0.83928514 184:0.83928514 185:0.83928514 186:0.64289158 187:0.64289158 188:0.64289158 189:0.64289158 190:0.85717806 191:0.64289158 192:0.64289158 193:0.85717806 194:0.85717806 195:0.41071218 196:0.41071218 197:0.41071218 198:0.4286051 199:0.41071218 200:0.4286051 201:0.41071218 202:0.4286051 203:0.41071218 204:0.41071218 205:0.4286051 206:0.4286051 207:0.4999625 208:0.48217672 209:0.4999625 210:0.4999625 211:0.62499866 212:0.4999625 213:0.4999625 214:0.4999625 215:0.48217672 216:0.48217672 217:0.4642838 218:0.4642838 219:0.4642838 220:0.4642838 221:0.5 222:0.5 223:0.5 224:0.5 225:0.5 226:0.5167 227:0.5167 228:0.5167 229:0.5167 230:0.5167 231:0.5333 232:0.55 233:0.55 234:0.5667 235:0.5833 236:0.6 237:0.6167 238:0.75 239:0.75 240:0.7167 241:0.7167 242:0.7167 243:0.9167 244:1 245:1 246:0.85 247:0.85 248:0.85 249:0.85 250:0.85 251:0.85 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:0.9 288:0.9 289:0.9 290:0.9 291:0.9 292:0.9 293:0.9 294:0.9167 295:0.75 296:0.7333 297:0.7 298:0.7167 299:0.7167 300:0.7 301:0.6167 302:0.6 303:0.5833 304:0.5667 305:0.5667 306:0.5667 307:0.55 308:0.55 309:0.55 310:0.55 311:0.55 312:0.55 313:0.5333 314:0.5333 315:0.5333 316:0.5333 317:0.5333 318:0.4667 319:0.4667 320:0.4667 321:0.45 322:0.45 323:0.4333 324:0.4333 325:0.4333 326:0.4333 327:0.4167 328:0.4167 329:0.4167 330:0.4167 331:0.4167 332:0.4167 333:0.4167 334:0.4167 335:0.4167 336:0.4167 337:0.4 338:0.4 339:0.4 340:0.4 341:0.4 342:0.4 343:0.4 344:0.4 345:0.4 346:0.3833 347:0.3833 348:0.3833 349:0.3833 350:0.3833 351:0.3833 352:0.3833 353:0.3833 354:0.3833 355:0.3833 356:0.3833 357:0.3833 358:0.4 359:0.4 360:0.4
-0.5977584850516793 1:0.45 2:0.45 3:0.45 4:0.45 5:0.45 6:0.45 7:0.45 8:0.45 9:0.45 10:0.45 11:0.45 12:0.45 13:0.45 14:0.45 15:0.45 16:0.45 17:0.4667 18:0.4667 19:0.4667 20:0.4667 21:0.4667 22:0.4667 23:0.4667 24:0.4833 25:0.4833 26:0.4833 27:0.4833 28:0.4833 29:0.5 30:0.5 31:0.5 32:0.5 33:0.5 34:0.5 35:0.5167 36:0.5167 37:0.55 38:0.5167 39:0.5667 40:0.55 41:0.5667 42:0.5667 43:0.5833 44:0.5833 45:0.6 46:0.6167 47:0.6167 48:0.6 49:0.6167 50:0.65 51:0.6667 52:0.65 53:0.6667 54:0.7 55:0.7 56:0.75 57:0.7667 58:0.7833 59:0.7667 60:0.8333 61:0.85 62:0.9333 63:0.9333 64:0.9333 65:0.9667 66:0.9667 67:1 68:1 69:1 70:1 71:1 72:1 73:1 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:0.8333 101:0.8333 102:0.8333 103:0.8333 104:0.8333 105:0.8333 106:0.8333 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:1 118:0.8833 119:0.7667 120:0.7667 121:0.75 122:0.7333 123:0.7167 124:0.7167 125:0.7167 126:0.7167 127:0.6667 128:0.6 129:0.6 130:0.6 131:0.6 132:0.5667 133:0.5667 134:0.5667 135:0.5667 136:0.5167 137:0.5167 138:0.5167 139:0.5167 140:0.5167 141:0.4667 142:0.43863158 143:0.43863158 144:0.43863158 145:0.43863158 146:0.42105263 147:0.40347368 148:0.40347368 149:0.40347368 150:0.40347368 151:0.386 152:0.386 153:0.386 154:0.386 155:0.386 156:0.36842105 157:0.35714056 158:0.35714056 159:0.35714056 160:0.35714056 161:0.35714056 162:0.35714056 163:0.35714056 164:0.35714056 165:0.35714056 166:0.35714056 167:0.35714056 168:0.35714056 169:0.35714056 170:0.35714056 171:1 172:0.85717806 173:0.4286051 174:0.4286051 175:0.4286051 176:0.4286051 177:0.4286051 178:0.4286051 179:0.4286051 180:0.41071218 181:0.41071218 182:0.41071218 183:0.41071218 184:0.41071218 185:0.39281926 186:0.39281926 187:0.39281926 188:0.39281926 189:0.39281926 190:0.39281926 191:0.39281926 192:0.39281926 193:0.39281926 194:0.35714056 195:0.35714056 196:0.35714056 197:0.33924764 198:0.35714056 199:0.35714056 200:0.35714056 201:0.35714056 202:0.35714056 203:0.35714056 204:0.35714056 205:0.35714056 206:0.35714056 207:0.35714056 208:0.35714056 209:0.35714056 210:0.35714056 211:0.35714056 212:0.39281926 213:0.39281926 214:0.39281926 215:0.39281926 216:0.39281926 217:0.39281926 218:0.48217672 219:0.48217672 220:0.48217672 221:0.5167 222:0.5333 223:0.5333 224:0.55 225:0.55 226:0.5667 227:0.5667 228:0.5833 229:0.5667 230:0.6 231:0.6 232:0.5667 233:0.6 234:0.5667 235:0.6167 236:0.6333 237:0.7 238:0.7167 239:0.7333 240:0.7167 241:0.7167 242:0.7167 243:0.7333 244:0.75 245:0.7833 246:0.8 247:0.8333 248:0.8667 249:0.9167 250:0.95 251:1 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:1 293:1 294:1 295:1 296:1 297:1 298:0.9333 299:0.9333 300:0.9333 301:0.9333 302:0.9333 303:0.95 304:0.75 305:0.7333 306:0.7333 307:0.7333 308:0.7167 309:0.6667 310:0.6333 311:0.6167 312:0.6167 313:0.6167 314:0.6167 315:0.6167 316:0.6 317:0.6 318:0.5833 319:0.5833 320:0.5667 321:0.5667 322:0.5667 323:0.5667 324:0.5667 325:0.5667 326:0.5667 327:0.5667 328:0.55 329:0.55 330:0.55 331:0.55 332:0.5 333:0.5 334:0.4833 335:0.4833 336:0.4833 337:0.4833 338:0.4833 339:0.4833 340:0.4833 341:0.4667 342:0.4667 343:0.4667 344:0.4667 345:0.4667 346:0.45 347:0.45 348:0.45 349:0.45 350:0.45 351:0.45 352:0.45 353:0.45 354:0.45 355:0.45 356:0.45 357:0.45 358:0.45 359:0.45 360:0.45
-0.1733932787329221 1:0.4333 2:0.4333 3:0.4333 4:0.4333 5:0.4667 6:0.4833 7:0.4833 8:0.4833 9:0.4833 10:0.5 11:0.5 12:0.5 13:0.45 14:0.45 15:0.45 16:0.45 17:0.45 18:0.45 19:0.45 20:0.45 21:0.45 22:0.45 23:0.5 24:0.4833 25:0.5 26:0.4833 27:0.5 28:0.4833 29:0.5 30:0.5 31:0.5 32:0.5 33:0.5167 34:0.5167 35:0.5167 36:0.5333 37:0.5333 38:0.5333 39:0.55 40:0.55 41:0.5667 42:0.5667 43:0.5667 44:0.5833 45:0.5667 46:0.65 47:0.6667 48:0.6667 49:0.6667 50:0.6833 51:0.65 52:0.65 53:0.65 54:0.65 55:0.65 56:0.65 57:0.65 58:0.5333 59:0.5333 60:0.5333 61:0.5333 62:0.5333 63:0.5333 64:0.5167 65:0.5333 66:0.5333 67:0.5333 68:0.5333 69:0.9667 70:0.9667 71:0.9667 72:0.55 73:0.55 74:0.55 75:0.55 76:0.55 77:0.55 78:0.55 79:0.55 80:0.55 81:0.55 82:0.55 83:0.55 84:0.55 85:0.55 86:0.9167 87:0.9167 88:0.9167 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:0.4667 118:0.4667 119:0.45 120:0.4333 121:0.3833 122:0.3667 123:0.3667 124:0.35 125:0.35 126:0.3333 127:0.3333 128:0.3167 129:0.3167 130:0.3 131:0.3 132:0.3 133:0.2833 134:0.2833 135:0.25 136:0.25 137:0.25 138:0.25 139:0.25 140:0.2333 141:0.2333 142:0.19294737 143:0.19294737 144:0.19294737 145:0.17547368 146:0.17547368 147:0.17547368 148:0.17547368 149:0.17547368 150:0.17547368 151:0.17547368 152:0.17547368 153:0.17547368 154:0.19294737 155:0.17547368 156:0.17547368 157:0.160747 158:0.17853278 159:0.160747 160:0.160747 161:0.160747 162:0.160747 163:0.160747 164:0.160747 165:0.160747 166:0.160747 167:0.17853278 168:0.1964257 169:0.2321044 170:0.2321044 171:0.2321044 172:0.2321044 173:0.41071218 174:0.41071218 175:0.41071218 176:0.41071218 177:0.41071218 178:0.41071218 179:0.41071218 180:0.41071218 181:0.41071218 182:0.41071218 183:0.41071218 184:0.41071218 185:0.39281926 186:0.39281926 187:0.39281926 188:0.39281926 189:0.39281926 190:0.39281926 191:0.39281926 192:0.39281926 193:0.39281926 194:0.39281926 195:0.39281926 196:0.39281926 197:0.41071218 198:0.41071218 199:0.41071218 200:0.41071218 201:0.41071218 202:0.41071218 203:0.41071218 204:0.41071218 205:0.4286051 206:0.4286051 207:0.4286051 208:0.4286051 209:0.4286051 210:0.4286051 211:0.4286051 212:0.4286051 213:0.4286051 214:0.44639088 215:0.44639088 216:0.44639088 217:0.4642838 218:0.4642838 219:0.4642838 220:0.48217672 221:0.5167 222:0.5333 223:0.5333 224:0.5333 225:0.55 226:0.5333 227:0.55 228:0.55 229:0.5667 230:0.5833 231:0.5833 232:0.6 233:0.6667 234:0.6667 235:0.6667 236:0.6833 237:0.6667 238:0.6833 239:0.6833 240:0.7 241:0.7167 242:0.7167 243:0.7333 244:0.75 245:0.7833 246:0.8 247:0.8167 248:0.8333 249:0.8667 250:0.9 251:0.95 252:0.9333 253:0.9333 254:0.9333 255:0.9333 256:0.9333 257:0.95 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:1 292:0.95 293:0.9167 294:0.8667 295:0.8333 296:0.8 297:0.7833 298:0.75 299:0.7333 300:0.7167 301:0.6833 302:0.6667 303:0.6667 304:0.6667 305:0.65 306:0.6333 307:0.6333 308:0.5667 309:0.55 310:0.55 311:0.55 312:0.55 313:0.55 314:0.55 315:0.55 316:0.4833 317:0.4833 318:0.4667 319:0.4667 320:0.4667 321:0.45 322:0.45 323:0.4333 324:0.4333 325:0.4333 326:0.4333 327:0.4167 328:0.4167 329:0.4167 330:0.4167 331:0.4 332:0.4 333:0.4 334:0.4 335:0.4 336:0.4 337:0.4 338:0.4 339:0.3833 340:0.3833 341:0.3833 342:0.3833 343:0.3833 344:0.3833 345:0.3667 346:0.3667 347:0.3667 348:0.3667 349:0.3667 350:0.3667 351:0.3667 352:0.3667 353:0.3667 354:0.3667 355:0.3667 356:0.3667 357:0.3667 358:0.3667 359:0.3667 360:0.4333
-0.3516405260248972 1:0.3 2:0.3 3:0.3 4:0.3 5:0.3 6:0.3 7:0.3 8:0.3 9:0.3 10:0.3 11:0.3 12:0.3 13:0.3 14:0.3 15:0.3 16:0.3 17:0.3 18:0.3 19:0.3 20:0.3 21:0.3 22:0.3167 23:0.3167 24:0.3167 25:0.3167 26:0.3167 27:0.3167 28:0.3167 29:0.3167 30:0.3333 31:0.3333 32:0.3 33:0.3 34:0.3 35:0.2833 36:0.2833 37:0.2667 38:0.2833 39:0.2833 40:0.2833 41:0.2833 42:0.2667 43:0.2833 44:0.2833 45:0.2667 46:0.2833 47:0.2667 48:0.2833 49:0.2833 50:0.2667 51:0.2833 52:0.2833 53:0.2833 54:0.2833 55:0.2667 56:0.3 57:0.9667 58:1 59:1 60:0.6 61:0.4833 62:0.4833 63:0.4833 64:0.4833 65:0.4833 66:0.4833 67:0.4833 68:0.4167 69:0.4167 70:0.4167 71:0.4167 72:0.4167 73:0.4167 74:0.4167 75:0.4167 76:0.4167 77:0.4167 78:0.4167 79:0.4167 80:0.4167 81:0.4167 82:0.4167 83:0.4167 84:0.4167 85:0.4167 86:0.4333 87:0.4333 88:0.4333 89:0.4333 90:0.4333 91:0.4333 92:0.4333 93:0.4333 94:0.4333 95:0.4333 96:0.4333 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:0.9 109:0.9 110:0.9 111:0.9 112:0.9 113:0.9 114:0.9167 115:0.8833 116:0.85 117:0.8167 118:0.7833 119:0.7667 120:0.7333 121:0.7167 122:0.7 123:0.6833 124:0.6667 125:0.65 126:0.6333 127:0.6167 128:0.6 129:0.5833 130:0.5667 131:0.5667 132:0.55 133:0.5333 134:0.5333 135:0.5167 136:0.5167 137:0.5 138:0.5 139:0.4833 140:0.4833 141:0.4833 142:0.45610526 143:0.45610526 144:0.45610526 145:0.43863158 146:0.43863158 147:0.40347368 148:0.40347368 149:0.40347368 150:0.40347368 151:0.386 152:0.386 153:0.386 154:0.386 155:0.386 156:0.36842105 157:0.35714056 158:0.35714056 159:0.35714056 160:0.35714056 161:0.35714056 162:0.35714056 163:0.35714056 164:0.35714056 165:0.35714056 166:0.35714056 167:0.35714056 168:0.33924764 169:0.33924764 170:0.33924764 171:0.33924764 172:0.33924764 173:0.33924764 174:0.33924764 175:0.33924764 176:0.33924764 177:0.24999732 178:0.24999732 179:0.24999732 180:0.24999732 181:0.24999732 182:0.24999732 183:0.24999732 184:0.24999732 185:0.24999732 186:0.24999732 187:0.24999732 188:0.24999732 189:0.24999732 190:0.24999732 191:0.24999732 192:0.24999732 193:0.24999732 194:0.24999732 195:0.24999732 196:0.24999732 197:0.24999732 198:0.24999732 199:0.24999732 200:0.24999732 201:0.37503348 202:0.37503348 203:0.37503348 204:0.37503348 205:0.37503348 206:0.39281926 207:0.39281926 208:0.39281926 209:0.39281926 210:0.39281926 211:0.41071218 212:0.41071218 213:0.41071218 214:0.41071218 215:0.4286051 216:0.41071218 217:0.41071218 218:0.41071218 219:0.41071218 220:0.41071218 221:0.45 222:0.45 223:0.45 224:0.45 225:0.45 226:0.4333 227:0.45 228:0.45 229:0.5667 230:0.5833 231:0.5833 232:0.6 233:0.6167 234:0.6333 235:0.6333 236:0.6833 237:0.7 238:0.7167 239:0.7333 240:0.7667 241:0.7833 242:0.8 243:0.8667 244:0.8667 245:0.9 246:0.9333 247:1 248:1 249:1 250:1 251:1 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:0.4667 273:0.4667 274:0.4667 275:0.4 276:0.4 277:0.4 278:0.4 279:0.4 280:0.4 281:0.4 282:0.4 283:0.4 284:0.4 285:0.4 286:0.4 287:0.4 288:0.4167 289:0.4167 290:0.9167 291:0.9167 292:0.9167 293:0.9167 294:1 295:1 296:1 297:1 298:1 299:1 300:1 301:1 302:1 303:1 304:1 305:1 306:1 307:1 308:1 309:1 310:1 311:1 312:1 313:1 314:1 315:1 316:1 317:0.3833 318:0.3833 319:0.3833 320:0.3667 321:0.3667 322:0.3667 323:0.35 324:0.35 325:0.35 326:0.35 327:0.3333 328:0.3333 329:0.3333 330:0.3333 331:0.3333 332:0.3333 333:0.3167 334:0.3167 335:0.3167 336:0.3167 337:0.3167 338:0.3167 339:0.3167 340:0.3167 341:0.3 342:0.3 343:0.3 344:0.3 345:0.3 346:0.3 347:0.3 348:0.3 349:0.3 350:0.3 351:0.3 352:0.3 353:0.3 354:0.3 355:0.3 356:0.3 357:0.3 358:0.3 359:0.3 360:0.3
-0.7970714984249795 1:0.35 2:0.35 3:0.35 4:0.35 5:0.35 6:0.35 7:0.35 8:0.35 9:0.35 10:0.35 11:0.35 12:0.35 13:0.35 14:0.35 15:0.35 16:0.35 17:0.35 18:0.35 19:0.35 20:0.3667 21:0.3667 22:0.3667 23:0.3667 24:0.3667 25:0.3667 26:0.3667 27:0.3667 28:0.3833 29:0.3833 30:0.3833 31:0.3833 32:0.3833 33:0.4 34:0.4 35:0.4 36:0.4 37:0.4167 38:0.4167 39:0.4167 40:0.4333 41:0.4333 42:0.4333 43:0.45 44:0.45 45:0.45 46:0.4667 47:0.4667 48:0.4833 49:0.4833 50:0.5 51:0.5167 52:0.5167 53:0.5333 54:0.55 55:0.55 56:0.5667 57:0.6167 58:0.6167 59:0.6167 60:0.6667 61:0.65 62:0.6667 63:0.7 64:0.75 65:0.7333 66:0.7833 67:0.8 68:0.8167 69:0.8833 70:0.8833 71:0.9667 72:0.9667 73:1 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:0.15 84:0.15 85:0.15 86:0.15 87:0.15 88:0.15 89:0.15 90:0.15 91:0.15 92:0.15 93:0.15 94:0.15 95:0.15 96:0.15 97:0.15 98:0.15 99:0.15 100:0.15 101:0.15 102:0.15 103:0.15 104:0.15 105:0.15 106:0.15 107:0.15 108:0.15 109:0.15 110:0.15 111:0.15 112:0.15 113:0.15 114:0.15 115:0.15 116:0.15 117:0.15 118:0.15 119:0.15 120:0.15 121:0.15 122:0.15 123:0.15 124:0.1667 125:0.1667 126:0.1667 127:0.1667 128:0.1667 129:0.1667 130:0.1667 131:0.1667 132:0.1667 133:0.1667 134:0.45 135:0.45 136:0.4333 137:0.4333 138:0.4333 139:0.4167 140:0.4167 141:0.4167 142:0.36842105 143:0.36842105 144:0.36842105 145:0.35084211 146:0.35084211 147:0.35084211 148:0.35084211 149:0.33336842 150:0.33336842 151:0.33336842 152:0.33336842 153:0.33336842 154:0.31578947 155:0.31578947 156:0.31578947 157:0.30356894 158:0.30356894 159:0.30356894 160:0.30356894 161:0.30356894 162:0.28567602 163:0.28567602 164:0.28567602 165:0.28567602 166:0.28567602 167:0.28567602 168:0.28567602 169:0.28567602 170:0.28567602 171:0.28567602 172:0.28567602 173:0.28567602 174:0.28567602 175:0.28567602 176:0.28567602 177:0.28567602 178:0.28567602 179:0.28567602 180:0.28567602 181:0.28567602 182:0.28567602 183:0.28567602 184:0.28567602 185:0.28567602 186:0.28567602 187:0.28567602 188:0.28567602 189:0.28567602 190:0.28567602 191:0.28567602 192:0.28567602 193:0.28567602 194:0.28567602 195:0.28567602 196:0.28567602 197:0.28567602 198:0.28567602 199:0.28567602 200:0.28567602 201:0.30356894 202:0.30356894 203:0.30356894 204:0.30356894 205:0.30356894 206:0.30356894 207:0.30356894 208:0.30356894 209:0.32146186 210:0.32146186 211:0.32146186 212:0.32146186 213:0.32146186 214:0.33924764 215:0.33924764 216:0.33924764 217:0.33924764 218:0.35714056 219:0.35714056 220:0.35714056 221:0.4167 222:0.4167 223:0.4167 224:0.4333 225:0.4333 226:0.4333 227:0.45 228:0.45 229:0.4667 230:0.4667 231:0.4833 232:0.5 233:0.5 234:0.5167 235:0.5333 236:0.5333 237:0.55 238:0.5667 239:0.5833 240:0.6 241:0.6167 242:0.6333 243:0.65 244:0.6833 245:0.7 246:0.7333 247:0.75 248:0.7833 249:0.8167 250:0.85 251:0.9 252:0.95 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:1 290:1 291:0.95 292:0.9 293:0.8667 294:0.8333 295:0.8 296:0.7667 297:0.7333 298:0.7167 299:0.7 300:0.6667 301:0.65 302:0.6333 303:0.6167 304:0.6 305:0.5833 306:0.5667 307:0.55 308:0.55 309:0.5333 310:0.5333 311:0.5333 312:0.5333 313:0.4833 314:0.4833 315:0.4667 316:0.4667 317:0.45 318:0.45 319:0.45 320:0.4333 321:0.4333 322:0.4333 323:0.4167 324:0.4167 325:0.4167 326:0.4 327:0.4 328:0.4 329:0.4 330:0.3833 331:0.3833 332:0.3833 333:0.3833 334:0.3833 335:0.3667 336:0.3667 337:0.3667 338:0.3667 339:0.3667 340:0.3667 341:0.3667 342:0.3667 343:0.35 344:0.35 345:0.35 346:0.35 347:0.35 348:0.35 349:0.35 350:0.35 351:0.35 352:0.35 353:0.35 354:0.35 355:0.35 356:0.35 357:0.35 358:0.35 359:0.35 360:0.35
-0.6987935041815414 1:0.45 2:0.45 3:0.45 4:0.45 5:0.45 6:0.45 7:0.45 8:0.45 9:0.45 10:0.45 11:0.4833 12:0.4833 13:0.4833 14:0.4833 15:0.4667 16:0.4667 17:0.4667 18:0.4833 19:0.4667 20:0.4833 21:0.4667 22:0.4667 23:0.4667 24:0.4833 25:0.4833 26:0.4833 27:0.4833 28:0.4833 29:0.5 30:0.5 31:0.5333 32:0.5333 33:0.55 34:0.5333 35:0.5333 36:0.5333 37:0.5333 38:0.5333 39:0.55 40:0.55 41:0.6 42:0.6 43:0.6 44:0.6167 45:1 46:1 47:0.45 48:0.45 49:1 50:0.45 51:0.5 52:0.45 53:0.4833 54:0.45 55:0.45 56:0.4 57:0.4 58:0.4 59:0.4 60:0.4 61:0.4 62:0.4 63:0.4 64:0.4 65:0.4 66:0.4 67:0.4 68:0.4 69:0.4167 70:0.4333 71:0.4667 72:0.5333 73:0.5333 74:0.5333 75:0.5333 76:0.55 77:0.5833 78:0.9333 79:0.9333 80:0.9333 81:0.7333 82:0.7333 83:0.7333 84:0.7333 85:0.7333 86:0.7333 87:0.7333 88:0.7333 89:0.7333 90:0.7333 91:0.7333 92:0.85 93:0.85 94:0.85 95:0.85 96:0.85 97:0.85 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:1 118:1 119:0.9 120:0.8833 121:0.8167 122:0.8167 123:0.7667 124:0.75 125:0.7333 126:0.7167 127:0.7 128:0.6833 129:0.6667 130:0.65 131:0.6333 132:0.6333 133:0.6167 134:0.6 135:0.6 136:0.5833 137:0.5667 138:0.5667 139:0.55 140:0.55 141:0.5333 142:0.50873684 143:0.50873684 144:0.49126316 145:0.49126316 146:0.47368421 147:0.47368421 148:0.47368421 149:0.45610526 150:0.45610526 151:0.45610526 152:0.45610526 153:0.42105263 154:0.42105263 155:0.42105263 156:0.42105263 157:0.41071218 158:0.41071218 159:0.41071218 160:0.41071218 161:0.41071218 162:0.41071218 163:0.41071218 164:0.41071218 165:0.39281926 166:0.39281926 167:0.39281926 168:0.39281926 169:0.39281926 170:0.39281926 171:0.39281926 172:0.39281926 173:0.39281926 174:0.39281926 175:0.39281926 176:0.39281926 177:0.39281926 178:0.39281926 179:0.39281926 180:0.39281926 181:0.39281926 182:0.39281926 183:0.39281926 184:0.39281926 185:0.39281926 186:0.39281926 187:0.39281926 188:0.39281926 189:0.39281926 190:0.39281926 191:0.39281926 192:0.39281926 193:0.39281926 194:0.39281926 195:0.39281926 196:0.39281926 197:0.39281926 198:0.41071218 199:0.41071218 200:0.41071218 201:0.41071218 202:0.41071218 203:0.41071218 204:0.41071218 205:0.4286051 206:0.4286051 207:0.4286051 208:0.4286051 209:0.4286051 210:0.44639088 211:0.44639088 212:0.44639088 213:0.44639088 214:0.4642838 215:0.4642838 216:0.4642838 217:0.48217672 218:0.48217672 219:0.4999625 220:0.4999625 221:0.5333 222:0.55 223:0.55 224:0.5667 225:0.5667 226:0.5833 227:0.6 228:0.6 229:0.6167 230:0.6333 231:0.6333 232:0.65 233:0.6667 234:0.6833 235:0.7 236:0.7167 237:0.7333 238:0.75 239:0.7667 240:0.8 241:0.8167 242:0.85 243:0.8667 244:0.9 245:1 246:1 247:1 248:1 249:1 250:1 251:1 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:0.8833 283:0.7167 284:0.7167 285:0.7167 286:0.7167 287:0.5833 288:0.5833 289:0.5833 290:0.5833 291:0.5833 292:0.5833 293:0.5833 294:0.5833 295:0.5833 296:0.6167 297:0.6167 298:0.6167 299:0.6167 300:0.6167 301:0.6333 302:0.6167 303:0.65 304:0.65 305:0.65 306:0.65 307:0.65 308:0.65 309:0.65 310:0.5667 311:0.5667 312:0.55 313:0.5333 314:0.5333 315:0.5167 316:0.5167 317:0.5 318:0.5 319:0.4833 320:0.4833 321:0.4833 322:0.4833 323:0.4833 324:0.4833 325:0.4833 326:0.4833 327:0.4833 328:0.4833 329:0.4833 330:0.5 331:0.5 332:0.5 333:0.5 334:0.5 335:0.5 336:0.5 337:0.5 338:0.5 339:0.4667 340:0.4667 341:0.4667 342:0.4667 343:0.4667 344:0.4667 345:0.4667 346:0.4667 347:0.4667 348:0.4667 349:0.4667 350:0.4667 351:0.4667 352:0.4667 353:0.4667 354:0.4667 355:0.4667 356:0.4667 357:0.4667 358:0.4667 359:0.4667 360:0.45
-0.1302920249306628 1:0.35 2:0.35 3:0.35 4:0.35 5:0.35 6:0.35 7:0.35 8:0.35 9:0.35 10:0.35 11:0.35 12:0.35 13:0.35 14:0.35 15:0.35 16:0.35 17:0.35 18:0.35 19:0.35 20:0.3667 21:0.3667 22:0.3667 23:0.3667 24:0.3667 25:0.3667 26:0.3667 27:0.3667 28:0.3833 29:0.3833 30:0.3833 31:0.3833 32:0.3833 33:0.4 34:0.4 35:0.4 36:0.4 37:0.4167 38:0.4167 39:0.4167 40:0.4333 41:0.4333 42:0.4333 43:0.45 44:0.45 45:0.45 46:0.4667 47:0.4667 48:0.5 49:0.5 50:0.5 51:0.5167 52:0.5333 53:0.5333 54:0.5833 55:0.5833 56:0.6 57:0.5833 58:0.7 59:0.7 60:0.7 61:0.7167 62:0.7333 63:0.7667 64:0.7833 65:0.8667 66:0.8667 67:0.8667 68:0.8667 69:0.9167 70:1 71:1 72:1 73:1 74:1 75:1 76:1 77:1 78:1 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:0.5333 100:0.5333 101:0.5333 102:0.5333 103:0.5333 104:0.5333 105:0.5333 106:0.5333 107:0.5333 108:1 109:1 110:1 111:1 112:1 113:1 114:0.75 115:0.75 116:0.7333 117:0.7 118:0.6833 119:0.65 120:0.6333 121:0.6167 122:0.6167 123:0.6167 124:0.6 125:0.5833 126:0.5667 127:0.55 128:0.55 129:0.55 130:0.5167 131:0.5167 132:0.5 133:0.4833 134:0.4833 135:0.4667 136:0.4667 137:0.45 138:0.45 139:0.45 140:0.4333 141:0.4333 142:0.40347368 143:0.386 144:0.386 145:0.386 146:0.36842105 147:0.36842105 148:0.36842105 149:0.36842105 150:0.35084211 151:0.35084211 152:0.35084211 153:0.35084211 154:0.35084211 155:0.33336842 156:0.33336842 157:0.32146186 158:0.32146186 159:0.32146186 160:0.32146186 161:0.32146186 162:0.32146186 163:0.30356894 164:0.30356894 165:0.30356894 166:0.30356894 167:0.30356894 168:0.30356894 169:0.30356894 170:0.30356894 171:0.30356894 172:0.30356894 173:0.30356894 174:0.30356894 175:0.30356894 176:0.30356894 177:0.30356894 178:0.30356894 179:0.30356894 180:0.30356894 181:0.30356894 182:0.30356894 183:0.30356894 184:0.30356894 185:0.30356894 186:0.30356894 187:0.30356894 188:0.30356894 189:0.30356894 190:0.30356894 191:0.30356894 192:0.30356894 193:0.30356894 194:0.30356894 195:0.30356894 196:0.30356894 197:0.30356894 198:0.30356894 199:0.30356894 200:0.32146186 201:0.32146186 202:0.32146186 203:0.32146186 204:0.32146186 205:0.32146186 206:0.32146186 207:0.32146186 208:0.33924764 209:0.33924764 210:0.33924764 211:0.33924764 212:0.33924764 213:0.35714056 214:0.35714056 215:0.35714056 216:0.35714056 217:0.37503348 218:0.37503348 219:0.37503348 220:0.39281926 221:0.45 222:0.45 223:0.45 224:0.45 225:0.45 226:0.4667 227:0.4667 228:0.4833 229:0.4833 230:0.5 231:0.5167 232:0.5167 233:0.5333 234:0.55 235:0.55 236:0.5667 237:0.5833 238:0.6 239:0.6167 240:0.6333 241:0.65 242:0.6667 243:0.7 244:0.7167 245:0.7333 246:0.7667 247:0.8 248:0.8333 249:0.8667 250:0.9 251:0.95 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:1 285:1 286:1 287:1 288:1 289:0.5667 290:0.5333 291:0.5167 292:0.4833 293:0.4667 294:0.45 295:0.4333 296:0.4167 297:0.4 298:0.4 299:0.4 300:0.3833 301:0.3833 302:0.3667 303:0.3667 304:0.35 305:0.35 306:0.3333 307:0.3333 308:0.3167 309:0.2833 310:0.2833 311:0.2833 312:0.2833 313:0.2833 314:0.3 315:0.2833 316:0.2833 317:0.2833 318:0.3 319:0.2833 320:0.2833 321:0.2833 322:0.2833 323:0.2833 324:0.3 325:0.3 326:0.3 327:0.9667 328:0.9667 329:0.9667 330:0.9833 331:0.95 332:0.95 333:0.95 334:0.95 335:0.8167 336:0.8167 337:0.8167 338:0.8167 339:0.8167 340:0.8167 341:0.4333 342:0.4333 343:0.4333 344:0.4333 345:0.4333 346:0.4333 347:0.4333 348:0.4333 349:0.4333 350:0.4333 351:0.4333 352:0.9167 353:0.9167 354:1 355:0.35 356:0.35 357:0.35 358:0.35 359:0.35 360:0.35
-1.407225774852224 1:0.25 2:0.25 3:0.25 4:0.25 5:0.25 6:0.25 7:0.25 8:0.25 9:0.25 10:0.25 11:0.25 12:0.25 13:0.25 14:0.25 15:0.25 16:0.25 17:0.25 18:0.25 19:0.25 20:0.25 21:0.25 22:0.25 23:0.25 24:0.25 25:0.2667 26:0.2667 27:0.2667 28:0.2667 29:0.2667 30:0.2667 31:0.2833 32:0.2833 33:0.2833 34:0.2833 35:0.2833 36:0.3 37:0.3333 38:0.3333 39:0.3333 40:0.3333 41:0.3333 42:0.3333 43:0.4333 44:0.4333 45:0.4333 46:0.4333 47:0.5333 48:0.5333 49:0.5333 50:0.5667 51:0.5167 52:0.55 53:0.5333 54:0.5333 55:0.55 56:0.55 57:0.55 58:0.55 59:0.55 60:0.5667 61:0.5667 62:0.6 63:0.6 64:0.6 65:0.8167 66:0.03333 67:0.03333 68:0.03333 69:0.03333 70:0.03333 71:0.03333 72:0.05 73:0.05 74:0.05 75:0.05 76:0.05 77:0.05 78:0.05 79:0.05 80:0.05 81:0.05 82:0.05 83:0.05 84:0.05 85:0.05 86:0.05 87:0.05 88:0.05 89:0.05 90:0.05 91:0.05 92:0.05 93:0.05 94:0.05 95:0.05 96:0.05 97:0.05 98:0.05 99:0.05 100:0.05 101:0.05 102:0.05 103:0.05 104:0.05 105:0.05 106:0.05 107:0.05 108:0.05 109:0.05 110:0.05 111:0.05 112:0.05 113:0.05 114:0.05 115:0.05 116:0.05 117:0.05 118:0.05 119:0.05 120:0.05 121:0.05 122:0.05 123:0.05 124:0.05 125:0.05 126:0.05 127:0.05 128:0.05 129:0.05 130:0.05 131:0.05 132:0.05 133:0.03333 134:0.03333 135:0.03333 136:0.03333 137:0.03333 138:0.03333 139:0.05 140:0.05 141:0.05 152:0.087684211 153:0.087684211 154:0.087684211 155:0.087684211 156:0.087684211 157:0.071389541 158:0.071389541 159:0.071389541 160:0.071389541 161:0.071389541 162:0.071389541 163:0.071389541 164:0.071389541 165:0.071389541 166:0.071389541 167:0.071389541 168:0.071389541 169:0.071389541 170:0.071389541 171:0.071389541 172:0.17853278 173:0.17853278 174:0.17853278 175:0.17853278 176:0.17853278 177:0.17853278 178:0.17853278 179:0.17853278 180:0.17853278 181:0.17853278 182:0.17853278 183:0.17853278 184:0.17853278 185:0.17853278 186:0.17853278 187:0.17853278 188:0.17853278 189:0.17853278 190:0.17853278 191:0.17853278 192:0.17853278 193:0.17853278 194:0.17853278 195:0.1964257 196:0.1964257 197:0.1964257 198:0.1964257 199:0.1964257 200:0.1964257 201:0.1964257 202:0.1964257 203:0.1964257 204:0.17853278 205:0.17853278 206:0.17853278 207:0.10717538 208:0.10717538 209:0.10717538 210:0.10717538 211:0.10717538 212:0.10717538 213:0.10717538 214:0.10717538 215:0.10717538 216:0.12496116 217:0.12496116 218:0.10717538 219:0.10717538 220:0.10717538 221:0.1833 222:0.1833 223:0.1667 224:0.1667 225:0.1667 226:0.1833 227:0.1667 228:0.1667 229:0.1667 230:0.1667 231:0.1667 232:0.1833 233:0.1833 234:0.1833 235:0.2167 236:0.2167 237:0.2333 238:0.2333 239:0.2333 240:0.2333 241:0.2333 242:0.2333 243:0.2333 244:0.2333 245:0.4333 246:0.5167 247:0.5167 248:0.5167 249:0.5167 250:0.5167 251:0.5167 252:0.5167 253:0.5167 254:0.5333 255:0.5667 256:0.5667 257:0.5667 258:0.55 259:0.5667 260:0.55 261:0.5667 262:0.5667 263:0.55 264:0.55 265:0.55 266:0.6167 267:0.6167 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:1 282:1 283:1 284:0.9667 285:0.85 286:0.8 287:0.75 288:0.7167 289:0.7 290:0.6833 291:0.65 292:0.6333 293:0.6 294:0.6167 295:0.6167 296:0.6 297:0.4833 298:0.4833 299:0.4833 300:0.4667 301:0.45 302:0.4 303:0.4 304:0.3833 305:0.3667 306:0.3667 307:0.35 308:0.35 309:0.3333 310:0.3333 311:0.3333 312:0.3167 313:0.3167 314:0.3167 315:0.3 316:0.3 317:0.3 318:0.2833 319:0.2833 320:0.2833 321:0.2833 322:0.2833 323:0.2667 324:0.2667 325:0.2833 326:0.2833 327:0.2667 328:0.2833 329:0.2833 330:0.2667 331:0.25 332:0.25 333:0.25 334:0.25 335:0.25 336:0.25 337:0.25 338:0.25 339:0.25 340:0.25 341:0.25 342:0.25 343:0.25 344:0.25 345:0.25 346:0.25 347:0.25 348:0.25 349:0.25 350:0.25 351:0.25 352:0.25 353:0.25 354:0.25 355:0.25 356:0.25 357:0.25 358:0.25 359:0.25 360:0.25
-0.7629019586111927 1:0.3667 2:0.3667 3:0.3667 4:0.3667 5:0.3667 6:0.3667 7:0.3667 8:0.3667 9:0.3667 10:0.3667 11:0.3667 12:0.3667 13:0.3667 14:0.3667 15:0.3667 16:0.3667 17:0.3667 18:0.3667 19:0.35 20:0.3333 21:0.3333 22:0.3333 23:0.3333 24:0.3333 25:0.3333 26:0.3333 27:0.3333 28:0.3333 29:0.3333 30:0.3333 31:0.3333 32:0.3333 33:0.3333 34:0.3333 35:0.3333 36:0.35 37:0.35 38:0.35 39:0.35 40:0.3833 41:0.3833 42:0.4 43:0.4 44:0.4 45:0.4167 46:0.4167 47:0.4333 48:0.4333 49:0.4333 50:0.5333 51:0.5333 52:0.5333 53:0.5333 54:0.6 55:0.6167 56:0.6333 57:0.4833 58:0.4833 59:0.4833 60:0.4833 61:0.4833 62:0.4833 63:0.4833 64:0.4833 65:0.4833 66:0.7 67:0.7 68:0.4333 69:0.4333 70:0.4333 71:0.4333 72:0.4333 73:0.4333 74:0.4333 75:0.4333 76:0.4333 77:0.4333 78:0.4333 79:0.4333 80:0.4833 81:0.4833 82:0.4833 83:0.65 84:0.65 85:0.7333 86:0.9833 87:0.9833 88:0.9833 89:0.9833 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:0.85 108:0.7667 109:0.7667 110:0.7667 111:0.7667 112:0.7667 113:0.7667 114:0.7667 115:0.7667 116:0.7667 117:0.7667 118:0.7167 119:0.7167 120:0.7 121:0.7167 122:0.7167 123:0.7167 124:0.7 125:0.7167 126:0.7167 127:0.7167 128:0.7167 129:1 130:1 131:1 132:1 133:0.5333 134:0.5333 135:0.5333 136:0.5333 137:0.5333 138:0.5333 139:0.5333 140:0.5333 141:0.5333 142:0.52631579 143:0.77189474 144:0.77189474 145:0.77189474 146:0.71926316 147:0.70178947 148:0.71926316 149:0.71926316 150:0.70178947 151:0.70178947 152:0.68421053 153:0.386 154:0.386 155:0.386 156:0.36842105 157:0.37503348 158:0.37503348 159:0.37503348 160:0.37503348 161:0.37503348 162:0.37503348 163:0.37503348 164:0.37503348 165:0.37503348 166:0.37503348 167:0.55353412 168:0.55353412 169:0.55353412 170:0.55353412 171:0.58931996 172:0.58931996 173:0.58931996 174:0.55353412 175:0.55353412 176:0.51785542 177:0.51785542 178:0.51785542 179:0.51785542 180:0.51785542 181:0.51785542 182:0.51785542 183:0.32146186 184:0.32146186 185:0.32146186 186:0.32146186 187:0.32146186 188:0.32146186 189:0.32146186 190:0.32146186 191:0.32146186 192:0.32146186 193:0.32146186 194:0.32146186 195:0.33924764 196:0.33924764 197:0.33924764 198:0.33924764 199:0.48217672 200:0.4999625 201:0.4999625 202:0.57142704 203:0.57142704 204:0.57142704 205:0.57142704 206:0.57142704 207:0.51785542 208:0.51785542 209:0.51785542 210:0.4286051 211:0.4286051 212:0.4286051 213:0.4286051 214:0.4286051 215:0.4286051 216:0.4286051 217:0.4286051 218:0.4286051 219:0.4286051 220:0.4286051 221:0.4667 222:0.7667 223:0.7833 224:0.7833 225:0.7667 226:0.7667 227:0.7833 228:0.6167 229:0.6167 230:0.6 231:0.6167 232:0.6167 233:0.6 234:0.6167 235:0.6167 236:0.65 237:0.6333 238:0.6333 239:0.65 240:0.6667 241:0.6667 242:0.6667 243:0.6667 244:0.6667 245:0.6667 246:0.6833 247:0.75 248:0.7833 249:0.7833 250:0.7833 251:0.7833 252:0.7833 253:0.7833 254:0.8167 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:1 278:1 279:1 280:1 281:0.9 282:0.9 283:0.9 284:0.9 285:0.9 286:0.9 287:0.9 288:0.95 289:0.95 290:0.95 291:0.95 292:0.3 293:0.2833 294:0.2833 295:0.2667 296:0.25 297:0.25 298:0.2333 299:0.2333 300:0.2167 301:0.1833 302:0.1833 303:0.1833 304:0.1833 305:0.1833 306:0.1833 307:0.1833 308:0.1833 309:0.1833 310:0.1833 311:0.1833 312:0.1833 313:0.1833 314:0.1833 315:0.1833 316:0.1833 317:0.1833 318:0.1833 319:0.1833 320:0.1833 321:0.1833 322:0.1833 323:0.1833 324:0.1833 325:0.1833 326:0.1833 327:0.2667 328:0.2667 329:0.2667 330:0.2667 331:0.2667 332:0.2667 333:0.2667 334:0.2667 335:0.2833 336:0.2667 337:0.2667 338:0.3 339:0.3 340:0.3 341:0.3 342:0.3 343:0.3 344:0.3167 345:0.3333 346:0.3333 347:0.3333 348:0.3333 349:0.3333 350:0.3333 351:0.3333 352:0.35 353:0.35 354:0.35 355:0.35 356:0.35 357:0.35 358:0.3667 359:0.3667 360:0.3667
-1.703244380358791 1:0.2667 2:0.2667 3:0.2667 4:0.2667 5:0.2667 6:0.2667 7:0.2667 8:0.2667 9:0.2667 10:0.2667 11:0.2667 12:0.2667 13:0.2667 14:0.2667 15:0.2667 16:0.2667 17:0.2667 18:0.2667 19:0.2667 20:0.2833 21:0.2833 22:0.5833 23:0.2667 24:0.2833 25:0.2667 26:0.25 27:0.25 28:0.25 29:0.25 30:0.25 31:0.25 32:0.25 33:0.2333 34:0.25 35:0.25 36:0.1833 37:0.1833 38:0.2 39:0.2 40:0.2 41:0.2 42:0.2 43:0.2 44:0.2 45:0.2 46:0.2 47:0.2 48:0.2 49:0.2 50:0.2 51:0.2 52:0.2 53:0.2 54:0.2 55:0.1833 56:0.1833 57:0.2 58:0.2 59:0.2 60:0.2167 61:0.2167 62:0.2167 63:0.2333 64:0.2333 65:0.25 66:0.25 67:0.35 68:0.35 69:0.35 70:0.35 71:0.3667 72:0.3833 73:0.4 74:0.4833 75:0.5333 76:0.6 77:0.6 78:0.95 79:1 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:0.95 107:0.9667 108:0.7667 109:0.7667 110:0.75 111:0.7167 112:0.6667 113:0.65 114:0.6333 115:0.6 116:0.5667 117:0.55 118:0.5333 119:0.5167 120:0.5 121:0.4833 122:0.4667 123:0.45 124:0.45 125:0.4333 126:0.4167 127:0.4167 128:0.4 129:0.4 130:0.3833 131:0.3833 132:0.3667 133:0.3667 134:0.3667 135:0.35 136:0.35 137:0.35 138:0.3333 139:0.3333 140:0.3333 141:0.3167 142:0.28073684 143:0.28073684 144:0.28073684 145:0.26315789 146:0.26315789 147:0.26315789 148:0.26315789 149:0.26315789 150:0.26315789 151:0.24557895 152:0.24557895 153:0.24557895 154:0.24557895 155:0.24557895 156:0.24557895 157:0.2321044 158:0.2321044 159:0.21431862 160:0.21431862 161:0.21431862 162:0.21431862 163:0.21431862 164:0.21431862 165:0.21431862 166:0.21431862 167:0.21431862 168:0.21431862 169:0.21431862 170:0.21431862 171:0.21431862 172:0.21431862 173:0.21431862 174:0.21431862 175:0.21431862 176:0.21431862 177:0.21431862 178:0.21431862 179:0.21431862 180:0.21431862 181:0.21431862 182:0.21431862 183:0.21431862 184:0.21431862 185:0.21431862 186:0.21431862 187:0.21431862 188:0.21431862 189:0.21431862 190:0.21431862 191:0.21431862 192:0.21431862 193:0.21431862 194:0.21431862 195:0.21431862 196:0.21431862 197:0.21431862 198:0.21431862 199:0.21431862 200:0.21431862 201:0.21431862 202:0.21431862 203:0.21431862 204:0.21431862 205:0.21431862 206:0.2321044 207:0.21431862 208:0.21431862 209:0.2321044 210:0.2321044 211:0.21431862 212:0.21431862 213:0.24999732 214:0.24999732 215:0.24999732 216:0.24999732 217:0.24999732 218:0.26789024 219:0.26789024 220:0.26789024 221:0.3167 222:0.3333 223:0.3333 224:0.3333 225:0.35 226:0.35 227:0.35 228:0.3667 229:0.3667 230:0.3667 231:0.3833 232:0.3833 233:0.4 234:0.4 235:0.4167 236:0.4167 237:0.4333 238:0.45 239:0.45 240:0.4667 241:0.4667 242:0.4667 243:0.5167 244:0.5333 245:0.55 246:0.5667 247:0.6 248:0.6167 249:0.6333 250:0.6333 251:0.7 252:0.7 253:0.7333 254:0.7667 255:0.8167 256:0.8667 257:0.9333 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:1 277:0.7833 278:0.6333 279:0.5667 280:0.5667 281:0.5667 282:0.4 283:0.35 284:0.3333 285:0.3 286:0.2833 287:0.2667 288:0.25 289:0.2333 290:0.2333 291:0.2167 292:0.2 293:0.2 294:0.1833 295:0.1833 296:0.1833 297:0.1667 298:0.1667 299:0.1667 300:0.15 301:0.15 302:0.15 303:0.1667 304:0.1667 305:0.1667 306:0.15 307:0.15 308:0.1667 309:0.1667 310:0.1667 311:0.15 312:0.15 313:0.15 314:0.15 315:0.15 316:0.15 317:0.15 318:0.15 319:0.15 320:0.15 321:0.15 322:0.15 323:0.15 324:0.15 325:0.15 326:0.15 327:0.15 328:0.15 329:0.15 330:0.15 331:0.15 332:0.15 333:0.15 334:0.15 335:0.15 336:0.15 337:0.15 338:0.15 339:0.2667 340:0.2667 341:0.2667 342:0.2833 343:0.2833 344:0.2833 345:0.2833 346:0.2833 347:0.5167 348:0.5333 349:0.5167 350:0.5333 351:0.5167 352:0.5333 353:0.5333 354:0.5167 355:0.5333 356:0.5333 357:0.5333 358:0.5333 359:0.5167 360:0.2667
-0.461920983197538 1:0.2167 2:0.2167 3:0.2167 4:0.2167 5:0.2167 6:0.2167 7:0.2167 8:0.2167 9:0.2167 10:0.2167 11:0.2167 12:0.2167 13:0.2167 14:0.2167 15:0.2167 16:0.2167 17:0.2167 18:0.2167 19:0.2167 20:0.2167 21:0.2167 22:0.2167 23:0.2167 24:0.2333 25:0.2333 26:0.2333 27:0.2333 28:0.2333 29:0.2333 30:0.2333 31:0.2333 32:0.2333 33:0.2333 34:0.2333 35:0.2333 36:0.25 37:0.25 38:0.25 39:0.25 40:0.25 41:0.25 42:0.2667 43:0.2667 44:0.2667 45:0.2667 46:0.2833 47:0.2833 48:0.2833 49:0.2833 50:0.3 51:0.3 52:0.3 53:0.3167 54:0.3167 55:0.3667 56:0.3667 57:0.3667 58:0.3667 59:0.3667 60:0.3667 61:0.4 62:0.4 63:0.4 64:0.4167 65:0.45 66:0.5167 67:0.5167 68:0.5167 69:0.5167 70:0.5667 71:0.5667 72:0.6 73:0.6667 74:0.7833 75:0.7833 76:0.7833 77:0.7833 78:0.85 79:0.85 80:1 81:1 82:1 83:1 84:1 85:1 86:1 87:1 88:1 89:1 90:1 91:1 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:1 118:1 119:1 120:1 121:1 122:1 123:1 124:1 125:1 126:1 127:1 128:0.5167 129:0.5167 130:0.5167 131:0.5167 132:0.5167 133:0.4667 134:0.45 135:0.45 136:0.4333 137:0.45 138:0.45 139:0.45 140:0.45 141:0.45 142:0.42105263 143:0.42105263 144:0.42105263 145:0.42105263 146:0.42105263 147:0.42105263 148:0.42105263 149:0.42105263 150:0.43863158 151:0.64915789 152:0.64915789 153:0.64915789 154:0.63157895 155:0.63157895 156:0.63157895 157:0.62499866 158:0.60710574 159:0.60710574 160:0.60710574 161:0.60710574 162:0.58931996 163:0.58931996 164:0.58931996 165:0.58931996 166:0.58931996 167:0.58931996 168:0.57142704 169:0.57142704 170:0.57142704 171:0.57142704 172:0.57142704 173:0.55353412 174:0.55353412 175:0.55353412 176:0.55353412 177:0.55353412 178:0.55353412 179:0.55353412 180:0.55353412 181:0.55353412 182:0.53574834 183:0.53574834 184:0.53574834 185:0.53574834 186:0.53574834 187:0.53574834 188:0.53574834 189:0.53574834 190:0.53574834 191:0.53574834 192:0.53574834 193:0.53574834 194:0.53574834 195:0.57142704 196:0.57142704 197:0.57142704 198:0.57142704 199:0.57142704 200:0.57142704 201:0.58931996 202:0.58931996 203:0.58931996 204:0.58931996 205:0.58931996 206:0.60710574 207:0.60710574 208:0.60710574 209:0.60710574 210:0.60710574 211:0.60710574 212:0.64289158 213:0.71424898 214:0.82139222 215:0.82139222 216:0.82139222 217:0.7678206 218:0.75003482 219:0.75003482 220:0.75003482 221:0.7667 222:0.7667 223:0.7667 224:0.7667 225:0.7833 226:0.8 227:0.8167 228:0.8167 229:0.8333 230:0.85 231:0.8667 232:0.8833 233:0.9167 234:0.9333 235:0.9333 236:0.95 237:0.9667 238:1 239:1 240:1 241:1 242:1 243:1 244:1 245:1 246:1 247:1 248:1 249:1 250:1 251:1 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:0.7333 271:0.7333 272:0.7333 273:0.7333 274:0.7333 275:0.7333 276:0.7333 277:0.7333 278:0.7333 279:0.7333 280:1 281:1 282:1 283:1 284:0.9167 285:0.85 286:0.8 287:0.8 288:0.8 289:0.8 290:0.8 291:0.75 292:0.6667 293:0.6833 294:0.6833 295:0.6833 296:0.6833 297:0.6833 298:0.6833 299:0.7333 300:0.4333 301:0.4167 302:0.4 303:0.4 304:0.3833 305:0.3667 306:0.3667 307:0.35 308:0.35 309:0.3333 310:0.3 311:0.3 312:0.3 313:0.2833 314:0.2833 315:0.2833 316:0.2833 317:0.2667 318:0.2667 319:0.2667 320:0.2667 321:0.25 322:0.25 323:0.25 324:0.25 325:0.25 326:0.25 327:0.2333 328:0.2333 329:0.2333 330:0.2333 331:0.2333 332:0.2333 333:0.2333 334:0.2333 335:0.2333 336:0.2333 337:0.2333 338:0.2333 339:0.2167 340:0.2167 341:0.2167 342:0.2167 343:0.2167 344:0.2167 345:0.2167 346:0.2167 347:0.2167 348:0.2167 349:0.2167 350:0.2167 351:0.2167 352:0.2167 353:0.2167 354:0.2167 355:0.2167 356:0.2167 357:0.2167 358:0.2167 359:0.2167 360:0.2167
-1.24390864212422 1:0.65 2:0.6833 3:0.45 4:0.45 5:0.45 6:0.45 7:0.45 8:0.45 9:0.45 10:0.45 11:0.4333 12:0.4167 13:0.4167 14:0.4 15:0.3667 16:0.3667 17:0.3667 18:0.3667 19:0.35 20:0.3333 21:0.3333 22:0.3333 23:0.3333 24:0.3333 25:0.3333 26:0.3333 27:0.3333 28:0.3333 29:0.3333 30:0.3333 31:0.3333 32:0.3333 33:0.3333 34:0.3333 35:0.3333 36:0.35 37:0.35 38:0.35 39:0.35 40:0.3667 41:0.3667 42:0.3667 43:0.3833 44:0.3833 45:0.3833 46:0.4 47:0.4 48:0.4 49:0.4167 50:0.4167 51:0.4333 52:0.4333 53:0.45 54:0.5167 55:0.5167 56:0.5167 57:0.5167 58:0.6 59:0.6 60:0.6 61:0.6 62:0.6 63:0.65 64:1 65:1 66:1 67:1 68:1 69:1 70:0.5333 71:0.5333 72:0.5333 73:0.5333 74:0.5333 75:0.5333 76:0.5333 77:0.5333 78:0.5333 79:0.5333 80:0.5333 81:0.5333 82:0.6 83:0.8667 84:0.8667 85:0.8667 86:0.8667 87:0.8667 88:0.8667 89:0.8667 90:0.8667 91:0.8833 92:1 93:1 94:1 95:1 96:1 97:1 98:1 99:1 100:1 101:1 102:1 103:1 104:1 105:1 106:1 107:1 108:1 109:1 110:1 111:1 112:1 113:1 114:1 115:1 116:1 117:0.9 118:0.8667 119:0.8333 120:0.8 121:0.7833 122:0.7667 123:0.7333 124:0.7167 125:0.7 126:0.6833 127:0.6667 128:0.65 129:0.6667 130:0.65 131:0.6333 132:0.6 133:0.6 134:0.6 135:0.6 136:0.6 137:0.6 138:0.6 139:0.6 140:0.6 141:0.6 142:0.57894737 143:0.80705263 144:0.80705263 145:0.78947368 146:0.78947368 147:0.59652632 148:0.614 149:0.56136842 150:0.56136842 151:0.56136842 152:0.54389474 153:0.54389474 154:0.54389474 155:0.56136842 156:0.54389474 157:0.53574834 158:0.53574834 159:0.53574834 160:0.55353412 161:0.55353412 162:0.55353412 163:0.58931996 164:0.58931996 165:0.60710574 166:0.53574834 167:0.53574834 168:0.53574834 169:0.53574834 170:0.41071218 171:0.41071218 172:0.39281926 173:0.39281926 174:0.39281926 175:0.39281926 176:0.39281926 177:0.39281926 178:0.39281926 179:0.39281926 180:0.39281926 181:0.39281926 182:0.39281926 183:0.39281926 184:0.39281926 185:0.39281926 186:0.39281926 187:0.39281926 188:0.39281926 189:0.39281926 190:0.39281926 191:0.39281926 192:0.39281926 193:0.39281926 194:0.39281926 195:0.39281926 196:0.39281926 197:0.39281926 198:0.41071218 199:0.41071218 200:0.41071218 201:0.41071218 202:0.41071218 203:0.41071218 204:0.41071218 205:0.4286051 206:0.4286051 207:0.4286051 208:0.4286051 209:0.4286051 210:0.44639088 211:0.44639088 212:0.44639088 213:0.44639088 214:0.4999625 215:0.51785542 216:0.51785542 217:0.51785542 218:0.51785542 219:0.37503348 220:0.37503348 221:0.4167 222:0.4167 223:0.4167 224:0.4167 225:0.4167 226:0.4167 227:0.4167 228:0.4167 229:0.4167 230:0.4167 231:0.4333 232:0.4333 233:0.45 234:0.4667 235:0.4667 236:0.75 237:0.7667 238:0.7833 239:0.8 240:0.8333 241:0.85 242:0.8833 243:0.9 244:0.9 245:0.9 246:0.9 247:0.9167 248:1 249:1 250:1 251:1 252:1 253:1 254:1 255:1 256:1 257:1 258:1 259:1 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:1 276:0.9167 277:0.8667 278:0.75 279:0.75 280:0.75 281:0.75 282:0.75 283:0.75 284:0.75 285:1 286:1 287:1 288:1 289:0.8333 290:0.7833 291:0.75 292:0.7333 293:0.7333 294:0.7333 295:0.7333 296:0.7333 297:0.7333 298:0.7333 299:0.5167 300:0.5 301:0.4833 302:0.4667 303:0.4667 304:0.4667 305:0.4667 306:0.45 307:0.45 308:0.4333 309:0.4167 310:0.4167 311:0.4 312:0.4 313:0.3833 314:0.3833 315:0.3833 316:0.3667 317:0.3667 318:0.3667 319:0.3667 320:0.3833 321:0.3667 322:0.3833 323:0.35 324:0.35 325:0.3833 326:0.35 327:0.3667 328:0.3833 329:0.35 330:0.4833 331:0.35 332:0.35 333:0.5 334:0.35 335:0.4833 336:0.4833 337:0.4833 338:0.4833 339:0.6833 340:0.6667 341:0.6667 342:0.6667 343:0.6667 344:0.6667 345:0.6667 346:0.6667 347:0.6667 348:0.6833 349:0.65 350:0.6333 351:0.6333 352:0.6333 353:0.6333 354:0.6333 355:0.6333 356:0.6333 357:0.6333 358:0.65 359:0.65 360:0.65
-0.6755532882257953 1:0.1 2:0.1 3:0.1 4:0.1 5:0.1 6:0.1167 7:0.1167 8:0.1167 9:0.1167 10:0.1167 11:0.1167 12:0.1167 13:0.1167 14:0.1167 15:0.1167 16:0.1167 17:0.1167 18:0.1167 19:0.1167 20:0.1167 21:0.1167 22:0.1167 23:0.1167 24:0.1167 25:0.1167 26:0.1167 27:0.1167 28:0.1167 29:0.1167 30:0.1167 31:0.1167 32:0.1167 33:0.1833 34:0.1833 35:0.1833 36:0.2167 37:0.2167 38:0.1833 39:0.1833 40:0.1833 41:0.2167 42:0.2167 43:0.2167 44:0.2167 45:0.2167 46:0.2167 47:0.2167 48:0.2167 49:0.2167 50:0.2167 51:0.2167 52:0.25 53:0.3167 54:0.3167 55:0.35 56:0.4167 57:0.4333 58:0.5 59:0.8333 60:1 61:1 62:1 63:1 64:1 65:1 66:1 67:1 68:1 69:1 70:1 71:1 72:1 73:1 74:0.55 75:0.55 76:0.55 77:0.55 78:0.55 79:0.55 80:0.55 81:0.55 82:0.5667 83:0.5667 84:1 85:0.2167 86:0.2167 87:0.2167 88:0.2167 89:0.1833 90:0.1833 91:0.1833 92:0.1833 93:0.1833 94:0.15 95:0.1333 96:0.1333 97:0.1333 98:0.1333 99:0.1333 100:0.1333 101:0.1333 102:0.1333 103:0.1167 104:0.1 105:0.1 106:0.1 107:0.1 108:0.1 109:0.1 110:0.1 111:0.1 112:0.1 113:0.1 114:0.1 115:0.1 116:0.1 117:0.1 118:0.08333 119:0.08333 120:0.08333 121:0.08333 122:0.08333 123:0.08333 124:0.08333 125:0.08333 126:0.08333 127:0.08333 128:0.08333 129:0.1 130:0.08333 131:0.08333 132:0.08333 133:0.08333 134:0.08333 135:0.08333 136:0.08333 137:0.08333 138:0.08333 139:0.08333 140:0.08333 141:0.08333 142:0.035084211 143:0.035084211 144:0.035084211 145:0.035084211 146:0.035084211 147:0.035084211 148:0.035084211 149:0.035084211 150:0.035084211 151:0.035084211 152:0.035084211 153:0.035084211 154:0.035084211 155:0.035084211 156:0.035084211 157:0.017850064 158:0.017850064 159:0.017850064 160:0.017850064 161:0.017850064 162:0.017850064 163:0.017850064 164:0.017850064 165:0.017850064 166:0.017850064 167:0.017850064 168:0.017850064 169:0.017850064 170:0.017850064 171:0.017850064 172:0.017850064 173:0.017850064 174:0.017850064 175:0.017850064 176:0.017850064 177:0.017850064 178:0.017850064 179:0.017850064 180:0.017850064 181:0.017850064 182:0.017850064 183:0.017850064 184:0.017850064 185:0.017850064 186:0.017850064 187:0.017850064 188:0.017850064 189:0.017850064 190:0.017850064 191:0.017850064 192:0.017850064 193:0.017850064 194:0.017850064 195:0.017850064 196:0.017850064 197:0.017850064 198:0.017850064 199:0.017850064 200:0.017850064 201:0.017850064 202:0.017850064 203:0.017850064 204:0.035710842 205:0.035710842 206:0.035710842 207:0.035710842 208:0.035710842 209:0.035710842 210:0.035710842 211:0.035710842 212:0.035710842 213:0.035710842 214:0.035710842 215:0.035710842 216:0.035710842 217:0.035710842 218:0.035710842 219:0.035710842 220:0.035710842 221:0.1 222:0.1 223:0.1 224:0.1167 225:0.1167 226:0.1167 227:0.1167 228:0.1167 229:0.1167 230:0.1167 231:0.1167 232:0.1167 233:0.1167 234:0.15 235:0.1667 236:0.1667 237:0.1667 238:0.1667 239:0.1667 240:0.1833 241:0.1833 242:0.1833 243:0.2 244:0.2 245:0.25 246:0.25 247:0.2667 248:0.3 249:0.3 250:0.3 251:0.3167 252:0.3333 253:0.35 254:0.5667 255:0.5667 256:0.5667 257:0.8333 258:0.85 259:0.85 260:0.8833 261:0.8833 262:0.8833 263:0.8833 264:0.8833 265:0.8833 266:0.8833 267:0.9333 268:1 269:1 270:1 271:1 272:1 273:1 274:1 275:0.35 276:0.3 277:0.3 278:0.3 279:0.3 280:0.2667 281:0.2333 282:0.2167 283:0.2 284:0.2 285:0.2 286:0.2 287:0.2 288:0.2 289:0.2 290:0.2 291:0.2 292:0.2 293:0.2 294:0.2 295:0.2 296:0.2 297:0.2 298:0.2 299:0.2 300:0.2 301:0.2 302:0.2 303:0.15 304:0.1333 305:0.1333 306:0.1333 307:0.1333 308:0.1333 309:0.1167 310:0.1167 311:0.1167 312:0.1167 313:0.1167 314:0.1167 315:0.1167 316:0.1167 317:0.1167 318:0.1167 319:0.1 320:0.1 321:0.1 322:0.1 323:0.1 324:0.1 325:0.1 326:0.1 327:0.1 328:0.1 329:0.1 330:0.1 331:0.1 332:0.1 333:0.1 334:0.1 335:0.1 336:0.1 337:0.1 338:0.1 339:0.1 340:0.1 341:0.1 342:0.1 343:0.1 344:0.1 345:0.1 346:0.1 347:0.1 348:0.1 349:0.1 350:0.1 351:0.1 352:0.1 353:0.1 354:0.1 355:0.1 356:0.1 357:0.1 358:0.1 359:0.1 360:0.1
-0.07977645679315452 1:0.1167 2:0.1167 3:0.1167 4:0.1167 5:0.1167 6:0.1167 7:0.1167 8:0.1167 9:0.1167 10:0.1167 11:0.1167 12:0.1167 13:0.1167 14:0.1167 15:0.1167 16:0.1167 17:0.1167 18:0.1167 19:0.1167 20:0.1167 21:0.1167 22:0.1167 23:0.1167 24:0.1167 25:0.1167 26:0.1167 27:0.1167 28:0.1167 29:0.1167 30:0.1167 31:0.1167 32:0.1167 33:0.1167 34:0.1167 35:0.1167 36:0.1167 37:0.1167 38:0.1167 39:0.1167 40:0.1333 41:0.1333 42:0.1333 43:0.1667 44:0.2667 45:0.2667 46:0.1667 47:0.1667 48:0.15 49:0.2167 50:0.2167 51:0.3 52:0.15 53:0.15 54:0.15 55:0.3167 56:0.3167 57:0.2167 58:0.2167 59:0.3333 60:0.3333 61:0.2167 62:0.2167 63:0.3667 64:0.2167 65:0.2167 66:0.2167 67:0.2167 68:0.4167 69:0.4167 70:0.4833 71:0.4833 72:0.4833 73:0.55 74:0.55 75:0.6167 76:0.6167 77:0.6 78:0.6 79:0.6 80:0.6 81:0.6 82:0.6 83:0.6 84:0.6 85:0.6 86:0.6167 87:0.6167 88:0.6167 89:0.6167 90:0.2833 91:0.2833 92:0.2833 93:0.2833 94:0.2833 95:0.2833 96:0.2833 97:0.2833 98:0.2833 99:0.2833 100:0.2833 101:0.2833 102:0.2833 103:0.2833 104:0.2833 105:0.2833 106:0.2833 107:0.2833 108:0.2833 109:0.2833 110:0.2833 111:0.2833 112:0.2833 113:0.2833 114:0.2833 115:0.2833 116:0.2833 117:0.1667 118:0.1667 119:0.1667 120:0.1667 121:0.1667 122:0.1667 123:0.1667 124:0.1667 125:0.1667 126:0.1833 127:0.1833 128:0.1667 129:0.1667 130:0.1667 131:0.1833 132:0.1833 133:0.1667 134:0.1667 135:0.1667 136:0.1833 137:0.1667 138:0.1667 139:0.1 140:0.1 141:0.1 142:0.052631579 143:0.052631579 144:0.052631579 145:0.052631579 146:0.052631579 147:0.052631579 148:0.052631579 149:0.052631579 150:0.052631579 151:0.052631579 152:0.052631579 153:0.052631579 154:0.052631579 155:0.052631579 156:0.052631579 157:0.035710842 158:0.035710842 159:0.035710842 160:0.035710842 161:0.035710842 162:0.035710842 163:0.035710842 164:0.035710842 165:0.035710842 166:0.035710842 167:0.035710842 168:0.035710842 169:0.035710842 170:0.035710842 171:0.035710842 172:0.035710842 173:0.035710842 174:0.035710842 175:0.035710842 176:0.035710842 177:0.035710842 178:0.035710842 179:0.035710842 180:0.035710842 181:0.035710842 182:0.035710842 183:0.035710842 184:0.035710842 185:0.035710842 186:0.035710842 187:0.035710842 188:0.035710842 189:0.035710842 190:0.035710842 191:0.035710842 192:0.035710842 193:0.035710842 194:0.035710842 195:0.035710842 196:0.035710842 197:0.035710842 198:0.035710842 199:0.035710842 200:0.035710842 201:0.035710842 202:0.035710842 203:0.035710842 204:0.035710842 205:0.035710842 206:0.035710842 207:0.035710842 208:0.035710842 209:0.035710842 210:0.035710842 211:0.035710842 212:0.035710842 213:0.035710842 214:0.035710842 215:0.035710842 216:0.035710842 217:0.035710842 218:0.035710842 219:0.035710842 220:0.035710842 221:0.1 222:0.1 223:0.1 224:0.1167 225:0.1167 226:0.1167 227:0.1167 228:0.1167 229:0.1333 230:0.15 231:0.15 232:0.15 233:0.15 234:0.15 235:0.1667 236:0.1667 237:0.1667 238:0.1667 239:0.1667 240:0.1667 241:0.1667 242:0.1667 243:0.1667 244:0.1667 245:0.1667 246:0.1667 247:0.1667 248:0.1667 249:0.15 250:0.1667 251:0.1667 252:0.1833 253:0.1833 254:0.2 255:0.2 256:0.2167 257:0.2333 258:0.25 259:0.2833 260:0.5333 261:0.5167 262:0.5333 263:0.3667 264:0.3667 265:0.3667 266:0.3667 267:0.3667 268:0.3667 269:0.3667 270:0.3667 271:0.3667 272:0.3667 273:0.3667 274:0.3667 275:1 276:1 277:0.8667 278:0.7833 279:0.7833 280:0.7833 281:0.7833 282:0.7833 283:0.7833 284:0.85 285:0.7833 286:0.6667 287:0.3333 288:0.35 289:0.6667 290:0.3333 291:0.35 292:0.3333 293:0.35 294:0.2333 295:0.2167 296:0.2167 297:0.2167 298:0.2 299:0.2 300:0.2167 301:0.1833 302:0.1833 303:0.1667 304:0.1667 305:0.1667 306:0.1667 307:0.1667 308:0.15 309:0.15 310:0.15 311:0.15 312:0.15 313:0.15 314:0.15 315:0.15 316:0.15 317:0.15 318:0.15 319:0.15 320:0.1333 321:0.1333 322:0.1333 323:0.1333 324:0.1333 325:0.1333 326:0.1333 327:0.1333 328:0.1333 329:0.1333 330:0.1333 331:0.1333 332:0.1333 333:0.1333 334:0.1333 335:0.1333 336:0.1333 337:0.1167 338:0.1167 339:0.1167 340:0.1167 341:0.1167 342:0.1167 343:0.1167 344:0.1167 345:0.1167 346:0.1167 347:0.1167 348:0.1167 349:0.1167 350:0.1167 351:0.1167 352:0.1167 353:0.1167 354:0.1167 355:0.1167 356:0.1167 357:0.1167 358:0.1167 359:0.1167 360:0.1167
-0.4149747376290368 1:0.1667 2:0.1667 3:0.1667 4:0.1667 5:0.1667 6:0.1667 7:0.1667 8:0.1667 9:0.1667 10:0.1667 11:0.1667 12:0.1667 13:0.1667 14:0.1667 15:0.1667 16:0.1667 17:0.1667 18:0.1667 19:0.1667 20:0.1667 21:0.1667 22:0.1667 23:0.1667 24:0.1667 25:0.1667 26:0.1667 27:0.1667 28:0.1667 29:0.1667 30:0.1667 31:0.1667 32:0.1833 33:0.1833 34:0.1833 35:0.1833 36:0.1833 37:0.1833 38:0.1833 39:0.1833 40:0.1833 41:0.1667 42:0.1667 43:0.1667 44:0.1833 45:0.1833 46:0.1833 47:0.1833 48:0.1833 49:0.1833 50:0.2 51:0.2 52:0.2 53:0.2 54:0.2167 55:0.2167 56:0.2167 57:0.2333 58:0.2333 59:0.2333 60:0.25 61:0.25 62:0.25 63:0.2667 64:0.2833 65:0.2833 66:0.3 67:0.3 68:0.3167 69:0.4833 70:0.4833 71:0.4833 72:0.4833 73:0.4833 74:0.4833 75:0.5 76:0.5 77:0.5833 78:0.65 79:0.75 80:0.75 81:1 82:1 83:1 84:1 85:0.6833 86:0.6833 87:0.6833 88:0.6833 89:0.6833 90:0.6833 91:0.6833 92:0.6833 93:0.6833 94:0.6833 95:0.6833 96:0.7 97:0.7 98:0.6167 99:0.55 100:0.55 101:0.5167 102:0.4833 103:0.4333 104:0.4 105:0.3667 106:0.3667 107:0.3667 108:0.3167 109:0.3 110:0.3 111:0.3 112:0.3 113:0.2833 114:0.2833 115:0.2667 116:0.25 117:0.25 118:0.2333 119:0.2333 120:0.2333 121:0.2333 122:0.2333 123:0.2 124:0.2 125:0.2 126:0.1833 127:0.1833 128:0.1833 129:0.1833 130:0.1833 131:0.1833 132:0.1833 133:0.1833 134:0.1833 135:0.1833 136:0.1833 137:0.1833 138:0.1833 139:0.1667 140:0.1667 141:0.1667 142:0.12284211 143:0.12284211 144:0.12284211 145:0.12284211 146:0.12284211 147:0.12284211 148:0.12284211 149:0.10526316 150:0.10526316 151:0.10526316 152:0.10526316 153:0.10526316 154:0.10526316 155:0.10526316 156:0.10526316 157:0.089282462 158:0.089282462 159:0.089282462 160:0.089282462 161:0.089282462 162:0.089282462 163:0.089282462 164:0.089282462 165:0.089282462 166:0.089282462 167:0.089282462 168:0.089282462 169:0.089282462 170:0.089282462 171:0.089282462 172:0.089282462 173:0.089282462 174:0.089282462 175:0.089282462 176:0.089282462 177:0.089282462 178:0.089282462 179:0.089282462 180:0.089282462 181:0.089282462 182:0.089282462 183:0.089282462 184:0.089282462 185:0.089282462 186:0.089282462 187:0.089282462 188:0.089282462 189:0.089282462 190:0.089282462 191:0.089282462 192:0.089282462 193:0.089282462 194:0.089282462 195:0.089282462 196:0.089282462 197:0.089282462 198:0.089282462 199:0.089282462 200:0.089282462 201:0.089282462 202:0.089282462 203:0.089282462 204:0.089282462 205:0.089282462 206:0.089282462 207:0.089282462 208:0.089282462 209:0.089282462 210:0.089282462 211:0.089282462 212:0.089282462 213:0.089282462 214:0.10717538 215:0.10717538 216:0.10717538 217:0.10717538 218:0.10717538 219:0.10717538 220:0.10717538 221:0.1667 222:0.1667 223:0.1667 224:0.1833 225:0.1833 226:0.1833 227:0.1833 228:0.1833 229:0.2167 230:0.2167 231:0.2167 232:0.2333 233:0.2333 234:0.2333 235:0.45 236:0.6333 237:0.6333 238:0.6333 239:0.6333 240:0.6333 241:0.7167 242:0.7667 243:0.8 244:0.8333 245:0.5833 246:0.5667 247:0.5667 248:0.5667 249:0.5667 250:0.5667 251:0.5667 252:0.5667 253:0.5667 254:0.5667 255:0.5667 256:0.6667 257:0.7167 258:0.7667 259:0.9167 260:1 261:1 262:1 263:1 264:1 265:1 266:1 267:1 268:1 269:1 270:1 271:1 272:1 273:0.7167 274:0.6667 275:0.6667 276:0.6667 277:0.6667 278:0.6667 279:0.3 280:0.2833 281:0.2833 282:0.2833 283:0.2833 284:0.1833 285:0.1667 286:0.15 287:0.15 288:0.15 289:0.15 290:0.15 291:0.15 292:0.15 293:0.15 294:0.15 295:0.15 296:0.15 297:0.15 298:0.15 299:0.15 300:0.15 301:0.15 302:0.15 303:0.1667 304:0.15 305:0.15 306:0.15 307:0.15 308:0.15 309:0.15 310:0.15 311:0.15 312:0.15 313:0.15 314:0.15 315:0.15 316:0.1667 317:0.1833 318:0.1833 319:0.2 320:0.2 321:0.2 322:0.1833 323:0.1833 324:0.1833 325:0.1833 326:0.1833 327:0.1833 328:0.1833 329:0.1833 330:0.1833 331:0.1667 332:0.1667 333:0.1667 334:0.1667 335:0.1667 336:0.1667 337:0.1667 338:0.1667 339:0.1667 340:0.1667 341:0.1667 342:0.1667 343:0.1667 344:0.1667 345:0.1667 346:0.1667 347:0.1667 348:0.1667 349:0.1667 350:0.1667 351:0.1667 352:0.1667 353:0.1667 354:0.1667 355:0.1667 356:0.1667 357:0.1667 358:0.1667 359:0.1667 360:0.1667

@ -0,0 +1,136 @@
/**
* @file
* @brief Representation of a 3D point
* @author Kai Lingemann. Institute of Computer Science, University of Osnabrueck, Germany.
* @author Andreas Nuechter. Institute of Computer Science, University of Osnabrueck, Germany.
*/
#ifndef __POINT_H__
#define __POINT_H__
#include <cmath>
#include <iostream>
using std::ostream;
using std::istream;
#include <stdexcept>
using std::runtime_error;
/**
* @brief Representation of a point in 3D space
*/
class Point {
public:
/**
* Default constructor
*/
inline Point() { x = y = z = 0.0; point_id = 0; type = 0; reflectance = 0.0; amplitude = 0.0; deviation = 0.0; rgb[0] = 255; rgb[1] = 255; rgb[2] = 255;};
/**
* Copy constructor
*/
inline Point(const Point& p) { x = p.x; y = p.y; z = p.z; type = p.type; point_id = p.point_id;
reflectance = p.reflectance; amplitude = p.amplitude; deviation = p.deviation; rgb[0] = p.rgb[0]; rgb[1] = p.rgb[1]; rgb[2] = p.rgb[2];};
/**
* Constructor with an array, i.e., vecctor of coordinates
*/
inline Point(const double *p) { x = p[0]; y = p[1]; z = p[2]; type = 0; reflectance = 0.0; amplitude = 0.0; deviation = 0.0;
rgb[0] = 255; rgb[1] = 255; rgb[2] = 255;};
inline Point(const double *p, const char *c) { x = p[0]; y = p[1]; z = p[2]; rgb[0] = c[0]; rgb[1] = c[1]; rgb[2] = c[2];};
/**
* Constructor with three double values
*/
inline Point(const double _x, const double _y, const double _z) { x = _x; y = _y; z = _z; };
inline Point(const double _x, const double _y, const double _z, const char _r, const char _g, const char _b) { x = _x; y = _y; z = _z; rgb[0] = _r; rgb[1] = _g; rgb[2] = _b;};
static inline Point cross(const Point &X, const Point &Y) {
Point res;
res.x = X.y * Y.z - X.z * Y.y;
res.y = X.z * Y.x - X.x * Y.z;
res.z = X.x * Y.y - X.y * Y.x;
return res;
};
static inline Point norm(const Point &p) {
double l = sqrt(p.x*p.x + p.y*p.y + p.z*p.z);
Point res(p.x/l, p.y/l, p.z/l);
return res;
};
inline Point operator+(const Point &p) const {
Point res;
res.x = x + p.x;
res.y = y + p.y;
res.z = z + p.z;
return res;
};
inline Point operator-(const Point &p) const {
Point res;
res.x = x - p.x;
res.y = y - p.y;
res.z = z - p.z;
return res;
};
inline Point& operator-=(const Point &p) {
x -= p.x;
y -= p.y;
z -= p.z;
return *this;
};
inline Point& operator+=(const Point &p) {
x += p.x;
y += p.y;
z += p.z;
return *this;
};
inline void transform(const double alignxf[16]);
inline double distance(const Point& p);
inline friend ostream& operator<<(ostream& os, const Point& p);
inline friend istream& operator>>(istream& is, Point& p);
// also public; set/get functions not necessary here
/// x coordinate in 3D space
double x;
/// y coordinate in 3D space
double y;
/// z coordinate in 3D space
double z;
/// additional information about the point, e.g., semantic
/// also used in veloscan for distiuguish moving or static
int type;
/////////////////////////for veloslam/////////////////////////////
double rad;
/// tang in cylindrical coordinates for veloscan
double tan_theta;
// point id in points for veloscan , you can use it find point.
long point_id;
/////////////////////////for veloslam/////////////////////////////
// color information of the point between 0 and 255
// rgb
unsigned char rgb[3];
float reflectance;
float amplitude;
float deviation;
};
inline Point operator*(const double &v, const Point &p) {
Point res;
res.x = v * p.x;
res.y = v * p.y;
res.z = v * p.z;
return res;
}
#include "point.icc"
#endif

@ -0,0 +1,302 @@
<?xml version="1.0" encoding="Windows-1252"?>
<VisualStudioProject
ProjectType="Visual C++"
Version="8.00"
Name="test"
ProjectGUID="{6AC673C7-7B3F-4520-A761-647B212A4BEF}"
Keyword="MFCProj"
>
<Platforms>
<Platform
Name="Win32"
/>
</Platforms>
<ToolFiles>
</ToolFiles>
<Configurations>
<Configuration
Name="Release|Win32"
OutputDirectory=".\Release"
IntermediateDirectory=".\Release"
ConfigurationType="1"
InheritedPropertySheets="$(VCInstallDir)VCProjectDefaults\UpgradeFromVC71.vsprops"
UseOfMFC="2"
ATLMinimizesCRunTimeLibraryUsage="false"
CharacterSet="2"
>
<Tool
Name="VCPreBuildEventTool"
/>
<Tool
Name="VCCustomBuildTool"
/>
<Tool
Name="VCXMLDataGeneratorTool"
/>
<Tool
Name="VCWebServiceProxyGeneratorTool"
/>
<Tool
Name="VCMIDLTool"
TypeLibraryName=".\Release/test.tlb"
HeaderFileName=""
/>
<Tool
Name="VCCLCompilerTool"
Optimization="2"
InlineFunctionExpansion="1"
AdditionalIncludeDirectories="..\..\include"
PreprocessorDefinitions="NDEBUG;PREP;WIN32;_CONSOLE;ANN_NO_RANDOM"
StringPooling="true"
RuntimeLibrary="2"
EnableFunctionLevelLinking="true"
UsePrecompiledHeader="0"
PrecompiledHeaderThrough="stdafx.h"
PrecompiledHeaderFile=".\Release/test.pch"
AssemblerListingLocation=".\Release/"
ObjectFile=".\Release/"
ProgramDataBaseFileName=".\Release/"
WarningLevel="3"
SuppressStartupBanner="true"
/>
<Tool
Name="VCManagedResourceCompilerTool"
/>
<Tool
Name="VCResourceCompilerTool"
PreprocessorDefinitions="NDEBUG"
Culture="3081"
/>
<Tool
Name="VCPreLinkEventTool"
/>
<Tool
Name="VCLinkerTool"
AdditionalDependencies="kernel32.lib user32.lib gdi32.lib winspool.lib comdlg32.lib advapi32.lib shell32.lib ole32.lib oleaut32.lib uuid.lib odbc32.lib odbccp32.lib"
OutputFile="..\bin\ann_test.exe"
LinkIncremental="1"
SuppressStartupBanner="true"
ProgramDatabaseFile=".\Release/test.pdb"
SubSystem="1"
TargetMachine="1"
/>
<Tool
Name="VCALinkTool"
/>
<Tool
Name="VCManifestTool"
/>
<Tool
Name="VCXDCMakeTool"
/>
<Tool
Name="VCBscMakeTool"
/>
<Tool
Name="VCFxCopTool"
/>
<Tool
Name="VCAppVerifierTool"
/>
<Tool
Name="VCWebDeploymentTool"
/>
<Tool
Name="VCPostBuildEventTool"
/>
</Configuration>
<Configuration
Name="Debug|Win32"
OutputDirectory=".\Debug"
IntermediateDirectory=".\Debug"
ConfigurationType="1"
InheritedPropertySheets="$(VCInstallDir)VCProjectDefaults\UpgradeFromVC71.vsprops"
UseOfMFC="2"
ATLMinimizesCRunTimeLibraryUsage="false"
CharacterSet="2"
>
<Tool
Name="VCPreBuildEventTool"
/>
<Tool
Name="VCCustomBuildTool"
/>
<Tool
Name="VCXMLDataGeneratorTool"
/>
<Tool
Name="VCWebServiceProxyGeneratorTool"
/>
<Tool
Name="VCMIDLTool"
TypeLibraryName=".\Debug/test.tlb"
HeaderFileName=""
/>
<Tool
Name="VCCLCompilerTool"
Optimization="0"
AdditionalIncludeDirectories="..\..\include"
PreprocessorDefinitions="_DEBUG;WIN32;_CONSOLE;ANN_NO_RANDOM;ANN_PERF"
BasicRuntimeChecks="3"
RuntimeLibrary="3"
UsePrecompiledHeader="0"
PrecompiledHeaderThrough="stdafx.h"
PrecompiledHeaderFile=".\Debug/test.pch"
AssemblerListingLocation=".\Debug/"
ObjectFile=".\Debug/"
ProgramDataBaseFileName=".\Debug/"
WarningLevel="3"
SuppressStartupBanner="true"
DebugInformationFormat="4"
CompileAs="0"
/>
<Tool
Name="VCManagedResourceCompilerTool"
/>
<Tool
Name="VCResourceCompilerTool"
PreprocessorDefinitions="_DEBUG"
Culture="3081"
/>
<Tool
Name="VCPreLinkEventTool"
/>
<Tool
Name="VCLinkerTool"
AdditionalDependencies="kernel32.lib user32.lib gdi32.lib winspool.lib comdlg32.lib advapi32.lib shell32.lib ole32.lib oleaut32.lib uuid.lib odbc32.lib odbccp32.lib"
OutputFile="..\bin\ann_test.exe"
LinkIncremental="2"
SuppressStartupBanner="true"
GenerateDebugInformation="true"
ProgramDatabaseFile=".\Debug/test.pdb"
SubSystem="1"
TargetMachine="1"
/>
<Tool
Name="VCALinkTool"
/>
<Tool
Name="VCManifestTool"
/>
<Tool
Name="VCXDCMakeTool"
/>
<Tool
Name="VCBscMakeTool"
/>
<Tool
Name="VCFxCopTool"
/>
<Tool
Name="VCAppVerifierTool"
/>
<Tool
Name="VCWebDeploymentTool"
/>
<Tool
Name="VCPostBuildEventTool"
/>
</Configuration>
</Configurations>
<References>
</References>
<Files>
<Filter
Name="Source Files"
Filter="cpp;c;cxx;rc;def;r;odl;idl;hpj;bat"
>
<File
RelativePath="..\..\test\ann_test.cpp"
>
<FileConfiguration
Name="Release|Win32"
>
<Tool
Name="VCCLCompilerTool"
Optimization="2"
PreprocessorDefinitions=""
UsePrecompiledHeader="0"
/>
</FileConfiguration>
<FileConfiguration
Name="Debug|Win32"
>
<Tool
Name="VCCLCompilerTool"
Optimization="0"
AdditionalIncludeDirectories=""
PreprocessorDefinitions=""
BasicRuntimeChecks="3"
UsePrecompiledHeader="0"
/>
</FileConfiguration>
</File>
<File
RelativePath="..\..\test\rand.cpp"
>
<FileConfiguration
Name="Release|Win32"
>
<Tool
Name="VCCLCompilerTool"
Optimization="2"
PreprocessorDefinitions=""
UsePrecompiledHeader="0"
/>
</FileConfiguration>
<FileConfiguration
Name="Debug|Win32"
>
<Tool
Name="VCCLCompilerTool"
Optimization="0"
AdditionalIncludeDirectories=""
PreprocessorDefinitions=""
BasicRuntimeChecks="3"
UsePrecompiledHeader="0"
/>
</FileConfiguration>
</File>
</Filter>
<Filter
Name="Header Files"
Filter="h;hpp;hxx;hm;inl"
>
<File
RelativePath="..\..\test\rand.h"
>
</File>
</Filter>
<Filter
Name="Test Data"
>
<File
RelativePath="test1.data"
>
</File>
<File
RelativePath="test1.in"
>
</File>
<File
RelativePath="test1.query"
>
</File>
<File
RelativePath="test2.in"
>
</File>
</Filter>
<Filter
Name="Resource Files"
Filter="ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe"
>
</Filter>
<File
RelativePath="ReadMe.txt"
>
</File>
</Files>
<Globals>
</Globals>
</VisualStudioProject>

@ -0,0 +1,429 @@
cmake_minimum_required (VERSION 2.6.1)
SET(CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/3rdparty/CMakeModules" ${CMAKE_MODULE_PATH})
project (Slam6D)
#include_directories(OPENGL_INCLUDE_DIR)
IF(WIN32)
set(Boost_USE_STATIC_LIBS TRUE)
ELSE(WIN32)
set(Boost_USE_STATIC_LIBS FALSE)
ENDIF(WIN32)
SET(Boost_ADDITIONAL_VERSIONS "1.42" "1.42.0" "1.44" "1.44.0" "1.45.0" "1.45" "1.46" "1.46.1" "1.47.0" "1.47" "1.48" "1.49")
IF(WIN32)
# for some unknown reason no one variant works on all windows platforms
find_package( Boost COMPONENTS serialization graph regex filesystem system thread date_time REQUIRED)
ELSE(WIN32)
find_package( Boost COMPONENTS serialization graph regex filesystem system thread date_time REQUIRED)
ENDIF(WIN32)
if(Boost_FOUND)
link_directories(${BOOST_LIBRARY_DIRS})
include_directories(${Boost_INCLUDE_DIRS})
add_definitions(${Boost_LIB_DIAGNOSTIC_DEFINITIONS})
endif()
#################################################
# Declare Options and modify build accordingly ##
#################################################
## FreeGLUT
OPTION(WITH_FREEGLUT "Whether freeglut is available. This enables iterative drawing in show. ON/OFF" ON)
IF(WITH_FREEGLUT)
MESSAGE(STATUS "With freeglut")
SET (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DWITH_FREEGLUT")
ELSE(WITH_FREEGLUT)
MESSAGE(STATUS "Without freeglut")
ENDIF(WITH_FREEGLUT)
## Show
OPTION(WITH_SHOW "Whether to build Show. This is the Visualization program of slam6d. ON/OFF" ON)
IF(WITH_SHOW)
FIND_PACKAGE(OpenGL REQUIRED)
FIND_PACKAGE(GLUT REQUIRED)
MESSAGE(STATUS "With show")
ELSE(WITH_SHOW)
# SET (WITH_OCTREE_DISPLAY "ON" CACHE INTERNAL "" FORCE)
MESSAGE(STATUS "Without show")
ENDIF(WITH_SHOW)
## WXShow
OPTION(WITH_WXSHOW "Whether to build WXShow. This is the wxwidgets variant of Show. ON/OFF" OFF)
IF(WITH_WXSHOW)
FIND_PACKAGE(OpenGL REQUIRED)
FIND_PACKAGE(GLUT REQUIRED)
find_package(wxWidgets COMPONENTS core base gl REQUIRED)
# set wxWidgets_wxrc_EXECUTABLE to be ignored in the configuration
SET (wxWidgets_wxrc_EXECUTABLE " " CACHE INTERNAL "" FORCE)
# wxWidgets include (this will do all the magic to configure everything)
include( ${wxWidgets_USE_FILE})
MESSAGE(STATUS "With wxshow")
ELSE(WITH_XWSHOW)
MESSAGE(STATUS "Without wxshow")
ENDIF(WITH_WXSHOW)
## Shapes
OPTION(WITH_SHAPE_DETECTION "Whether to build shapes and planes executable for detecting planes. ON/OFF" OFF)
IF(WITH_SHAPE_DETECTION)
MESSAGE(STATUS "With shape detection")
ELSE(WITH_SHAPE_DETECTION)
MESSAGE(STATUS "Without shape detection")
ENDIF(WITH_SHAPE_DETECTION)
## Interior reconstruction
option(WITH_MODEL "Whether to build model executable for modelling interior environments. ON/OFF" OFF)
if(WITH_MODEL)
message(STATUS "With interior reconstruction")
else(WITH_MODEL)
message(STATUS "Without interior reconstruction")
endif(WITH_MODEL)
## Thermo
OPTION(WITH_THERMO "Whether to build executables for mutual calibration of laser scanner and camera. ON/OFF" OFF)
IF(WITH_THERMO)
FIND_PACKAGE(OpenCV REQUIRED)
add_subdirectory(3rdparty/cvblob)
include_directories(${CMAKE_SOURCE_DIR}/3rdparty/cvblob)
link_directories(${CMAKE_SOURCE_DIR}/3rdparty/cvblob)
MESSAGE(STATUS "With thermo")
ELSE(WITH_THERMO)
MESSAGE(STATUS "Without thermo")
ENDIF(WITH_THERMO)
## Octree
OPTION(WITH_OCTREE_DISPLAY "Whether to use octree display for efficiently culling scans ON/OFF" ON)
IF(WITH_OCTREE_DISPLAY)
MESSAGE(STATUS "Using octree display")
SET (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DUSE_GL_POINTS")
ELSE(WITH_OCTREE_DISPLAY)
MESSAGE(STATUS "Using displaylists: Warning potentially much slower")
ENDIF(WITH_OCTREE_DISPLAY)
#SET (WITH_OCTREE_DISPLAY ${WITH_OCTREE_DISPLAY} CACHE BOOL
#"Whether to use octree display for efficiently culling scans ON/OFF" FORCE)
## Octree
OPTION(WITH_COMPACT_OCTREE "Whether to use the compact octree display ON/OFF" OFF)
IF(WITH_COMPACT_OCTREE)
MESSAGE(STATUS "Using compact octrees")
SET (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DUSE_COMPACT_TREE")
ELSE(WITH_COMPACT_OCTREE)
MESSAGE(STATUS "Not using compact octreees: Warning uses more memory")
ENDIF(WITH_COMPACT_OCTREE)
## Glee?
OPTION(WITH_GLEE "Whether to use OpenGL extensions, requires glee. ON/OFF" OFF)
IF(WITH_GLEE)
MESSAGE(STATUS "Using opengl extensions")
SET (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DWITH_GLEE")
ELSE(WITH_GLEE)
MESSAGE(STATUS "Not using opengl extensions")
ENDIF(WITH_GLEE)
## Gridder
OPTION(WITH_GRIDDER "Whether to build the 2DGridder binary ON/OFF" OFF)
IF(WITH_GRIDDER)
MESSAGE(STATUS "With 2DGridder")
ELSE(WITH_GRIDDER)
MESSAGE(STATUS "Without 2DGridder")
ENDIF(WITH_GRIDDER)
## Dynamic VELOSLAM
OPTION(WITH_VELOSLAM "Whether to build the Velodyne data processing (veloslam/veloshow) ON/OFF" OFF)
IF(WITH_VELOSLAM)
MESSAGE(STATUS "With VELOSLAM")
ELSE(WITH_VELOSLAM)
MESSAGE(STATUS "Without VELOSLAM")
ENDIF(WITH_VELOSLAM)
## Home-made Laserscanner
OPTION(WITH_DAVID_3D_SCANNER "Whether to build the David scanner app for homemade laser scanners binary ON/OFF" OFF)
IF(WITH_DAVID_3D_SCANNER)
MESSAGE(STATUS "With David scanner")
ELSE(WITH_DAVID_3D_SCANNER)
MESSAGE(STATUS "Without David scanner")
ENDIF(WITH_DAVID_3D_SCANNER)
## Tools
OPTION(WITH_TOOLS "Whether to build additional tools like convergence frame_to_graph etc. ON/OFF" OFF)
IF(WITH_TOOLS)
MESSAGE(STATUS "With Tools")
ELSE(WITH_TOOLS)
MESSAGE(STATUS "Without Tools")
ENDIF(WITH_TOOLS)
## Scan reduction
OPTION(WITH_SCAN_REDUCTION "Whether to build the scan reduction binary scan_red ON/OFF" OFF)
IF(WITH_SCAN_REDUCTION)
MESSAGE(STATUS "With scan_red")
ELSE(WITH_SCAN_REDUCTION)
MESSAGE(STATUS "Without scan_red")
ENDIF(WITH_SCAN_REDUCTION)
## Scan difference
OPTION(WITH_SCAN_DIFF "Whether to build the scan_diff binary ON/OFF" OFF)
IF(WITH_SCAN_DIFF)
MESSAGE(STATUS "With scan_diff")
ELSE(WITH_SCAN_DIFF)
MESSAGE(STATUS "Without scan_diff")
ENDIF(WITH_SCAN_DIFF)
## CAD matching
OPTION (WITH_CAD "Wether to build with CAD import lib ON/OFF" OFF)
IF (WITH_CAD)
MESSAGE (STATUS "With CAD import")
find_package (Boost COMPONENTS program_options filesystem REQUIRED)
ELSE (WITH_CAD)
MESSAGE (STATUS "Without CAD import")
ENDIF (WITH_CAD)
## RivLib
OPTION(WITH_RIVLIB "Whether the RIEGL rivlib is present ON/OFF" OFF)
IF(WITH_RIVLIB)
MESSAGE(STATUS "Compiling a scan IO for RXP files")
include_directories(${CMAKE_SOURCE_DIR}/3rdparty)
link_directories(${CMAKE_SOURCE_DIR}/3rdparty)
SET(RIEGL_DIR ${CMAKE_SOURCE_DIR}/3rdparty/riegl/)
IF(WIN32)
SET(RIVLIB ${RIEGL_DIR}libscanlib-mt.lib ${RIEGL_DIR}libctrllib-mt.lib ${RIEGL_DIR}libboost_system-mt-1_43_0-vns.lib)
ELSE(WIN32)
SET(RIVLIB ${RIEGL_DIR}libscanlib-mt-s.a ${RIEGL_DIR}libctrllib-mt-s.a ${RIEGL_DIR}libboost_system-mt-s-1_43_0-vns.a pthread)
ENDIF(WIN32)
FIND_PACKAGE(LibXml2 )
ELSE(WITH_RIVLIB)
MESSAGE(STATUS "Do NOT compile a scan IO for RXP")
ENDIF(WITH_RIVLIB)
## CUDA support, TODO depend on CUDA_FIND
OPTION(WITH_CUDA "Compile with CUDA support" OFF)
IF(WITH_CUDA)
MESSAGE(STATUS "Compiling WITH CUDA support")
FIND_PACKAGE(CUDA)
SET (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DWITH_CUDA")
ELSE(WITH_CUDA)
MESSAGE(STATUS "Compiling WITHOUT CUDA support")
ENDIF(WITH_CUDA)
## PMD
OPTION(WITH_PMD "Whether to build the PMD tools like grabVideoAnd3D calibrate etc. ON/OFF" OFF)
IF(WITH_PMD)
FIND_PACKAGE(OpenGL REQUIRED)
MESSAGE(STATUS "With Tools")
ELSE(WITH_PMD)
MESSAGE(STATUS "Without Tools")
ENDIF(WITH_PMD)
## FBR
OPTION(WITH_FBR "Whether to compile feature based registration. ON/OFF" OFF)
IF(WITH_FBR)
MESSAGE(STATUS "With FBR ")
ELSE(WITH_FBR)
MESSAGE(STATUS "Without FBR")
ENDIF(WITH_FBR)
## Special treatment for system specifics
IF(APPLE)
add_definitions(-Dfopen64=fopen)
ENDIF(APPLE)
## Multiple Cores
IF(APPLE)
SET(PROCESSOR_COUNT 2)
ELSE(APPLE)
INCLUDE(CountProcessors)
SET(NUMBER_OF_CPUS "${PROCESSOR_COUNT}" CACHE STRING "The number of processors to use (default: ${PROCESSOR_COUNT})" )
ENDIF(APPLE)
# OPEN
FIND_PACKAGE(OpenMP)
IF(OPENMP_FOUND)
OPTION(WITH_OPENMP "Whether to use parallel processing capabilities of OPENMP. ON/OFF" ON)
ENDIF(OPENMP_FOUND)
IF(OPENMP_FOUND AND WITH_OPENMP)
MESSAGE(STATUS "With OpenMP ")
SET (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DMAX_OPENMP_NUM_THREADS=${PROCESSOR_COUNT} -DOPENMP_NUM_THREADS=${NUMBER_OF_CPUS} ${OpenMP_CXX_FLAGS} -DOPENMP")
ELSE(OPENMP_FOUND AND WITH_OPENMP)
MESSAGE(STATUS "Without OpenMP")
SET (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DMAX_OPENMP_NUM_THREADS=1 -DOPENMP_NUM_THREADS=1")
ENDIF(OPENMP_FOUND AND WITH_OPENMP)
## TORO
OPTION(WITH_TORO "Whether to use TORO. ON/OFF" OFF)
IF(WITH_TORO)
IF(WIN32)
SET(Subversion_SVN_EXECUTABLE "svn.exe")
ENDIF(WIN32)
cmake_minimum_required (VERSION 2.8)
include(ExternalProject)
ExternalProject_Add(toro3d
SVN_REPOSITORY https://www.openslam.org/data/svn/toro/trunk
SOURCE_DIR "${CMAKE_SOURCE_DIR}/3rdparty/toro"
CONFIGURE_COMMAND ""
BUILD_COMMAND make
BUILD_IN_SOURCE 1
INSTALL_COMMAND cp ${CMAKE_SOURCE_DIR}/3rdparty/toro/toro3d ${CMAKE_SOURCE_DIR}/bin/
)
MESSAGE(STATUS "With TORO ")
ELSE(WITH_TORO)
MESSAGE(STATUS "Without TORO")
ENDIF(WITH_TORO)
## HOGMAN
OPTION(WITH_HOGMAN "Whether to use HOGMAN. ON/OFF" OFF)
IF(WITH_HOGMAN)
# dependant on libqt4-devi
find_package( Qt4 REQUIRED)
# CMake of earlier versions do not have external project capabilities
cmake_minimum_required (VERSION 2.8)
include(ExternalProject)
ExternalProject_Add(hogman
SVN_REPOSITORY https://svn.openslam.org/data/svn/hog-man/trunk
SOURCE_DIR "${CMAKE_SOURCE_DIR}/3rdparty/hogman"
CONFIGURE_COMMAND <SOURCE_DIR>/configure --prefix=<INSTALL_DIR>
BUILD_COMMAND LD_LIBRARY_PATH=${CMAKE_SOURCE_DIR}/3rdparty/hogman/lib make
BUILD_IN_SOURCE 1
INSTALL_COMMAND cp ${CMAKE_SOURCE_DIR}/3rdparty/hogman/bin/hogman3d ${CMAKE_SOURCE_DIR}/bin/ &&
cp ${CMAKE_SOURCE_DIR}/3rdparty/hogman/lib/libhogman_csparse.so ${CMAKE_SOURCE_DIR}/lib/ &&
cp ${CMAKE_SOURCE_DIR}/3rdparty/hogman/lib/libhogman_graph_optimizer_hogman.so ${CMAKE_SOURCE_DIR}/lib/ &&
cp ${CMAKE_SOURCE_DIR}/3rdparty/hogman/lib/libhogman_graph_optimizer.so ${CMAKE_SOURCE_DIR}/lib/ &&
cp ${CMAKE_SOURCE_DIR}/3rdparty/hogman/lib/libhogman_graph.so ${CMAKE_SOURCE_DIR}/lib/ &&
cp ${CMAKE_SOURCE_DIR}/3rdparty/hogman/lib/libhogman_graph_viewer.so ${CMAKE_SOURCE_DIR}/lib/ &&
cp ${CMAKE_SOURCE_DIR}/3rdparty/hogman/lib/libhogman_math.so ${CMAKE_SOURCE_DIR}/lib/ &&
cp ${CMAKE_SOURCE_DIR}/3rdparty/hogman/lib/libhogman_qglviewer.so ${CMAKE_SOURCE_DIR}/lib/ &&
cp ${CMAKE_SOURCE_DIR}/3rdparty/hogman/lib/libhogman_stuff.so ${CMAKE_SOURCE_DIR}/lib/
)
MESSAGE(STATUS "With HOGMAN: Currently hogman needs to be compiled manually, please make sure hogman3d is somewhere in your PATH")
ELSE(WITH_HOGMAN)
MESSAGE(STATUS "Without HOGMAN")
ENDIF(WITH_HOGMAN)
OPTION(EXPORT_SHARED_LIBS "Whether to build additional shared libraries for use in other projects. ON/OFF" OFF)
IF(EXPORT_SHARED_LIBS)
MESSAGE(STATUS "exporting additional libraries")
ELSE(EXPORT_SHARED_LIBS)
MESSAGE(STATUS "not exporting libraries")
ENDIF(EXPORT_SHARED_LIBS)
OPTION(WITH_METRICS "Whether to use metrics in slam6d. ON/OFF" OFF)
IF(WITH_METRICS)
MESSAGE(STATUS "With metrics in slam6d.")
SET (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DWITH_METRICS")
ELSE(WITH_METRICS)
MESSAGE(STATUS "Without metrics in slam6d.")
ENDIF(WITH_METRICS)
IF(WIN32)
SET(ADDITIONAL_CFLAGS "-O2" CACHE STRING"Additional flags given to the compiler ()" )
include_directories(${CMAKE_SOURCE_DIR}/3rdparty/windows/)
link_directories(${CMAKE_SOURCE_DIR}/3rdparty/windows)
link_directories(${CMAKE_SOURCE_DIR}/3rdparty/windows/x64)
add_library(XGetopt STATIC ${CMAKE_SOURCE_DIR}/3rdparty/windows/XGetopt.cpp)
SET(CMAKE_STATIC_LIBRARY_SUFFIX "32.lib")
ELSE(WIN32)
SET(ADDITIONAL_CFLAGS "-O3 -std=c++0x -msse3 -Wall -finline-functions -Wno-unused-but-set-variable -Wno-write-strings -Wno-char-subscripts -Wno-unused-result" CACHE STRING"Additional flags given to the compiler (-O3 -Wall -finline-functions -Wno-write-strings)" )
# Add include path for OpenGL without GL/-prefix
# to avoid the include incompatibility between MACOS
# and linux
FIND_PATH(OPENGL_INC gl.h /usr/include/GL)
include_directories(${OPENGL_INC})
ENDIF(WIN32)
# Add OpenGL includes for MACOS if needed
# The OSX OpenGL frameworks natively supports freeglut extensions
IF(APPLE)
include_directories(/System/Library/Frameworks/GLUT.framework/Headers)
include_directories(/System/Library/Frameworks/OpenGL.framework/Headers)
ENDIF(APPLE)
SET (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${ADDITIONAL_CFLAGS}")
# Hide CMake variables
SET (CMAKE_INSTALL_PREFIX "/usr/local" CACHE INTERNAL "" FORCE)
SET (CMAKE_BUILD_TYPE "" CACHE INTERNAL "" FORCE)
# Set output directories for libraries and executables
SET( CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_SOURCE_DIR}/lib )
SET( CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_SOURCE_DIR}/obj )
SET( CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_SOURCE_DIR}/bin )
# Set include and link dirs ...
include_directories(${CMAKE_SOURCE_DIR}/include)
include_directories(${CMAKE_SOURCE_DIR}/3rdparty/)
include_directories(${CMAKE_SOURCE_DIR}/3rdparty/glui)
include_directories(${CMAKE_SOURCE_DIR}/3rdparty/wxthings/include/)
include_directories(${CMAKE_SOURCE_DIR}/3rdparty/ann_1.1.1_modified/include)
include_directories(${CMAKE_SOURCE_DIR}/3rdparty/ann_1.1.1_modified/src)
link_directories(${CMAKE_SOURCE_DIR}/obj)
link_directories(${CMAKE_SOURCE_DIR}/lib)
add_subdirectory(3rdparty)
add_subdirectory(src/slam6d)
add_subdirectory(src/scanio)
add_subdirectory(src/scanserver)
add_subdirectory(src/veloslam)
add_subdirectory(src/show)
add_subdirectory(src/grid)
add_subdirectory(src/pmd)
add_subdirectory(src/shapes)
add_subdirectory(src/thermo)
IF(WITH_FBR)
add_subdirectory(src/slam6d/fbr)
ENDIF(WITH_FBR)
add_subdirectory(src/scanner)
add_subdirectory(src/model)
IF(EXPORT_SHARED_LIBS)
## Compiling a shared library containing all of the project
add_library(slam SHARED src/slam6d/icp6D.cc)
target_link_libraries(slam scanlib_s ANN_s sparse_s newmat_s)
ENDIF(EXPORT_SHARED_LIBS)
MESSAGE (STATUS "Build environment is set up!")
# hack to "circumvent" Debug and Release folders that are created under visual studio
# this is why the INSTALL target has to be used in visual studio
IF(MSVC)
INSTALL(DIRECTORY ${CMAKE_SOURCE_DIR}/bin/Release/ CONFIGURATIONS Release DESTINATION ${CMAKE_SOURCE_DIR}/windows FILES_MATCHING PATTERN "*.dll" PATTERN "*.exe")
IF( CMAKE_SIZEOF_VOID_P EQUAL 8 )
INSTALL(DIRECTORY ${CMAKE_SOURCE_DIR}/3rdparty/windows/x64/ CONFIGURATIONS Release DESTINATION ${CMAKE_SOURCE_DIR}/windows FILES_MATCHING PATTERN "*.dll" PATTERN "*.exe")
ELSE( CMAKE_SIZEOF_VOID_P EQUAL 8 )
INSTALL(DIRECTORY ${CMAKE_SOURCE_DIR}/3rdparty/windows/ CONFIGURATIONS Release DESTINATION ${CMAKE_SOURCE_DIR}/windows FILES_MATCHING PATTERN "*.dll" PATTERN "*.exe")
ENDIF(CMAKE_SIZEOF_VOID_P EQUAL 8 )
INSTALL(DIRECTORY ${CMAKE_SOURCE_DIR}/bin/Debug/ CONFIGURATIONS Debug DESTINATION ${CMAKE_SOURCE_DIR}/windows FILES_MATCHING PATTERN "*.dll" PATTERN "*.exe")
IF( CMAKE_SIZEOF_VOID_P EQUAL 8 )
INSTALL(DIRECTORY ${CMAKE_SOURCE_DIR}/3rdparty/windows/x64/ CONFIGURATIONS Debug DESTINATION ${CMAKE_SOURCE_DIR}/windows FILES_MATCHING PATTERN "*.dll" PATTERN "*.exe")
ELSE( CMAKE_SIZEOF_VOID_P EQUAL 8 )
INSTALL(DIRECTORY ${CMAKE_SOURCE_DIR}/3rdparty/windows/ CONFIGURATIONS Debug DESTINATION ${CMAKE_SOURCE_DIR}/windows FILES_MATCHING PATTERN "*.dll" PATTERN "*.exe")
ENDIF(CMAKE_SIZEOF_VOID_P EQUAL 8 )
ENDIF(MSVC)

Some files were not shown because too many files have changed in this diff Show More

Loading…
Cancel
Save